You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
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 this issue
Sep 3, 2023
· 4 comments
Add multiple subscribers and publishers in the system.
Use high frequency msg
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:
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.
Change the publisher to "best effort" mode. However, when the publisher is adjusted to "best effort" mode, the topic cannot be received in ROS.
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>#ifdefESP_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>#definemalloc(size) pvPortMalloc(size)
#definefree(ptr) vPortFree(ptr)
#defineSTRING_BUFFER_LEN 6
#defineMAX_trajectoryPOINTS 30
#defineRCCHECK(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); \
} \
}
#defineRCSOFTCHECK(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 publisherrcl_publisher_tcontrol_commond_publisher;
rcl_subscription_tlocalization_estimate_subscription;
rcl_subscription_tchassis_report_subscription;
rcl_subscription_ttrajectory_subscription;
// message bufdevastator_localization_msgs__msg__LocalizationEstimateLightlocalization_estimate_submsg;
devastator_control_msgs__msg__VehicleReportCommonLightchassis_submsg;
mcu_planning__msg__PlanningTrajectorytrajectorysubmsg;
devastator_control_msgs__msg__VehicleControlCommandLightcommond_pubmsg;
// msg countsize_tloc_count_=0;
size_tchs_count_=0;
size_tplan_count_=0;
// interfaceLocalizationEstimatelocalization;
ChassisReportchassis;
ADCTrajectory*trajectory;
ControlCommandcontrol_cmd;
ControlError*control_error;
// params and flagsboolenable_plan_speed_clamp_= true;
doubleplan_speed_clamp_value_=120.4;
// Agent pointControllerAgent*agent_point;
voidcontrol_commond_pub_callback(rcl_timer_t*timer, int64_tlast_call_time) {
// printf("in pub\n");RCLC_UNUSED(last_call_time);
Statuscheckresult=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);
}
}
voidpub_callback(rcl_timer_t*timer, int64_tlast_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 commandcommond_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;
intstart_time=xTaskGetTickCount();
if (timer!=NULL) {
RCSOFTCHECK(rcl_publish(&control_commond_publisher, &commond_pubmsg,
NULL));
}
printf("publish use %d\n", xTaskGetTickCount()-start_time);
}
voidlocalization_estimate_callback(constvoid*msgin) {
printf("loc cb\n");
constdevastator_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");
}
voidchassis_report_callback(constvoid*msgin) {
printf("chass cb\n");
constdevastator_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");
}
voidtrajectory_callback(constvoid*msgin) {
printf("tra cb\n");
constmcu_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 (inti=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;
}
}
voidget_rosidl_runtime_c_String_memory(rosidl_runtime_c__String*str,
intlen) {
str->capacity=len;
str->data= (char*)malloc(str->capacity*sizeof(char));
str->size=0;
}
voidget_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));
}
voidappMain(void*argument) {
trajectory= (ADCTrajectory*)malloc(sizeof(ADCTrajectory));
rcl_allocator_tallocator=rcl_get_default_allocator();
rclc_support_tsupport;
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_tnode;
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_ttimer;
rcl_timer_tpub_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_texecutor;
// 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));
ControllerAgentagent;
Devastator__Control__ControlConfconf;
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);
}
Three publisher working but no one enter callback,Looking forward to your reply very much
The text was updated successfully, but these errors were encountered:
Junming-Liang
changed the title
unable to enter the callback function when publisher's frequency increases or the receiver's data volume becomes larger, and the trigger becomes invalid.
Unable to enter the callback function when publisher's frequency increases or the receiver's data volume becomes larger and the trigger becomes invalid.
Sep 3, 2023
I found the reason why the published best effort topics could not be received. The solution is the same as for this issue:#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.
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.
Issue template
Steps to reproduce the issue
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:
Additional information
This is my source code app.c:
Three publisher working but no one enter callback,Looking forward to your reply very much
The text was updated successfully, but these errors were encountered: