micro-ROS / micro_ros_setup

Support macros for building micro-ROS-based firmware.
Apache License 2.0
336 stars 128 forks source link

Unable to enter the callback function when publisher's frequency increases or the receiver's data volume becomes larger and the trigger becomes invalid. #660

Open Junming-Liang opened 10 months ago

Junming-Liang commented 10 months ago

Issue template

Steps to reproduce the issue

  1. Add multiple subscribers and publishers in the system.
  2. Use high frequency msg
  3. Too long time in callbcak

Expected behavior

All subscribers should be able to enter their callback functions when there are publishers in the system.

Actual behavior

When using only subscribers, everything works fine. However, when adding publishers to the system, some subscribers cannot enter their callback functions. (This problem also occurs when I don't set up a publisher and receive topic messages at a high frequency)The following solutions have been attempted but did not fully resolve the issue:

  1. Reduce the size of publishers and messages. With this approach, some improvement was observed, but still, not all messages could be received. Of the three subscribers set up, only one or two would be able to enter their callback functions.
  2. Change the publisher to "best effort" mode. However, when the publisher is adjusted to "best effort" mode, the topic cannot be received in ROS.
  3. Use Trigger. When Trigger is set to accept all messages or to enter the callback only when a specific message is received, none of the subscriber's callback functions can be entered.

Additional information

This is my source code app.c:

#include <rcl/error_handling.h>
#include <rcl/rcl.h>
#include <rclc/executor.h>
#include <rclc/rclc.h>
// #include
// </home/liangjunming/program/mcu_ws/firmware/mcu_ws/install/std_msgs/include/std_msgs/msg/detail/header__struct.h>
#include "devastator_control_msgs/msg/vehicle_control_command.h"
#include "devastator_control_msgs/msg/vehicle_control_command_light.h"
#include "devastator_control_msgs/msg/vehicle_report_common.h"
#include "devastator_control_msgs/msg/vehicle_report_common_light.h"
#include "devastator_localization_msgs/msg/localization_estimate.h"
#include "devastator_localization_msgs/msg/localization_estimate_light.h"

#include "devastator_planning_msgs/msg/path_point.h"
// #include "devastator_planning_msgs/msg/target_trajectory.h"
#include "devastator_planning_msgs/msg/trajectory_point.h"
#include "mcu_planning/msg/planning_trajectory.h"
#include "mcu_planning/msg/trajectory_point.h"
#include <std_msgs/msg/header.h>
#include <stdio.h>
#include <time.h>
#include <unistd.h>
#ifdef ESP_PLATFORM
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#endif
#include "control_nodes/common/interfaces_c.h"
#include "control_nodes/controller_agent_c.h"
#include "control_nodes/controllers/lat_pid_controller_c.h"
#include "control_nodes_proto_c/control_conf.pb-c.h"
#include <math.h>
#define malloc(size) pvPortMalloc(size)
#define free(ptr) vPortFree(ptr)

#define STRING_BUFFER_LEN 6
#define MAX_trajectoryPOINTS 30
#define RCCHECK(fn)                                                            \
  {                                                                            \
    rcl_ret_t temp_rc = fn;                                                    \
    if ((temp_rc != RCL_RET_OK)) {                                             \
      printf("Failed status on line %d: %d. Aborting.\n", __LINE__,            \
             (int)temp_rc);                                                    \
      vTaskDelete(NULL);                                                       \
    }                                                                          \
  }
#define RCSOFTCHECK(fn)                                                        \
  {                                                                            \
    rcl_ret_t temp_rc = fn;                                                    \
    if ((temp_rc != RCL_RET_OK)) {                                             \
      printf("Failed status on line %d: %d. Continuing.\n", __LINE__,          \
             (int)temp_rc);                                                    \
    }                                                                          \
  }
// subscriber and publisher
rcl_publisher_t control_commond_publisher;
rcl_subscription_t localization_estimate_subscription;
rcl_subscription_t chassis_report_subscription;
rcl_subscription_t trajectory_subscription;
// message buf
devastator_localization_msgs__msg__LocalizationEstimateLight
    localization_estimate_submsg;
devastator_control_msgs__msg__VehicleReportCommonLight chassis_submsg;
mcu_planning__msg__PlanningTrajectory trajectorysubmsg;
devastator_control_msgs__msg__VehicleControlCommandLight commond_pubmsg;
// msg count
size_t loc_count_ = 0;
size_t chs_count_ = 0;
size_t plan_count_ = 0;
// interface
LocalizationEstimate localization;
ChassisReport chassis;
ADCTrajectory *trajectory;
ControlCommand control_cmd;
ControlError *control_error;
// params and flags
bool enable_plan_speed_clamp_ = true;
double plan_speed_clamp_value_ = 120.4;
// Agent point
ControllerAgent *agent_point;

void control_commond_pub_callback(rcl_timer_t *timer, int64_t last_call_time) {
  // printf("in pub\n");
  RCLC_UNUSED(last_call_time);
  Status checkresult = ControllerAgent_CheckInput(
      agent_point, &localization, &chassis, trajectory, chassis.header_time);
  if (Status_equal(&checkresult, &ok_status)) {
    ControllerAgent_ComputeControlCommand(agent_point, &localization, &chassis,
                                          trajectory, chassis.header_time,
                                          &control_cmd, control_error);
    ControllerAgent_ProcessOutput(agent_point, &localization, &chassis, &control_cmd);
    printf("cmd:steer%f", control_cmd.steer);
    printf("cmd:acc%f", control_cmd.acceleration);
  }
}
void pub_callback(rcl_timer_t *timer, int64_t last_call_time){
  RCLC_UNUSED(last_call_time);

  commond_pubmsg.late_mode = control_cmd.late_mode;
  commond_pubmsg.eps_torque = control_cmd.eps_torque;
  commond_pubmsg.front_wheel_target = control_cmd.front_wheel_target;
  commond_pubmsg.steering_target = 15.5 * control_cmd.steer / 3.14 * 180;

  // longit control command
  commond_pubmsg.long_mode = control_cmd.long_mode;
  commond_pubmsg.speed = control_cmd.speed;
  commond_pubmsg.acceleration = control_cmd.acceleration;
  commond_pubmsg.longit_torque = control_cmd.longit_torque;
  int start_time = xTaskGetTickCount();
  if (timer != NULL) {
    RCSOFTCHECK(rcl_publish(&control_commond_publisher, &commond_pubmsg,
    NULL));
  }
  printf("publish use %d\n", xTaskGetTickCount()-start_time);
}

void localization_estimate_callback(const void *msgin) {
  printf("loc cb\n");
  const devastator_localization_msgs__msg__LocalizationEstimateLight *msg =
      (devastator_localization_msgs__msg__LocalizationEstimateLight *)msgin;
  localization.x = msg->pose.position.x;
  localization.y = msg->pose.position.y;

  localization.z = msg->pose.position.z;
  localization.heading = msg->pose.heading;
  localization.heading = MathUtils_NormalizeAngle(localization.heading);
  localization.pitch = msg->pose.pitch;
  localization.vx = msg->pose.linear_velocity.x;
  localization.vy = msg->pose.linear_velocity.y;
  localization.vz = msg->pose.linear_velocity.z;
  localization.ax = msg->pose.linear_acceleration.x;
  localization.ay = msg->pose.linear_acceleration.y;
  localization.header_time =
      (msg->header.stamp.sec + msg->header.stamp.nanosec / 1e9);

  localization.sequence_num = loc_count_;
  loc_count_ += 1;
  // printf("Out localization callback\n");
}
void chassis_report_callback(const void *msgin) {
  printf("chass cb\n");

  const devastator_control_msgs__msg__VehicleReportCommonLight *msg =
      (devastator_control_msgs__msg__VehicleReportCommonLight *)msgin;
  chassis.yaw_rate = -msg->yaw_rate;
  chassis.gear_enable = msg->gear_enable;
  chassis.gear = msg->gear;
  chassis.late_enable = msg->late_enable; 
  chassis.late_driveover = msg->late_driveover; 

  chassis.steer_torque = msg->steer_torque;
  chassis.longit_driveover = msg->longit_driveover;

  chassis.longit_acc = msg->longit_acc;

  chassis.steer_angle = msg->steer_angle;
  chassis.speed = msg->speed / 3.6;
  chassis.longit_enable = msg->longit_enable;
  chassis.longit_acc = msg->longit_acc;
  chassis.steer_rotate_angel_speed = msg->steer_rotate_angle_speed;
  chassis.header_time =
      (msg->header.stamp.sec + msg->header.stamp.nanosec / 1e9);
  chassis.sequence_num = chs_count_;
  chs_count_ += 1;
  // printf("Out chassis callback\n");
}
void trajectory_callback(const void *msgin) {
  printf("tra cb\n");
  const mcu_planning__msg__PlanningTrajectory *msg =
      (mcu_planning__msg__PlanningTrajectory *)msgin;
  trajectory->sequence_num = plan_count_;
  plan_count_ += 1;
  trajectory->size = msg->trajectory_point.size;
  vec_TrajectoryPoint_resize(
      &trajectory->points, trajectory->size,
      (TrajectoryPoint){0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0});
  trajectory->header_time =
      (msg->header.stamp.sec + msg->header.stamp.nanosec / 1e9);
  trajectory->is_replan = msg->is_replan;
  trajectory->car_in_dead_end = msg->car_in_dead_end;
  trajectory->is_estop = msg->is_estop;

  for (int i = 0; i < trajectory->size; i++) {
    vec_TrajectoryPoint_data(&trajectory->points)[i].x =
        msg->trajectory_point.data[i].path_point.x;
    vec_TrajectoryPoint_data(&trajectory->points)[i].y =
        msg->trajectory_point.data[i].path_point.y;
    vec_TrajectoryPoint_data(&trajectory->points)[i].z =
        msg->trajectory_point.data[i].path_point.z;

    vec_TrajectoryPoint_data(&trajectory->points)[i].theta =
        msg->trajectory_point.data[i].path_point.theta;
    vec_TrajectoryPoint_data(&trajectory->points)[i].kappa =
        msg->trajectory_point.data[i].path_point.kappa;
    vec_TrajectoryPoint_data(&trajectory->points)[i].s =
        msg->trajectory_point.data[i].path_point.s;
    // vec_TrajectoryPoint_data(&trajectory->points)[i].dkappa =
    //     msg->trajectory_point.data[i].path_point.dkappa;
    vec_TrajectoryPoint_data(&trajectory->points)[i].v =
        msg->trajectory_point.data[i].v;
    if (enable_plan_speed_clamp_ &&
        vec_TrajectoryPoint_data(&trajectory->points)[i].v >
            plan_speed_clamp_value_)
      vec_TrajectoryPoint_data(&trajectory->points)[i].v =
          plan_speed_clamp_value_;

    vec_TrajectoryPoint_data(&trajectory->points)[i].a =
        msg->trajectory_point.data[i].a;
    // t->points[i]->da = msg->trajectorypoint[i].da;
    vec_TrajectoryPoint_data(&trajectory->points)[i].relative_time =
        msg->trajectory_point.data[i].relative_time;
  }
  if (trajectory->size <= 1) {
    printf("trajectory too short!\n");
  } else {
    trajectory->total_path_length =
        vec_TrajectoryPoint_back(&trajectory->points)->s;
    trajectory->total_path_time =
        vec_TrajectoryPoint_back(&trajectory->points)->relative_time;
  }
}
void get_rosidl_runtime_c_String_memory(rosidl_runtime_c__String *str,
                                        int len) {
  str->capacity = len;
  str->data = (char *)malloc(str->capacity * sizeof(char));
  str->size = 0;
}
void get_msgbuff_memory(void) {
  get_rosidl_runtime_c_String_memory(
      &localization_estimate_submsg.header.frame_id, STRING_BUFFER_LEN);
  get_rosidl_runtime_c_String_memory(
      &localization_estimate_submsg.state_message, STRING_BUFFER_LEN);

  trajectorysubmsg.trajectory_point.capacity = MAX_trajectoryPOINTS;
  trajectorysubmsg.trajectory_point.data =
      (mcu_planning__msg__TrajectoryPoint *)malloc(
          trajectorysubmsg.trajectory_point.capacity *
          sizeof(mcu_planning__msg__TrajectoryPoint));
}

void appMain(void *argument) {
  trajectory = (ADCTrajectory *)malloc(sizeof(ADCTrajectory));
  rcl_allocator_t allocator = rcl_get_default_allocator();
  rclc_support_t support;
  RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
  printf(" the min free heap size is %d \r\n", (int32_t)xPortGetFreeHeapSize());
  printf(" the min free stack size is %d \r\n",
         (int32_t)uxTaskGetStackHighWaterMark(NULL));
  rcl_node_t node;
  RCCHECK(rclc_node_init_default(&node, "control_node", "", &support));
  printf(" the min free heap size is %d \r\n", (int32_t)xPortGetFreeHeapSize());
  printf(" the min free stack size is %d \r\n",
         (int32_t)uxTaskGetStackHighWaterMark(NULL));
  printf("xixi\n");
  printf(" the min free heap size is %d \r\n", (int32_t)xPortGetFreeHeapSize());
  printf(" the min free stack size is %d \r\n",
         (int32_t)uxTaskGetStackHighWaterMark(NULL));
  RCCHECK(rclc_subscription_init_default(
      &localization_estimate_subscription, &node,
      ROSIDL_GET_MSG_TYPE_SUPPORT(devastator_localization_msgs, msg,
                                  LocalizationEstimateLight),
      "/localization/localization_estimate_light"));
  printf(" the min free heap size is %d \r\n", (int32_t)xPortGetFreeHeapSize());
  printf(" the min free stack size is %d \r\n",
         (int32_t)uxTaskGetStackHighWaterMark(NULL));
  RCSOFTCHECK(rclc_subscription_init_default(
      &chassis_report_subscription, &node,
      ROSIDL_GET_MSG_TYPE_SUPPORT(devastator_control_msgs, msg,
                                  VehicleReportCommonLight),
      "/control/vehicle_report_common_light"));
  printf(" the min free heap size is %d \r\n", (int32_t)xPortGetFreeHeapSize());
  printf(" the min free stack size is %d \r\n",
         (int32_t)uxTaskGetStackHighWaterMark(NULL));

  RCSOFTCHECK(rclc_subscription_init_default(
      &trajectory_subscription, &node,
      // ROSIDL_GET_MSG_TYPE_SUPPORT(devastator_planning_msgs, msg,
      //                             TargetTrajectory),
      ROSIDL_GET_MSG_TYPE_SUPPORT(mcu_planning, msg,
                                  PlanningTrajectory),
      "/planning/trajectory_path_translated"));

  LocalizationEstimate_Init(&localization);
  ChassisReport_Init(&chassis);
  ADCTrajectory_Creat(trajectory);
  ControlCommand_Init(&control_cmd);
  printf(" the min free heap size is %d \r\n", (int32_t)xPortGetFreeHeapSize());
  printf(" the min free stack size is %d \r\n",
         (int32_t)uxTaskGetStackHighWaterMark(NULL));
  rcl_timer_t timer;
  rcl_timer_t pub_timer;
 RCCHECK(rclc_timer_init_default(&timer, &support, RCL_MS_TO_NS(100),
                               control_commond_pub_callback));
   RCCHECK(rclc_timer_init_default(&pub_timer, &support, RCL_MS_TO_NS(100),
                                pub_callback));
  rclc_executor_t executor;
  // rclc_executor_t exepub;
  // rclc_executor_t exetra;
  // rclc_executor_t exelocal;
  RCCHECK(rclc_executor_init(&executor, &support.context, 5, &allocator));
  // RCCHECK(rclc_executor_init(&exepub, &support.context, 1, &allocator));
  // RCCHECK(rclc_executor_init(&exetra, &support.context, 2, &allocator));
  // RCCHECK(rclc_executor_init(&exelocal, &support.context, 2, &allocator));
  RCCHECK(rclc_executor_add_subscription(
      &executor, &chassis_report_subscription, &chassis_submsg,
      &chassis_report_callback, ON_NEW_DATA));
  RCCHECK(rclc_executor_add_subscription(
      &executor, &localization_estimate_subscription,
      &localization_estimate_submsg, &localization_estimate_callback,
      ON_NEW_DATA));

  RCCHECK(rclc_executor_add_subscription(&executor, &trajectory_subscription,
                                         &trajectorysubmsg,
                                         &trajectory_callback, ON_NEW_DATA));
   RCCHECK(rclc_executor_add_timer(&executor, &timer));
  RCCHECK(rclc_executor_add_timer(&executor, &pub_timer));
    RCCHECK(rclc_executor_set_trigger(&executor, rclc_executor_trigger_one, &localization_estimate_submsg));

  printf("2232\n");
  get_msgbuff_memory();
  printf("33333\n");
  printf(" the min free heap size is %d \r\n", (int32_t)xPortGetFreeHeapSize());
  printf(" the min free stack size is %d \r\n",
         (int32_t)uxTaskGetStackHighWaterMark(NULL));
  ControllerAgent agent;
  Devastator__Control__ControlConf conf;
  get_proto_conf(&conf);
  ControllerAgent_Creat(&agent);
  ControllerAgent_init(&agent, &conf);
    printf(" the min free heap size is %d \r\n", (int32_t)xPortGetFreeHeapSize());
  printf(" the min free stack size is %d \r\n",
         (int32_t)uxTaskGetStackHighWaterMark(NULL));
  agent_point = &agent;

  while (1) {
    rclc_executor_spin(&executor);
  }
  // RCCHECK(rcl_publisher_fini(&control_commond_publisher, &node));
  RCCHECK(rcl_node_fini(&node));
  // ControllerAgent_Free(&agent);
}
# liangjunming @ liangjunming-Inspiron-3668 in ~/program/mcu_ws on git:master x [12:41:09] C:254                                                                                                [455/45760]
$ ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB1 -v5 -b 460800                                                                                                                         
[1693749364.569793] info     | TermiosAgentLinux.cpp | init                     | running...             | fd: 3                                                                                           
[1693749364.570320] info     | Root.cpp           | set_verbose_level        | logger setup           | verbose_level: 5                                                                                   
[1693749379.251483] info     | Root.cpp           | create_client            | create                 | client_key: 0x0A173F68, session_id: 0x81                                                           
[1693749379.251710] info     | SessionManager.hpp | establish_session        | session established    | client_key: 0x0A173F68, address: 0                                                                 
[1693749379.251934] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 19                                                                  
[1693749379.259649] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 44                                                                  
[1693749379.307033] info     | ProxyClient.cpp    | create_participant       | participant created    | client_key: 0x0A173F68, participant_id: 0x000(1)                                                   
[1693749379.307151] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14                                                                  
[1693749379.307169] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.310115] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.321611] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 148                                                                 
[1693749379.321831] info     | ProxyClient.cpp    | create_topic             | topic created          | client_key: 0x0A173F68, topic_id: 0x000(2), participant_id: 0x000(1)                               
[1693749379.321887] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14                                                                  
[1693749379.321900] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.324256] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.326511] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 24                                                                  
[1693749379.326631] info     | ProxyClient.cpp    | create_subscriber        | subscriber created     | client_key: 0x0A173F68, subscriber_id: 0x000(4), participant_id: 0x000(1)                          
[1693749379.326670] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14                                                                  
[1693749379.326685] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.328243] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.331965] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 40                                                                  
[1693749379.641920] info     | ProxyClient.cpp    | create_datareader        | datareader created     | client_key: 0x0A173F68, datareader_id: 0x000(6), subscriber_id: 0x000(4)                           
[1693749379.642005] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14                                                                  
[1693749379.642075] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.644981] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.653671] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 156                                                                 
[1693749379.653713] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.653972] info     | ProxyClient.cpp    | create_topic             | topic created          | client_key: 0x0A173F68, topic_id: 0x001(2), participant_id: 0x000(1)
[1693749379.654030] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14
[1693749379.654048] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13
[1693749379.654061] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13
[1693749379.655518] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749379.657984] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 24
[1693749379.658068] info     | ProxyClient.cpp    | create_subscriber        | subscriber created     | client_key: 0x0A173F68, subscriber_id: 0x001(4), participant_id: 0x000(1)
[1693749379.658110] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14
[1693749379.658127] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13
[1693749379.660500] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749379.664250] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 40
[1693749379.664663] info     | ProxyClient.cpp    | create_datareader        | datareader created     | client_key: 0x0A173F68, datareader_id: 0x001(6), subscriber_id: 0x001(4)
[1693749379.664705] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14
[1693749379.664744] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13
[1693749379.667644] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749379.675542] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 140
[1693749379.675725] info     | ProxyClient.cpp    | create_topic             | topic created          | client_key: 0x0A173F68, topic_id: 0x002(2), participant_id: 0x000(1)
[1693749379.675760] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14
[1693749379.675776] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13
[1693749379.677327] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749379.679614] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 24
[1693749379.679670] info     | ProxyClient.cpp    | create_subscriber        | subscriber created     | client_key: 0x0A173F68, subscriber_id: 0x002(4), participant_id: 0x000(1)
[1693749379.679703] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14
[1693749379.679719] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13
[1693749379.681292] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749379.679719] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13                                                       [403/45760]
[1693749379.681292] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.685065] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 40                                                                  
[1693749379.685429] info     | ProxyClient.cpp    | create_datareader        | datareader created     | client_key: 0x0A173F68, datareader_id: 0x002(6), subscriber_id: 0x002(4)                           
[1693749379.685472] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 14                                                                  
[1693749379.685490] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.688542] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749379.741765] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 24                                                                  
[1693749379.741989] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749389.983715] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000000, len: 112                                                                   
[1693749389.983833] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 124                                                                 
[1693749389.984339] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000001, len: 56                                                                    
[1693749389.984377] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 68                                                                  
[1693749389.989424] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749389.992472] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749390.082869] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000000, len: 112                                                                   
[1693749390.082944] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 124                                                                 
[1693749390.083493] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000001, len: 56                                                                    
[1693749390.083537] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 68                                                                  
[1693749390.088074] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749390.090121] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749390.182944] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000000, len: 112                                                                   
[1693749390.183040] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 124                                                                 
[1693749390.183690] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000001, len: 56                                                                    
[1693749390.183737] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 68                                                                  
[1693749390.188046] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749390.190243] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                                                  
[1693749390.284413] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000000, len: 112                                                                   
[1693749390.284544] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 124                                                                 
[1693749390.285074] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000001, len: 56                                                                    
[1693749390.285115] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 68                                                                  
[1693749390.289628] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749390.291601] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749390.382624] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000000, len: 112 
[1693749390.382705] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 124
[1693749390.383142] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000001, len: 56                                          
[1693749390.383184] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 68
[1693749390.387651] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749390.389762] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749390.483427] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000000, len: 112 
[1693749390.483512] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 124                                      
[1693749390.484381] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000001, len: 56  
[1693749390.484429] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 68
[1693749390.488506] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749390.490671] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13 
[1693749390.583185] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000000, len: 112                                    
[1693749390.583281] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 124
[1693749390.583876] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000001, len: 56  
[1693749390.583928] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 68
[1693749390.588221] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13
[1693749390.590424] debug    | SerialAgentLinux.cpp | recv_message             | [==>> SER <<==]        | client_key: 0x0A173F68, len: 13                                        
[1693749390.683125] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000000, len: 112 
[1693749390.683206] debug    | SerialAgentLinux.cpp | send_message             | [** <<SER>> **]        | client_key: 0x0A173F68, len: 124
[1693749390.683721] debug    | DataReader.cpp     | read_fn                  | [==>> DDS <<==]        | client_key: 0x00000001, len: 56  

Three publisher working but no one enter callback,Looking forward to your reply very much

Junming-Liang commented 10 months ago

I found the reason why the published best effort topics could not be received. The solution is the same as for this issue:https://github.com/micro-ROS/micro_ros_setup/issues/236. It's because when I subscribed to the corresponding topics in ROS, I did not set the QOS to best effort.However, I still have not found a solution for the issue with the Trigger.

pablogs9 commented 10 months ago

Can we close this as solved?

Junming-Liang commented 10 months ago

Can we close this as solved?

Thank you very much for your reply. After setting the publisher correctly, my issue was actually resolved. Now I can subscribe and publish related topics normally. However, my question about the Trigger remains unresolved. After I set up the Trigger, there is still the issue that none of the topics can enter the callback function, whether using rclc_executor_trigger_one or rclc_executor_trigger_all. This is very frustrating for me.

pablogs9 commented 10 months ago

@JanStaschulat could you take a look at this issue about triggering the executor in RCLC?