Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Max number of subscribers timers and publishers #147

Open
dudu8009 opened this issue Aug 21, 2024 · 2 comments
Open

Max number of subscribers timers and publishers #147

dudu8009 opened this issue Aug 21, 2024 · 2 comments

Comments

@dudu8009
Copy link

Issue template

I'm trying to run 5 timers from one esp32 dev board and so far it fails to run, i would like to know how can i set the max number of timers higher, also i haven't understood what is the proper flow to init a node with subscribers, publishers and timers and how to properly clean up.
that is, what is the correct order of init for the different entities and shutdown?
i haven't found a demo of this, and currently the micro_ros_platformio repo doesn't have a lot of demos

  • Hardware description: upboard, ubuntu 22.04
  • RTOS: esp32 dev board
  • Installation type: platformio
  • Version or commit hash: humble

Code example

#ifdef DEBUG
HardwareSerial Debug(2);
#define DEBUG_TX_PIN 19
#define DEBUG_RX_PIN 18
#define DebugPrint Debug.print
#define DebugPrintln Debug.println
#else
#define DebugPrint
#define DebugPrintln
#endif

//========================== ROS variables==================================================

char buffer[150];
#define RCSOFTCHECK(fn)                                                                             \
    {                                                                                               \
        rcl_ret_t temp_rc = fn;                                                                     \
        if ((temp_rc != RCL_RET_OK))                                                                \
        {                                                                                           \
            sprintf(buffer, "\nFailed status on line %d: %d. Continuing.", __LINE__, (int)temp_rc); \
            DebugPrintln(buffer);                                                                   \
        }                                                                                           \
    }
#define RCCHECK(fn)                                                                                \
    {                                                                                              \
        rcl_ret_t temp_rc = fn;                                                                    \
        if ((temp_rc != RCL_RET_OK))                                                               \
        {                                                                                          \
            sprintf(buffer, "\nFailed status on line %d: %d. Stopping!.", __LINE__, (int)temp_rc); \
            DebugPrintln(buffer);                                                                  \
            return false;                                                                          \
        }                                                                                          \
    }
rclc_support_t support;
rclc_executor_t executor;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t motor_data_timer;

// Set client QoS
const rmw_qos_profile_t *qos_profile_sensor_data = &rmw_qos_profile_sensor_data;

//==========================Code=====================================================
void cleanup_ros_entities()
{
    DebugPrintln("Cleaning up ROS entities...");
    rmw_context_t *rmw_context = rcl_context_get_rmw_context(&support.context);
    (void)rmw_uros_set_context_entity_destroy_session_timeout(rmw_context, 0);

    RCSOFTCHECK(rcl_publisher_fini(&motor_data_pub, &node));
    
    RCSOFTCHECK(rcl_timer_fini(&motor_data_timer));
    
    RCSOFTCHECK(rcl_subscription_fini(&mode_sub, &node));
    
    RCSOFTCHECK(rclc_executor_fini(&executor));
    RCSOFTCHECK(rcl_node_fini(&node));
    RCSOFTCHECK(rclc_support_fini(&support));
    delay(1000);
}

bool setup_node_and_entities()
{
    set_microros_serial_transports(Serial);
    delay(1000);
    rmw_uros_sync_session(100);
    allocator = rcl_get_default_allocator();
    executor = rclc_executor_get_zero_initialized_executor();
    RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
    RCCHECK(rclc_node_init_default(&node, "esp32_node", "", &support));
    
    RCCHECK(rclc_publisher_init(&motor_data_pub, &node, Motor_Data_type_support, "motor_data", qos_profile_sensor_data));
    
    RCCHECK(rclc_subscription_init_default(&mode_sub, &node, Mode_type_support, "mode"));
    
    RCCHECK(rclc_timer_init_default(&motor_data_timer, &support, RCL_MS_TO_NS(1000), motor_data_callback));

    RCCHECK(rclc_executor_init(&executor, &support.context, 11, &allocator)); //what should be the number for the number of handles?
    
    RCCHECK(rclc_executor_add_timer(&executor, &motor_data_timer));
    
    RCCHECK(rclc_executor_add_subscription(&executor, &mode_sub, &mode_msg, &mode_callback, ON_NEW_DATA));

    return true;
}

@hippo5329
Copy link
Contributor

hippo5329 commented Aug 22, 2024

You may follow my wiki. https://github.com/hippo5329/micro_ros_arduino_examples_platformio/wiki

The count in executer init is the total number of timers and subscribers.

In most cases, only one timer is enough. Eg, one 50Hz control loop timer can be used to derive the other slower timings.

The allocation of publishers, subscribers and services is assigned by the colcon meta. You may find an example in the esp32 env.

@hippo5329
Copy link
Contributor

hippo5329 commented Aug 22, 2024

Example of derived timer in hippo5329/linorobot2_hardware

In 50Hz control timer,

#define RANGE_TIMER 100 // 10Hz

EXECUTE_EVERY_N_MS(RANGE_TIMER, {
range_msg = getRange();
range_msg.header.stamp.sec = time_stamp.tv_sec;
range_msg.header.stamp.nanosec = time_stamp.tv_nsec;
RCSOFTCHECK(rcl_publish(&range_publisher, &range_msg, NULL)) });

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants