micro-ROS / micro_ros_platformio

micro-ROS library for Platform.IO
Apache License 2.0
205 stars 77 forks source link

number of timers available #100

Closed patrickwasp closed 1 year ago

patrickwasp commented 1 year ago

Issue template

Steps to reproduce the issue

#include <Arduino.h>
#include <micro_ros_platformio.h>

#define RC_CHECK(fn)             \
  {                              \
    rcl_ret_t temp_rc = fn;      \
    if ((temp_rc != RCL_RET_OK)) \
    {                            \
      rcError();                 \
    }                            \
  }

#define EXECUTE_EVERY_N_MS(MS, X)      \
  do                                   \
  {                                    \
    static volatile int64_t init = -1; \
    if (init == -1)                    \
    {                                  \
      init = uxr_millis();             \
    }                                  \
    if (uxr_millis() - init > MS)      \
    {                                  \
      X;                               \
      init = uxr_millis();             \
    }                                  \
  } while (0)

#include <stdio.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <rmw_microros/rmw_microros.h>

#include <std_msgs/msg/int32.h>

rclc_support_t g_support;
rcl_node_t g_node;
rclc_executor_t g_executor;
static rcl_allocator_t g_allocator;
rcl_init_options_t g_init_options;

rcl_timer_t g_update_first_timer;
rcl_timer_t g_update_second_timer;
rcl_timer_t g_update_third_timer;
rcl_timer_t g_first_publisher_timer;
rcl_timer_t g_second_publisher_timer;
rcl_timer_t g_third_publisher_timer;

rcl_publisher_t g_first_publisher;
rcl_publisher_t g_second_publisher;
rcl_publisher_t g_third_publisher;

std_msgs__msg__Int32 g_first_msg;
std_msgs__msg__Int32 g_second_msg;
std_msgs__msg__Int32 g_third_msg;

float g_first_value;
float g_second_value;
float g_third_value;

enum class AgentStates
{
  kWaiting,
  kAvailable,
  kConnected,
  kDisconnected
};
enum AgentStates g_agent_state;

void rcError()
{
}

void publishFirstTimerCallback(rcl_timer_t *timer, int64_t last_call_time)
{
  (void)last_call_time;
  if (timer != NULL)
  {
    g_first_msg.data = g_first_value;
    RC_CHECK(rcl_publish(&g_first_publisher, &g_first_msg, NULL));
  }
}

void publishSecondTimerCallback(rcl_timer_t *timer, int64_t last_call_time)
{
  (void)last_call_time;
  if (timer != NULL)
  {
    g_second_msg.data = g_second_value;
    RC_CHECK(rcl_publish(&g_second_publisher, &g_second_msg, NULL));
  }
}

void publishThirdTimerCallback(rcl_timer_t *timer, int64_t last_call_time)
{
  (void)last_call_time;
  if (timer != NULL)
  {
    g_third_msg.data = g_third_value;
    RC_CHECK(rcl_publish(&g_third_publisher, &g_third_msg, NULL));
  }
}

void updateFirstValue()
{
  g_first_value = millis();
}

void updateFirstValueTimerCallback(rcl_timer_t *timer, int64_t last_call_time)
{
  (void)last_call_time;
  if (timer != NULL)
  {
    updateFirstValue();
  }
}

void updateSecondValue()
{
  usleep(100 * 1000);
  g_second_value += 1;
}

void updateSecondValueTimerCallback(rcl_timer_t *timer, int64_t last_call_time)
{
  (void)last_call_time;
  if (timer != NULL)
  {
    updateSecondValue();
  }
}

void updateThirdValue()
{
  usleep(1000 * 1000);
  g_third_value += 10;
}

void updateThirdValueTimerCallback(rcl_timer_t *timer, int64_t last_call_time)
{
  (void)last_call_time;
  if (timer != NULL)
  {
    updateThirdValue();
  }
}

bool createEntities()
{
  g_allocator = rcl_get_default_allocator();

  g_init_options = rcl_get_zero_initialized_init_options();
  RC_CHECK(rcl_init_options_init(&g_init_options, g_allocator));
  RC_CHECK(rcl_init_options_set_domain_id(&g_init_options, 8));
  rclc_support_init_with_options(&g_support, 0, NULL, &g_init_options, &g_allocator);

  RC_CHECK(rclc_node_init_default(&g_node, "node_name", "namespace", &g_support));

  // create publishers
  RC_CHECK(rclc_publisher_init_default(
      &g_first_publisher,
      &g_node,
      ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
      "first_publisher"));

  RC_CHECK(rclc_publisher_init_default(
      &g_second_publisher,
      &g_node,
      ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
      "second_publisher"));

  RC_CHECK(rclc_publisher_init_default(
      &g_third_publisher,
      &g_node,
      ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
      "third_publisher"));

  // create publish timers
  RC_CHECK(rclc_timer_init_default(
      &g_first_publisher_timer,
      &g_support,
      RCL_MS_TO_NS(100),
      publishFirstTimerCallback));

  RC_CHECK(rclc_timer_init_default(
      &g_second_publisher_timer,
      &g_support,
      RCL_MS_TO_NS(1000),
      publishSecondTimerCallback));

  RC_CHECK(rclc_timer_init_default(
      &g_third_publisher_timer,
      &g_support,
      RCL_MS_TO_NS(5000),
      publishThirdTimerCallback));

  // create update timers
  RC_CHECK(rclc_timer_init_default(
      &g_update_first_timer,
      &g_support,
      RCL_MS_TO_NS(10),
      updateFirstValueTimerCallback));

  RC_CHECK(rclc_timer_init_default(
      &g_update_second_timer,
      &g_support,
      RCL_MS_TO_NS(500),
      updateSecondValueTimerCallback));

  RC_CHECK(rclc_timer_init_default(
      &g_update_third_timer,
      &g_support,
      RCL_MS_TO_NS(5000),
      updateThirdValueTimerCallback));

  // create executor
  g_executor = rclc_executor_get_zero_initialized_executor();
  RC_CHECK(rclc_executor_init(&g_executor, &g_support.context, 6, &g_allocator));
  RC_CHECK(rclc_executor_add_timer(&g_executor, &g_first_publisher_timer));
  RC_CHECK(rclc_executor_add_timer(&g_executor, &g_second_publisher_timer));
  RC_CHECK(rclc_executor_add_timer(&g_executor, &g_third_publisher_timer));
  RC_CHECK(rclc_executor_add_timer(&g_executor, &g_update_first_timer));
  RC_CHECK(rclc_executor_add_timer(&g_executor, &g_update_second_timer));
  RC_CHECK(rclc_executor_add_timer(&g_executor, &g_update_third_timer));

  return true;
}

void destroyEntities()
{
  rmw_context_t *rmw_context = rcl_context_get_rmw_context(&g_support.context);
  (void)rmw_uros_set_context_entity_destroy_session_timeout(rmw_context, 0);

  RC_CHECK(rcl_publisher_fini(&g_first_publisher, &g_node));
  RC_CHECK(rcl_publisher_fini(&g_second_publisher, &g_node));
  RC_CHECK(rcl_publisher_fini(&g_third_publisher, &g_node));
  RC_CHECK(rcl_timer_fini(&g_first_publisher_timer));
  RC_CHECK(rcl_timer_fini(&g_second_publisher_timer));
  RC_CHECK(rcl_timer_fini(&g_third_publisher_timer));
  RC_CHECK(rcl_timer_fini(&g_update_first_timer));
  RC_CHECK(rcl_timer_fini(&g_update_second_timer));
  RC_CHECK(rcl_timer_fini(&g_update_third_timer));
  rclc_executor_fini(&g_executor);
  RC_CHECK(rcl_node_fini(&g_node));
  rclc_support_fini(&g_support);
}

void setup()
{
  g_first_value = 0;
  g_second_value = 0;
  g_third_value = 0;

  Serial.begin(115200);
  set_microros_serial_transports(Serial);
  delay(2000);

  g_agent_state = AgentStates::kWaiting;
}

void loop()
{
  switch (g_agent_state)
  {
  case AgentStates::kWaiting:
    EXECUTE_EVERY_N_MS(500, g_agent_state = (RMW_RET_OK == rmw_uros_ping_agent(100, 1)) ? AgentStates::kAvailable : AgentStates::kWaiting;);
    break;
  case AgentStates::kAvailable:
    g_agent_state = (true == createEntities()) ? AgentStates::kConnected : AgentStates::kWaiting;
    if (g_agent_state == AgentStates::kWaiting)
    {
      destroyEntities();
    };
    break;
  case AgentStates::kConnected:
    EXECUTE_EVERY_N_MS(200, g_agent_state = (RMW_RET_OK == rmw_uros_ping_agent(100, 1)) ? AgentStates::kConnected : AgentStates::kDisconnected;);
    if (g_agent_state == AgentStates::kConnected)
    {
      rclc_executor_spin_some(&g_executor, RCL_MS_TO_NS(100));
    }
    break;
  case AgentStates::kDisconnected:
    destroyEntities();
    g_agent_state = AgentStates::kWaiting;
    break;
  default:
    break;
  }
}

Expected behavior

second and third values should be updated. They should also be published at different frequencies.

Actual behavior

only the first value is published with the correct value.

rqt

Additional information

If I change the order of the publishers and timers in code then different publishers start working. Is there a built-in limit in rclc_executor_get_zero_initialized_executor(), rcl_get_default_allocator(), or rcl_get_zero_initialized_init_options() that set the number of timers that can be run?

When it comes to timers, does the timeout_ns indicate how often it will run or how long it will wait for the callback to return? If it is just a timeout, how do you set the callback frequency? Are timer callbacks run asynchronously or are they blocking for the rest of the code?

the meta I'm using is

{
    "names": {
        "rmw_microxrcedds": {
            "cmake-args": [
                "-DRMW_UXRCE_MAX_NODES=1",
                "-DRMW_UXRCE_MAX_PUBLISHERS=10",
                "-DRMW_UXRCE_MAX_SUBSCRIPTIONS=5",
                "-DRMW_UXRCE_MAX_SERVICES=1",
                "-DRMW_UXRCE_MAX_CLIENTS=1",
                "-DRMW_UXRCE_MAX_HISTORY=4",
                "-DRMW_UXRCE_TRANSPORT=custom"
            ]
        }
    }
}
Acuadros95 commented 1 year ago

The maximum number of timers is configured with the colcon parameter RMW_UXRCE_MAX_GUARD_CONDITION which defaults to 4 (detail)

When it comes to timers, does the timeout_ns indicate how often it will run or how long it will wait for the callback to return? If it is just a timeout, how do you set the callback frequency?

The timeout value defines the callback frequency, its not related to the callback execution time.

Are timer callbacks run asynchronously or are they blocking for the rest of the code?

The callbacks run on the same thread that the executor spin method is called, so they the callbacks will block until they return.

You can find more info about timers and the executor here: Executor and timers.

patrickwasp commented 1 year ago

Thanks for the link to vulcanexus, looks like a great resource.

After adding "-DRMW_UXRCE_MAX_GUARD_CONDITION=20" to the meta file I still don't see the values of the second or third publisher changing. Is there a practical limit to the guard condition value?

Why does rqt show ~48Hz for every publisher, when I have the timeouts set to different values?

this is my platformio.ini

[env:esp32-poe-iso]
platform = espressif32
board = esp32-poe-iso
framework = arduino
monitor_speed = 115200
board_microros_transport = serial
board_microros_distro = humble
board_microros_user_meta = config/esp32.meta
lib_deps = 
    https://github.com/micro-ROS/micro_ros_platformio#1.0.0
Acuadros95 commented 1 year ago

After adding "-DRMW_UXRCE_MAX_GUARD_CONDITION=20" to the meta file I still don't see the values of the second or third publisher changing.

Did your rebuild the library?

Also, some thoughts:

patrickwasp commented 1 year ago

I changed the lib_deps to the latest commit

https://github.com/micro-ROS/micro_ros_platformio#8103c3c2bbf52bc2cae5ff95fc61f06dd5792b62

now everything seems to work correctly, including the correct frequency in Hz. Thanks! Is 20 a good number, or is it too high?

rqt

Acuadros95 commented 1 year ago

Glad to hear!

Is 20 a good number, or is it too high?

Only a RMW_UXRCE_MAX_GUARD_CONDITION per timer is needed, but you will just waste a bit of memory.

Closing!