micro-ROS / micro_ros_arduino

micro-ROS library for Arduino
Apache License 2.0
453 stars 117 forks source link

Questions about the parameters that determine the number of topics and topic size for publishers and subscribers #1615

Open ChoiYouJung opened 11 months ago

ChoiYouJung commented 11 months ago

Issue template

Steps to reproduce the issue

(1) Code Behavior Description The difference between the first and second operation codes is that among the types of ROS messages transmitted from the SBC (Linux) to the MCU, one joint_state message (joint_state_2) has been changed from 1000ms to 30msec.

The second operation code had a data loss of up to 10 pieces, but the second operation code had an issue in which several ROS messages were lost out of the total received data.

The operating time of the code ranged from a minimum of 3 hours to a maximum of 10 hours.

[1] Action code first

[2] Action code second

For reference, the RQT graph is as follows. Screenshot from 2023-12-20 15-33-15

The micro_ros_node in the center is Teensy4.1 or i.MX-RT1060 MCU.

Question Q1. When the amount of ROS message data received or transmitted increases, as in the second operation code, are there any parameters that can be adjusted?

Q2. When I modified the following parameters in the colcon.meta parameter, I modified two of the parameters of the RMW Micro XRCE-DDS implementation. Is my understanding of the following parameters correct? If not, what parameters can be modified to enable the code to respond when the amount of data sent or received increases?

https://github.com/micro-ROS/rmw_microxrcedds

RMW_UXRCE_STREAM_HISTORY_INPUT
// Data storage buffer when ROS message is received (maximum number of data received) // Data transmission direction: SBC (linux) -> MCU (Teensy or i.MXRT1060)

RMW_UXRCE_STREAM_HISTORY_OUTPUT // Data storage buffer when sending a ROS message (maximum number of data transmitted) // Data transmission direction: SBC (linux) <- MCU (Teensy or i.MXRT1060)

(For reference, I changed RMW_UXRCE_STREAM_HISTORY_INPUT and RMW_UXRCE_STREAM_HISTORY_OUTPUT from the default value of 4 to 8.)

Q3. Additionally, I have a question about managing memory. Are the input buffer and output buffer at the following address the buffers that store the data when the ROS message is transmitted? And is it correct that the buffer is captured in the stack section of RAM memory?

https://micro.ros.org/docs/concepts/middleware/memo_prof/

Expected behavior

Actual behavior

[1] Action code first

[2] Action code second

Additional information

pablogs9 commented 11 months ago

Hello, your two scenarios are basically the same, which is the difference between [1] Action code first and [2] Action code second

[1] Action code first

Code that operates 16 publishers, 6 subscriptions, and 10 ROS Timers

Types of Publish ROS Topic and ROS Timer operation cycle odom(odometry)(30mesc), battery(battery)(500mec), UInt8MultiArray_1(UInt8MultiArray)(100mec), UInt8MultiArray_2(UInt8MultiArray)(50mec), UInt16MultiArray_2(UInt16MultiArray)(100msec), UInt16MultiArray_1(UInt16MultiArray)(500msec), joint_state_1(joint_state)(100msec), imu(sensor_imu)(30msec), version(string)(1000msec), test_message(int32)(1000msec)

Types of Subscription ROS Topics twist, bool_1(Bool), bool_2(Bool), ColorRGBA_1(ColorRGBA), ColorRGBA_2(ColorRGBA), joint_state_2(jointstate)

[2] Action code second

Code that operates 16 publishers, 6 subscriptions, and 10 ROS Timers

Types of Publish ROS Topic and ROS Timer operation cycle odom(odometry)(30mesc), battery(battery)(500mec), UInt8MultiArray_1(UInt8MultiArray)(100mec), UInt8MultiArray_2(UInt8MultiArray)(50mec), UInt16MultiArray_2(UInt16MultiArray)(100msec), UInt16MultiArray_1(UInt16MultiArray)(500msec), joint_state_1(joint_state)(100msec), imu(sensor_imu)(30msec), version(string)(1000msec), test_message(int32)(1000msec)

Types of Subscription ROS Topics twist, bool_1(Bool), bool_2(Bool), ColorRGBA_1(ColorRGBA), ColorRGBA_2(ColorRGBA), joint_state_2(jointstate)

Regarding your questions:

Q1. When the amount of ROS message data received or transmitted increases, as in the second operation code, are there any parameters that can be adjusted?

That's it, you can tune the Micro XRCE-DDS layer and the RMW layer to adjust the middleware operation, but more importantly, your micro-ROS application execution shall be correctly designed to handle your pubs and subs. Could you share your application code?

For example, I assume that you are using a serial port for communication micro-ROS with the Agent, assuming 115200 bauds, you will have an approx bandwidth of ~115 kbps or ~14 kB/s, have you analyzed the size and rates of your publications and subscriptions does not exceed this rate?

Q2. When I modified the following parameters in the colcon.meta parameter, I modified two of the parameters of the RMW Micro XRCE-DDS implementation. Is my understanding of the following parameters correct? If not, what parameters can be modified to enable the code to respond when the amount of data sent or received increases?

Those two parameters are involved in the buffering mechanism of the middleware, so increasing them will help to have a better performance. Remember that the stream histories sizes shall be power of 2.

Q3. Additionally, I have a question about managing memory. Are the input buffer and output buffer at the following address the buffers that store the data when the ROS message is transmitted?

Yes

And is it correct that the buffer is captured in the stack section of RAM memory?

By default all memory in micro-ROS client is statically allocated, so normally it exists in .BSS or .DATA sections.

Result: Data loss occurs in some ROS messages.

BTW, are your publishers and subscribers reliable or best effort?

ChoiYouJung commented 10 months ago

Sorry for not being able to share the entire application code.

If we simplify the application code and share the structure, it is as follows.

#include <micro_ros_arduino.h>

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

#include <std_msgs/msg/int32.h>
#include <nav_msgs/msg/odometry.h>
#include <sensor_msgs/msg/battery_state.h>
#include <std_msgs/msg/string.h>
#include <sensor_msgs/msg/joint_state.h>
#include <std_msgs/msg/multi_array_layout.h>
#include <std_msgs/msg/multi_array_dimension.h>
#include <std_msgs/msg/u_int16_multi_array.h>
#include <std_msgs/msg/u_int8_multi_array.h>
#include <sensor_msgs/msg/imu.h>
#include<geometry_msgs/msg/twist.h>
#include <std_msgs/msg/bool.h>
#include <std_msgs/msg/color_rgba.h>

// publisher
rcl_publisher_t test_pub1;
rcl_publisher_t odom_pub;
rcl_publisher_t battery_pub;
rcl_publisher_t joint_state_pub;
rcl_publisher_t cliff_pub;
rcl_publisher_t state1_test_pub;
rcl_publisher_t state2_test_pub;
rcl_publisher_t ir_pub;
rcl_publisher_t test_pub2;
rcl_publisher_t imu_pub;

rcl_publisher_t cmd_vel_echo_pub;
rcl_publisher_t test_cmd1_echo_pub;
rcl_publisher_t test_cmd2_echo_pub;
rcl_publisher_t test_cmd3_echo_pub;
rcl_publisher_t test_cmd4_echo_pub;
rcl_publisher_t cmd_joint_echo_pub;

// ROS message - publisher message
std_msgs__msg__Int32 test_msg1;
nav_msgs__msg__Odometry odom_msg;
sensor_msgs__msg__BatteryState battery_state_msg;
sensor_msgs__msg__JointState joint_state_msg;
std_msgs__msg__MultiArrayDimension cliff_dim[1];
std_msgs__msg__UInt16MultiArray cliff_msg;
std_msgs__msg__MultiArrayDimension state1_dim[1];
std_msgs__msg__UInt16MultiArray state1_msg;
std_msgs__msg__MultiArrayDimension state2_dim[1];
std_msgs__msg__UInt8MultiArray state2_msg;
std_msgs__msg__MultiArrayDimension ir_dim[1];
std_msgs__msg__UInt8MultiArray ir_msg;
std_msgs__msg__String test_msg2;
sensor_msgs__msg__Imu imu_msg;

geometry_msgs__msg__Twist cmd_vel_echo_msg;
std_msgs__msg__Bool test_cmd1_echo_msg;
std_msgs__msg__Bool test_cmd2_echo_msg;
std_msgs__msg__ColorRGBA test_cmd3_echo_msg;
std_msgs__msg__ColorRGBA test_cmd4_echo_msg;
sensor_msgs__msg__JointState cmd_joint_echo_msg;

// subscription
rcl_subscription_t cmd_vel_sub;
rcl_subscription_t test_cmd1_sub;
rcl_subscription_t test_cmd2_sub;
rcl_subscription_t test_cmd3_sub;
rcl_subscription_t test_cmd4_sub;
rcl_subscription_t cmd_joint_sub;

// ROS message - subscription message
geometry_msgs__msg__Twist cmd_vel_msg;
std_msgs__msg__Bool test_cmd1_msg;
std_msgs__msg__Bool test_cmd2_msg;
std_msgs__msg__ColorRGBA test_cmd3_msg;
std_msgs__msg__ColorRGBA test_cmd4_msg;
sensor_msgs__msg__JointState cmd_joint_msg;

rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;

// timer
rcl_timer_t test1_timer; 
rcl_timer_t odom_pub_timer;
rcl_timer_t battery_pub_timer;
rcl_timer_t joint_state_pub_timer;
rcl_timer_t cliff_pub_timer;
rcl_timer_t state1_pub_timer;
rcl_timer_t state2_pub_timer;
rcl_timer_t ir_pub_timer;
rcl_timer_t test2_timer;
rcl_timer_t imu_pub_timer;

void test_pub1_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&test_pub1, &msg, NULL);
    }
}

void odom_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&odom_pub, &odom_msg, NULL);
    }
}

void battery_state_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&battery_pub, &battery_state_msg, NULL);
    }
}

void joint_state_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&joint_state_pub, &joint_state_msg, NULL);
    }
}

void cliff_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&cliff_pub, &cliff_msg, NULL);
    }
}

void state1_test_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&state1_test_pub, &state1_msg, NULL);
    }
}

void state2_test_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&state2_test_pub, &state2_msg, NULL);
    }
}

void ir_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&ir_pub, &ir_msg, NULL);
    }
}

void test2_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&test_pub2, &test_msg2, NULL);
    }
}

void imu_timer_cb(rcl_timer_t * timer, int64_t last_call_time)
{
    if (timer != NULL) {
        rcl_publish(&imu_pub, &imu_msg, NULL);
    }
}

void cmd_vel_sub_cb(const void * msgin)
{
    rcl_publish(&cmd_vel_echo_pub, &cmd_vel_echo_msg, NULL);
}

void test_cmd1_sub_cb(const void * msgin)
{
    rcl_publish(&test_cmd1_echo_pub, &test_cmd1_echo_msg, NULL);
}

void test_cmd2_sub_cb(const void * msgin)
{
    rcl_publish(&test_cmd2_echo_pub, &test_cmd2_echo_msg, NULL);
}

void test_cmd3_sub_cb(const void * msgin)
{
    rcl_publish(&test_cmd3_echo_pub, &test_cmd3_echo_msg, NULL);
}

void test_cmd4_sub_cb(const void * msgin)
{
    rcl_publish(&test_cmd4_echo_pub, &test_cmd4_echo_msg, NULL);
}

void cmd_joint_sub_cb(const void * msgin)
{
    rcl_publish(&cmd_joint_echo_pub, &cmd_joint_echo_msg, NULL);
}

bool create_entities(void)
{
    allocator = rcl_get_default_allocator();

    support_err = rclc_support_init(&support, 0, NULL, &allocator);

    rclc_node_init_default(&node, "micro_ros_node", "", &support);

    rclc_publisher_init_default(
        &test_pub1,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
        "micro_ros_arduino_node_publisher");

    rclc_publisher_init_default(
        &odom_pub,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(nav_msgs, msg, Odometry),
        "uros_odom");

    rclc_publisher_init_default(
        &battery_pub,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, BatteryState),
        "uros_battery_state");

    rclc_publisher_init_default(
        &joint_state_pub,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, JointState),
        "uros_joint_state");

    rclc_publisher_init_default(
            &cliff_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt16MultiArray),
            "uros_cliff");

    rclc_publisher_init_default(
            &state1_test_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt16MultiArray),
            "uros_state1_test");

    rclc_publisher_init_default(
            &ir_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt8MultiArray),
            "uros_ir");

    rclc_publisher_init_default(
            &state2_test_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, UInt8MultiArray),
            "uros_state2_test");

    rclc_publisher_init_default(
        &test_pub2,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),
        "uros_test2");

    rclc_publisher_init_default(
            &imu_publisher,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, Imu),
            "uros_imu");

    rclc_publisher_init_default(
            &cmd_vel_echo_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Twist),
            "uros_echo_cmd_vel");

    rclc_publisher_init_default(
          &cmd_docking_mode_echo_pub,
          &node,
          ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool),
          "uros_echo_test_cmd1");

    rclc_publisher_init_default(
            &cmd_depth_camera_echo_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool),
            "uros_echo_test_cmd2");

    rclc_publisher_init_default(
        &led_earL_echo_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, ColorRGBA),
            "uros_echo_test_cmd3");

    rclc_publisher_init_default(
        &led_earR_echo_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, ColorRGBA),
            "uros_echo_test_cmd4");

    rclc_publisher_init_default(
            &cmd_joint_echo_pub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, JointState),
            "uros_echo_cmd_joint");

    rclc_subscription_init_default(
            &cmd_vel_sub,
            &node,
            ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Twist),
            "uros_cmd_vel");

    rclc_subscription_init_default(
        &test_cmd1_sub,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool),
        "uros_test_cmd1");

    rclc_subscription_init_default(
        &test_cmd2_sub,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool),
        "uros_test_cmd2");

    rclc_subscription_init_default(
        &test_cmd3_sub,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, ColorRGBA),
        "uros_test_cmd3");

    rclc_subscription_init_default(
        &test_cmd4_sub,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, ColorRGBA),
        "uros_test_cmd4");

    rclc_subscription_init_default(
        &cmd_joint_sub,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, JointState),
        "uros_cmd_joint");

    const unsigned int timer_timeout1 = 1000;
    rclc_timer_init_default(
        &test1_timer,
            &support,
            RCL_MS_TO_NS(timer_timeout1),
            test_pub1_timer_cb);

    const unsigned int odom_timer_timeout = 33;
    rclc_timer_init_default(
        &odom_pub_timer,
        &support,
        RCL_MS_TO_NS(odom_timer_timeout),
        odom_timer_cb);

    const unsigned int battery_timer_timeout = 500;
    rclc_timer_init_default(
        &battery_pub_timer,
        &support,
        RCL_MS_TO_NS(battery_timer_timeout),
        battery_state_timer_cb);

    const unsigned int joint_state_timer_timeout = 100;
    create_err10 = rclc_timer_init_default(
        &joint_state_pub_timer,
        &support,
        RCL_MS_TO_NS(joint_state_timer_timeout),
        joint_state_timer_cb);

    const unsigned int cliff_timer_timeout = 100;
    create_err11 = rclc_timer_init_default(
        &cliff_pub_timer,
        &support,
        RCL_MS_TO_NS(cliff_timer_timeout),
        cliff_timer_cb);

    const unsigned int state1_test_timer_timeout = 500;
    rclc_timer_init_default(
        &state1_pub_timer,
        &support,
        RCL_MS_TO_NS(state1_test_timer_timeout),
        state1_test_timer_cb);

    const unsigned int state2_test_timer_timeout = 100;
    rclc_timer_init_default(
        &state2_test_pub,
        &support,
        RCL_MS_TO_NS(state2_test_timer_timeout),
        state2_test_timer_cb);

    const unsigned int ir_timer_timeout = 50;
    rclc_timer_init_default(
        &ir_pub_timer,
        &support,
        RCL_MS_TO_NS(ir_timer_timeout),
        ir_timer_cb);

    const unsigned int test2_timer_timeout = 1000;
    rclc_timer_init_default(
        &test2_timer,
        &support,
        RCL_MS_TO_NS(test2_timer_timeout),
        test2_timer_cb);

    const unsigned int imu_timer_timeout = 33; 
    rclc_timer_init_default(
        &imu_pub_timer,
        &support,
        RCL_MS_TO_NS(imu_timer_timeout),
        imu_timer_cb);

    rclc_executor_init(&executor, &support.context, 16, &allocator);

    rclc_executor_add_timer(&executor, &test1_timer);
    rclc_executor_add_timer(&executor, &odom_pub_timer);
    rclc_executor_add_timer(&executor, &battery_pub_timer);
    rclc_executor_add_timer(&executor, &joint_state_pub_timer);
    rclc_executor_add_timer(&executor, &cliff_pub_timer);
    rclc_executor_add_timer(&executor, &state1_pub_timer);
    rclc_executor_add_timer(&executor, &state2_pub_timer);
    rclc_executor_add_timer(&executor, &ir_pub_timer);
    rclc_executor_add_timer(&executor, &test2_timer);
    rclc_executor_add_timer(&executor, &imu_pub_timer);

    rclc_executor_add_subscription(&executor, &cmd_vel_sub, &cmd_vel_msg, &cmd_vel_sub_cb, ON_NEW_DATA);
    rclc_executor_add_subscription(&executor, &test_cmd1_sub, &test_cmd1, &test_cmd1_sub_cb, ON_NEW_DATA);
    rclc_executor_add_subscription(&executor, &test_cmd2_sub, &test_cmd2, &test_cmd2_sub_cb, ON_NEW_DATA);
    rclc_executor_add_subscription(&executor, &test_cmd3_sub, &test_cmd3, &test_cmd3_sub_cb, ON_NEW_DATA);
    rclc_executor_add_subscription(&executor, &test_cmd4_sub, &test_cmd4, &test_cmd4_sub_cb, ON_NEW_DATA);
    rclc_executor_add_subscription(&executor, &cmd_joint_sub, &cmd_joint_msg, &cmd_joint_sub_cb, ON_NEW_DATA);

}

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

    rcl_publisher_fini(&test_pub1, &node);
    rcl_publisher_fini(&odom_pub, &node);
    rcl_publisher_fini(&battery_pub, &node);
    rcl_publisher_fini(&joint_state_pub, &node);
    rcl_publisher_fini(&cliff_pub, &node);
    rcl_publisher_fini(&state1_test_pub, &node);
    rcl_publisher_fini(&state2_test_pub, &node);
    rcl_publisher_fini(&ir_pub, &node);
    rcl_publisher_fini(&test_pub2, &node);
    rcl_publisher_fini(&imu_pub, &node);

    rcl_publisher_fini(&cmd_vel_echo_pub, &node);
    rcl_publisher_fini(&test_cmd1_echo_pub, &node);
    rcl_publisher_fini(&test_pub2, &node);
    rcl_publisher_fini(&test_cmd3_echo_pub, &node);
    rcl_publisher_fini(&test_cmd4_echo_pub, &node);
    rcl_publisher_fini(&cmd_joint_echo_pub, &node);

    rcl_subscription_fini(&cmd_vel_sub, &node);
    rcl_subscription_fini(&test_cmd1_sub, &node);
    rcl_subscription_fini(&test_cmd2_sub, &node);
    rcl_subscription_fini(&test_cmd3_sub, &node);
    rcl_subscription_fini(&test_cmd4_sub, &node);
    rcl_subscription_fini(&cmd_joint_sub, &node);

    rcl_timer_fini(&test1_timer);
    rcl_timer_fini(&odom_pub_timer);
    rcl_timer_fini(&battery_pub_timer);
    rcl_timer_fini(&joint_state_pub_timer); 
    rcl_timer_fini(&cliff_pub_timer);
    rcl_timer_fini(&state1_pub_timer);
    rcl_timer_fini(&state2_pub_timer);
    rcl_timer_fini(&ir_pub_timer);
    rcl_timer_fini(&test2_timer);
    rcl_timer_fini(&imu_pub_timer);

    rcl_node_fini(&node);
    rclc_executor_fini(&executor);
    rclc_support_fini(&support);
}

void setup(){
    set_microros_transports();

    // Initializa ROS message
    Init_ROS_message();

    mros_states = WAITING_AGENT;
}

void loop(){

    switch(mros_states)
    {
        case WAITING_AGENT:
            EXECUTE_EVERY_N_MS(10, mros_states = (RMW_RET_OK == rmw_uros_ping_agent(10,1)) ? AGENT_AVAILABLE : WAITING_AGENT;);
            break;
        case AGENT_AVAILABLE:
            mros_states = (true == create_entities()) ? AGENT_CONNECTED : WAITING_AGENT;
            if (mros_states == WAITING_AGENT) {
                destroy_entities();
            }
            break;
        case AGENT_CONNECTED:
            EXECUTE_EVERY_N_MS(100, mros_states = (RMW_RET_OK == rmw_uros_ping_agent(5, 2)) ? AGENT_CONNECTED : AGENT_DISCONNECTED;);
            if (mros_states == AGENT_CONNECTED){
                rclc_executor_spin_some(&executor, RCL_MS_TO_NS(10));
            }
            break;
        case AGENT_DISCONNECTED:
            destroy_entities();
            mros_states = WAITING_AGENT;
            break;
        default:
            break;
    }

}

The answers to the following questions are as follows.

Question: BTW, are your publishers and subscribers reliable or best effort?

Answer: I know that it is set to reliable if you use the rclc_publisher_init_default or rclc_subscription_init_default function. Therefore, I set the publisher and subscriber to reliable,