Closed KatterSnow closed 2 years ago
Hello, please provide steps for replicating these problems. First of all, how are you building the micro-ROS library? AFAIK STM32F303 is not supported by micro_ros_setup.
Also, provide a whole code that can be used to replicate this in our environment.
@pablogs9 ,Hello Sorry for the late reply.
I built the micro-ROS library with the tutorial: First micro-ROS Application on FreeRTOS https://micro.ros.org/docs/tutorials/core/first_application_rtos/freertos/
olimex-stm32-e407 is supported by stm32f4, I change the code of it and add a new floder,like: firmware/freertos_apps/microros_stm32_f303_extensions/ then modified the "PLATFORM": test-stm32-f303 Of course, new scripts are established in src/micro_ros_setup/config/freertos/stm-f303. A important step: Library functions of stm32f303 are used to modified the "firmware/freertos_apps/microros_olimex_e407_extensions/Src/microros_transports.c" serial transport is used as CustomTransport(baud rate: 3000000 bit/s)).
Then, follow these steps:
ros2 run micro_ros_setup create_firmware_ws.sh freertos test-stm32-f303
ros2 run micro_ros_setup configure_firmware.sh ping_pong --transport serial
ros2 run micro_ros_setup build_firmware.sh
In this way,I built the micro-ROS library(Most of files is copy from microros_olimex_e407_extensions)
Every demo of publisher/subscriber/service in "firmware/freertos_apps/apps" can work as expected.
Step1 :estabulished a micro-ROS APP: firmware/freertos_apps/apps/sensor I am sorry about that: for some reason, I cannot provide the code of all publishers. Here,I changed my publishers.(All are imu_message now, sum no more than 400byte)
app.c
#include <stdio.h>
#include <unistd.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rcl_action/rcl_action.h>
#include <rmw_microros/rmw_microros.h>
#include <imu_message/msg/imu_message.h>
#include "my_service_message/srv/my_service_message.h"
#include "service_test/srv/service_test.h"
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <time.h>
#ifdef ESP_PLATFORM
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#endif
#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);}}
rcl_publisher_t imu_publisher1;
rcl_publisher_t imu_publisher2;
rcl_publisher_t imu_publisher3;
rcl_publisher_t imu_publisher4;
rcl_publisher_t imu_publisher5;
rcl_publisher_t imu_publisher6;
rcl_publisher_t imu_publisher7;
rcl_publisher_t imu_publisher8;
rcl_publisher_t imu_publisher9;
rcl_publisher_t imu_publisher10;
rcl_publisher_t imu_publisher11;
rcl_publisher_t imu_publisher12;
rcl_publisher_t imu_publisher13;
rcl_publisher_t imu_publisher14;
rcl_publisher_t imu_publisher15;
rcl_publisher_t imu_publisher16;
rcl_service_t service;
rcl_service_t service1;
imu_message__msg__ImuMessage imu_msg_pub1;
imu_message__msg__ImuMessage imu_msg_pub2;
imu_message__msg__ImuMessage imu_msg_pub3;
imu_message__msg__ImuMessage imu_msg_pub4;
imu_message__msg__ImuMessage imu_msg_pub5;
imu_message__msg__ImuMessage imu_msg_pub6;
imu_message__msg__ImuMessage imu_msg_pub7;
imu_message__msg__ImuMessage imu_msg_pub8;
imu_message__msg__ImuMessage imu_msg_pub9;
imu_message__msg__ImuMessage imu_msg_pub10;
imu_message__msg__ImuMessage imu_msg_pub11;
imu_message__msg__ImuMessage imu_msg_pub12;
imu_message__msg__ImuMessage imu_msg_pub13;
imu_message__msg__ImuMessage imu_msg_pub14;
imu_message__msg__ImuMessage imu_msg_pub15;
imu_message__msg__ImuMessage imu_msg_pub16;
service_test__srv__ServiceTest_Request reqq;
service_test__srv__ServiceTest_Response ress;
void service_callback(const void * req, void * res){
my_service_message__srv__MyServiceMessage_Request * req_in = (my_service_message__srv__MyServiceMessage_Request *) req;
my_service_message__srv__MyServiceMessage_Response * res_in = (my_service_message__srv__MyServiceMessage_Response *) res;
printf("Service request value: %s\n", req_in->demand.data);
if(strcmp("aa", req_in->demand.data) == 0){
snprintf(res_in->data.data, res_in->data.capacity, "ASUCCESS");
}
else if(strcmp("bb", req_in->demand.data) == 0){
snprintf(res_in->data.data, res_in->data.capacity, "BSUCCESS");
}
else {
snprintf(res_in->data.data, res_in->data.capacity, "DK");
}
}
void service_callback1(const void * reqq, void * ress){
service_test__srv__ServiceTest_Request * reqq_in = (service_test__srv__ServiceTest_Request *) reqq;
service_test__srv__ServiceTest_Response * ress_in = (service_test__srv__ServiceTest_Response *) ress;
printf("Service request value: %d + %d.\n", (int) reqq_in->a, (int) reqq_in->b);
ress_in->sum = reqq_in->a + reqq_in->b;
}
void publisher_timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{
RCLC_UNUSED(last_call_time);
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&imu_publisher1, &imu_msg_pub1, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher2, &imu_msg_pub2, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher3, &imu_msg_pub3, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher4, &imu_msg_pub4, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher5, &imu_msg_pub5, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher6, &imu_msg_pub6, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher7, &imu_msg_pub7, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher8, &imu_msg_pub8, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher9, &imu_msg_pub9, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher10, &imu_msg_pub10, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher11, &imu_msg_pub11, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher12, &imu_msg_pub12, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher13, &imu_msg_pub13, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher14, &imu_msg_pub14, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher15, &imu_msg_pub15, NULL));
RCSOFTCHECK(rcl_publish(&imu_publisher16, &imu_msg_pub16, NULL));
}
}
void appMain(void * arg)
{
rcl_allocator_t allocator = rcl_get_default_allocator();
rclc_support_t support;
// create init_options
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
// create node
rcl_node_t node;
RCCHECK(rclc_node_init_default(&node, "sensor_node", "", &support));
// create publisher
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher1, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu1"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher2, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu2"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher3, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu3"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher4, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu4"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher5, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu5"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher6, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu6"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher7, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu7"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher8, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu8"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher9, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu9"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher10, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu10"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher11, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu11"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher12, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu12"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher13, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu13"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher14, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu14"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher15, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu15"));
RCCHECK(rclc_publisher_init_best_effort(&imu_publisher16, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(imu_message, msg, ImuMessage), "/sensor/imu16"));
// create service
RCCHECK(rclc_service_init_best_effort(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(my_service_message, srv, MyServiceMessage), "/mcu_service"));
RCCHECK(rclc_service_init_best_effort(&service1, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(service_test, srv, ServiceTest), "/service_test"));
// create timer,
rcl_timer_t timer;
const unsigned int timer_timeout = 5;
RCCHECK(rclc_timer_init_default(&timer, &support, RCL_MS_TO_NS(timer_timeout), publisher_timer_callback));
rclc_executor_t executor_pub;
unsigned int num_handles_pub = 1;
executor_pub = rclc_executor_get_zero_initialized_executor();
RCCHECK(rclc_executor_init(&executor_pub, &support.context, num_handles_pub, &allocator));
RCCHECK(rclc_executor_add_timer(&executor_pub, &timer));
rclc_executor_t executor_srv;
unsigned int num_handles_srv = 2;
executor_srv = rclc_executor_get_zero_initialized_executor();
RCCHECK(rclc_executor_init(&executor_srv, &support.context, num_handles_srv, &allocator));
my_service_message__srv__MyServiceMessage_Request req;
my_service_message__srv__MyServiceMessage_Response res;
my_service_message__srv__MyServiceMessage_Request__init(&req);
my_service_message__srv__MyServiceMessage_Response__init(&res);
const unsigned int SERVICE_MSG_CAPACITY = 10;
req.demand.data = malloc(SERVICE_MSG_CAPACITY);
req.demand.capacity = SERVICE_MSG_CAPACITY;
snprintf(req.demand.data, req.demand.capacity, "zz1");
req.demand.size = strlen(req.demand.data);
res.data.data = malloc(SERVICE_MSG_CAPACITY);
res.data.capacity = SERVICE_MSG_CAPACITY;
snprintf(res.data.data, res.data.capacity, "zz2");
res.data.size = strlen(res.data.data);
service_test__srv__ServiceTest_Request__init(&reqq);
service_test__srv__ServiceTest_Response__init(&ress);
RCCHECK(rclc_executor_add_service(&executor_srv, &service, &req, &res, service_callback));
RCCHECK(rclc_executor_add_service(&executor_srv, &service1, &reqq, &ress, service_callback1));
// assign message to publisher
imu_message__msg__ImuMessage__init(&imu_msg_pub1);
imu_message__msg__ImuMessage__init(&imu_msg_pub2);
imu_message__msg__ImuMessage__init(&imu_msg_pub3);
imu_message__msg__ImuMessage__init(&imu_msg_pub4);
imu_message__msg__ImuMessage__init(&imu_msg_pub5);
imu_message__msg__ImuMessage__init(&imu_msg_pub6);
imu_message__msg__ImuMessage__init(&imu_msg_pub7);
imu_message__msg__ImuMessage__init(&imu_msg_pub8);
imu_message__msg__ImuMessage__init(&imu_msg_pub9);
imu_message__msg__ImuMessage__init(&imu_msg_pub10);
imu_message__msg__ImuMessage__init(&imu_msg_pub11);
imu_message__msg__ImuMessage__init(&imu_msg_pub12);
imu_message__msg__ImuMessage__init(&imu_msg_pub13);
imu_message__msg__ImuMessage__init(&imu_msg_pub14);
imu_message__msg__ImuMessage__init(&imu_msg_pub15);
imu_message__msg__ImuMessage__init(&imu_msg_pub16);
while(1){
rclc_executor_spin_some(&executor_pub, RCL_MS_TO_NS(3));
usleep(4000);
rclc_executor_spin_some(&executor_srv, RCL_MS_TO_NS(1));
}
// free resources
RCCHECK(rcl_publisher_fini(&imu_publisher1, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher2, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher3, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher4, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher5, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher6, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher7, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher8, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher9, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher10, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher11, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher12, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher13, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher14, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher15, &node));
RCCHECK(rcl_publisher_fini(&imu_publisher16, &node));
RCCHECK(rcl_service_fini(&service, &node));
RCCHECK(rcl_service_fini(&service1, &node));
RCCHECK(rcl_node_fini(&node));
vTaskDelete(NULL);
}
app-colcon.meta:
{
"names": {
"rmw_microxrcedds": {
"cmake-args": [
"-DRMW_UXRCE_MAX_NODES=1",
"-DRMW_UXRCE_MAX_PUBLISHERS=16",
"-DRMW_UXRCE_MAX_SUBSCRIPTIONS=0",
"-DRMW_UXRCE_MAX_SERVICES=2",
"-DRMW_UXRCE_MAX_CLIENTS=0",
"-DRMW_UXRCE_MAX_HISTORY=2",
]
}
}
}
follow this tutorial: https://micro.ros.org/docs/tutorials/advanced/create_new_type/ ServiceTest.srv:
{
int64 a
int64 b
---
int64 sum
}
MyServiceMessage.srv
{
string demand
---
string data
}
ImuMessage.srv
{
float32 x
float32 y
float32 z
}
Step2:ros2 run micro_ros_setup configure_firmware.sh sensor --transport serial
Step3: ros2 run micro_ros_setup build_firmware.sh
then flash the microROS.bin
Step4:ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/serial/by-id/usb-1a86_USB_Serial-if00-port0 -b 3000000 -v6
Then, I got problem2: the service returns "1",which means: Generic error to indicate operation could not complete successfully. This problem don't always exist, I changed nothing but test again, everything can be ok sometimes. I modified this problem by increasing "-DRMW_UXRCE_MAX_HISTORY" :"-DRMW_UXRCE_MAX_HISTORY=3" However, I have changed "-DUCLIENT_SERIAL_TRANSPORT_MTU=1024", The internal middleware layer uses a buffer of 1024x3 = 3072 Bytes, it is much larger than the data I wanted to transmit. There must be something wrong. This buff seems to be unrelated with the attributes.stack_size in freeRTOS task, how can it be optimized to save space? This problem may cause RAM not enough. (Where can I find the logfile of rclc?)
Step5:ros2 topic hz /sensor/imu1
Then I got problem4: The publish frequency is no more 60 HZ which is expected to be 200 HZ problem5:when I run a lot of programs in callback of service, if one node is enough to support 16 publisher and 2 services? I want to ask if micro-ros can support establish two or more tasks of freeRTOS in micro-ROS app main,or any other example to support "multi-threading".
Step6: ros2 service call /mcu_service my_service_message/srv/MyServiceMessage "demand: bb"
Then, I got problem3: I received this error: terminate called after throwing an instance of 'eprosima::fastcdr::exception::NotEnoughMemoryException' what(): Not enough memory in the buffer stream Aborted (core dumped) however,for ServiceTest(the other service), everything is ok
step7: try again: ros2 service call /mcu_service my_service_message/srv/MyServiceMessage "demand: bb"
problem3 will not happen. How can I slove this problem? it seems due to srv "string".
step8: ros2 service call -r 0.5 /service_test service_test/srv/ServiceTest "{a: 1, b: 2}"
Then I got problem6: I can get the response several times and then there is no any response. The client-agent communication is still running. problem7:However,sometimes the client-agent communication will stop: invalid client key
step9: I changed "service" to "subsriber",and change these codes:
while(1){
rclc_executor_spin_some(&executor_pub, RCL_MS_TO_NS(5));
usleep(5000);
rclc_executor_spin_some(&executor_sub, RCL_MS_TO_NS(5));
}
The publish frequency was no more than 60HZ (tested by "ros2 topic hz").
while(1){
rclc_executor_spin_some(&executor_pub, RCL_MS_TO_NS(3);
usleep(4000);
rclc_executor_spin_some(&executor_sub, RCL_MS_TO_NS(1));
}
problem1:The publish frequency was no more than 120 HZ.
Regarding the publish frequency problem:
You configured the timer to publish each 5 ms (200 hz), but on your main loop you are adding a delay with usleep
and rclc_executor_spin_some(&executor_sub, ...)
In fact, you are getting exactly the expected rate:
First spin (5 ms) + sleep (5 ms) + second spin (5 ms) = 15 ms ≈ 60 hz
while(1) {
rclc_executor_spin_some(&executor_pub, RCL_MS_TO_NS(5));
usleep(5000);
rclc_executor_spin_some(&executor_sub, RCL_MS_TO_NS(5));
}
First spin (3 ms) + sleep (4 ms) + second spin (1 ms) = 8 ms = 125 hz
while(1) {
rclc_executor_spin_some(&executor_pub, RCL_MS_TO_NS(5));
usleep(5000);
rclc_executor_spin_some(&executor_sub, RCL_MS_TO_NS(5));
}
To solve this:
usleep
.Please check your source code carefully
Here you are calling rclc_service_init_best_effort
on service
twice, leaving service1
unitialized:
RCCHECK(rclc_service_init_best_effort(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(my_service_message, srv, MyServiceMessage), "/mcu_service"));
RCCHECK(rclc_service_init_best_effort(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(service_test, srv, ServiceTest), "/service_test"));
Where are imu_publisher
and imu_msg_pub
defined?
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&imu_publisher, &imu_msg_pub, NULL));
}
Please check your source code carefully
- Here you are calling
rclc_service_init_best_effort
onservice
twice, leavingservice1
unitialized:RCCHECK(rclc_service_init_best_effort(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(my_service_message, srv, MyServiceMessage), "/mcu_service")); RCCHECK(rclc_service_init_best_effort(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(service_test, srv, ServiceTest), "/service_test"));
- Where are
imu_publisher
andimu_msg_pub
defined?if (timer != NULL) { RCSOFTCHECK(rcl_publish(&imu_publisher, &imu_msg_pub, NULL)); }
Sorry, the error code is modified. But these mistakes donot led to above-mentioned problems for I tested micro-ROS with right code. I, again,am really sorry for the mistakes.
Thank you! "Spin each executor on a different freeRTOS task" may mean I should establish 2 tasks of freeRTOS in micro-ROS appMain. I will try it!
@Acuadros95 I really appreciate your help! Hello, I used one executor to add a timer and 2 services,the publish frequency can be increased.
while(1) {
rclc_executor_spin_some(&executor_pub, RCL_MS_TO_NS(2));
usleep(4000);
}
the publish frequency : 85 -- 95HZ
while(1) {
rclc_executor_spin_some(&executor_pub, RCL_MS_TO_NS(1));
usleep(4000);
}
the publish frequency : 61 -- 85HZ
The delay may be the intrinsic feature caused by service?
@pablogs9 ,Something else:
1. problem2 still exists after increasing
RMW_UXRCE_MAX_HISTORY=3
Without any change of code,
sometimes the service returns "1" at:
RCCHECK(rclc_service_init_best_effort(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(my_service_message, srv, MyServiceMessage), "/mcu_service"));
sometimes the service returns "1" at:
RCCHECK(rclc_service_init_best_effort(&service1, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(service_test, srv, ServiceTest), "/service_test"));
sometimes everything is ok, the agent-client connection can work well.
When I set
RMW_UXRCE_MAX_HISTORY=2
UCLIENT_SERIAL_TRANSPORT_MTU=2048
ERROR: region `RAM' overflowed by 1592 bytes
but When I set
RMW_UXRCE_MAX_HISTORY=4
UCLIENT_SERIAL_TRANSPORT_MTU=1024
This problem does not exist.
2. Today, I tested micro-ROS with only 2 service: (one srv contions string) problem3 still exists:
**terminate called after throwing an instance of 'eprosima::fastcdr::exception::NotEnoughMemoryException' what(): Not enough memory in the buffer stream Aborted (core dumped)**
3. log of agent(problem7) This problem seems only exists when involves "service" (after client-agent connecting run for a while)
1650966289.290667] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 FA 7A 07 01 08 00 7B 43 00 25 00 00 00 00
[1650966289.290865] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 FB 7A 07 01 06 00 7B 44 00 15 00 41 00 00
[1650966289.291097] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 36, data:
0000: 81 01 FC 7A 07 01 1C 00 7B 45 00 35 00 41 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00
[1650966289.291267] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 FD 7A 07 01 09 00 7B 46 00 45 00 00 00 00 00 00 00 00
[1650966289.291473] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 FE 7A 07 01 0A 00 7B 47 00 55 00 00 00 00 00 00 00 00
[1650966289.291666] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 FF 7A 07 01 0C 00 7B 48 00 65 00 00 00 00 00 00 00 00
[1650966289.291832] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 28, data:
0000: 81 01 00 7B 07 01 14 00 7B 49 00 75 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.292087] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 01 7B 07 01 07 00 7B 4A 00 85 00 00 00 00
[1650966289.292125] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 02 7B 07 01 07 00 7B 4B 00 95 00 00 00 00
[1650966289.292289] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 03 7B 07 01 06 00 7B 4C 00 A5 00 00 00 00
[1650966289.292580] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 04 7B 07 01 07 00 7B 4D 00 B5 00 00 00 00
[1650966289.292614] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 05 7B 07 01 06 00 7B 4E 00 C5 00 00 00 00
[1650966289.292799] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 06 7B 07 01 07 00 7B 4F 00 D5 00 00 00 00
[1650966289.293112] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 07 7B 07 01 0C 00 7B 50 00 E5 00 00 00 00 00 00 00 00
[1650966289.293165] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 40, data:
0000: 81 01 08 7B 07 01 1D 00 7B 51 00 F5 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00 00 00 00 00
[1650966289.297477] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 88, data:
0000: 81 01 09 7B 07 01 4D 00 7B 52 00 05 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0040: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.298381] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 36, data:
0000: 81 01 0C 7B 07 01 1C 00 7B 55 00 35 00 41 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00
[1650966289.298513] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 0D 7B 07 01 09 00 7B 56 00 45 00 00 00 00 00 00 00 00
[1650966289.298738] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 0E 7B 07 01 0A 00 7B 57 00 55 00 00 00 00 00 00 00 00
[1650966289.298767] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 0F 7B 07 01 0C 00 7B 58 00 65 00 00 00 00 00 00 00 00
[1650966289.299658] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 28, data:
0000: 81 01 10 7B 07 01 14 00 7B 59 00 75 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.299703] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 11 7B 07 01 07 00 7B 5A 00 85 00 00 00 00
[1650966289.299726] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 12 7B 07 01 07 00 7B 5B 00 95 00 00 00 00
[1650966289.301660] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 17 7B 07 01 0C 00 7B 60 00 E5 00 00 00 00 00 00 00 00
[1650966289.304515] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 88, data:
0000: 81 01 19 7B 07 01 4D 00 7B 62 00 05 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0040: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.304903] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 1B 7B 07 01 06 00 7B 64 00 15 00 41 00 00
[1650966289.305046] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 36, data:
0000: 81 01 1C 7B 07 01 1C 00 7B 65 00 35 00 41 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00
[1650966289.305287] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 1D 7B 07 01 09 00 7B 66 00 45 00 00 00 00 00 00 00 00
[1650966289.305506] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 1E 7B 07 01 0A 00 7B 67 00 55 00 00 00 00 00 00 00 00
[1650966289.305847] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 28, data:
0000: 81 01 20 7B 07 01 14 00 7B 69 00 75 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.306140] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 21 7B 07 01 07 00 7B 6A 00 85 00 00 00 00
[1650966289.306186] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 22 7B 07 01 07 00 7B 6B 00 95 00 00 00 00
[1650966289.306464] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 23 7B 07 01 06 00 7B 6C 00 A5 00 00 00 00
[1650966289.306835] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 24 7B 07 01 07 00 7B 6D 00 B5 00 00 00 00
[1650966289.306879] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 26 7B 07 01 07 00 7B 6F 00 D5 00 00 00 00
[1650966289.307040] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 27 7B 07 01 0C 00 7B 70 00 E5 00 00 00 00 00 00 00 00
[1650966289.311673] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 2A 7B 07 01 08 00 7B 73 00 25 00 00 00 00
[1650966289.311911] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 2B 7B 07 01 06 00 7B 74 00 15 00 41 00 00
[1650966289.312630] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 36, data:
0000: 81 01 2C 7B 07 01 1C 00 7B 75 00 35 00 41 00 00 00 00 00 00 00 00 00 00 00 00 00 00 63 7C C3 02
0020: 00 00 00 00
[1650966289.312746] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 2D 7B 07 01 09 00 7B 76 00 45 00 00 00 00 00 00 00 00
[1650966289.312783] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 2E 7B 07 01 0A 00 7B 77 00 55 00 00 00 00 00 00 00 00
[1650966289.312813] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 2F 7B 07 01 0C 00 7B 78 00 65 00 00 00 00 00 00 00 00
[1650966289.313614] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 28, data:
0000: 81 01 30 7B 07 01 14 00 7B 79 00 75 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.313674] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 31 7B 07 01 07 00 7B 7A 00 85 00 00 00 00
[1650966289.313692] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 32 7B 07 01 07 00 7B 7B 00 95 00 00 00 00
[1650966289.314075] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 37 7B 07 01 0C 00 7B 80 00 E5 00 00 00 00 00 00 00 00
[1650966289.316281] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 40, data:
0000: 81 01 38 7B 07 01 1D 00 7B 81 00 F5 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00 00 00 00 00
[1650966289.319617] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 88, data:
0000: 81 01 39 7B 07 01 4D 00 7B 82 00 05 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0040: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.319687] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 3A 7B 07 01 08 00 7B 83 00 25 00 00 00 00
[1650966289.320128] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 41 7B 07 01 07 00 7B 8A 00 85 00 00 00 00
[1650966289.320155] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 42 7B 07 01 07 00 7B 8B 00 95 00 00 00 00
[1650966289.320331] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 43 7B 07 01 06 00 7B 8C 00 A5 00 00 00 00
[1650966289.320510] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 44 7B 07 01 07 00 7B 8D 00 B5 00 00 00 00
[1650966289.320816] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 46 7B 07 01 07 00 7B 8F 00 D5 00 00 00 00
[1650966289.321033] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 47 7B 07 01 0C 00 7B 90 00 E5 00 00 00 00 00 00 00 00
[1650966289.323133] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 40, data:
0000: 81 01 48 7B 07 01 1D 00 7B 91 00 F5 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00 00 00 00 00
[1650966289.325732] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 88, data:
0000: 81 01 49 7B 07 01 4D 00 7B 92 00 05 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0040: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.325766] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 4A 7B 07 01 08 00 7B 93 00 25 00 00 00 00
[1650966289.325855] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 16, data:
0000: 81 01 4B 7B 07 01 06 00 7B 94 00 15 00 41 00 00
[1650966289.326037] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 36, data:
0000: 81 01 4C 7B 07 01 1C 00 7B 95 00 35 00 41 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0020: 00 00 00 00
[1650966289.326472] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 4D 7B 07 01 09 00 7B 96 00 45 00 00 00 00 00 00 00 00
[1650966289.326509] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 4E 7B 07 01 0A 00 7B 97 00 55 00 00 00 00 00 00 00 00
[1650966289.327726] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 4F 7B 07 01 0C 00 7B 98 00 65 00 00 00 00 00 00 00 00
[1650966289.327776] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 28, data:
0000: 81 01 50 7B 07 01 14 00 7B 99 00 75 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966289.329695] debug | SerialAgentLinux.cpp | recv_message | [==>> SER <<==] | client_key: 0x085BAF84, len: 20, data:
0000: 81 01 57 7B 07 01 0C 00 7B A0 00 E5 00 00 00 00 00 00 00 00
[1650966289.333277] info | Root.cpp | delete_client | delete | client_key: 0x085BAF84
[1650966289.333332] info | SessionManager.hpp | destroy_session | session closed | client_key: 0x085BAF84, address: 0
[1650966289.333390] warning | Root.cpp | create_client | invalid client key | client_key: 0x00000000
[1650966302.553494] error | InputMessage.cpp | log_error | deserialization error | buffer:
0000: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966303.785584] error | InputMessage.cpp | log_error | deserialization error | buffer:
0000: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966324.610849] error | InputMessage.cpp | log_error | deserialization error | buffer:
0000: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966337.224934] error | InputMessage.cpp | log_error | deserialization error | buffer:
0000: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966339.668034] error | InputMessage.cpp | log_error | deserialization error | buffer:
0000: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966362.803445] error | InputMessage.cpp | log_error | deserialization error | buffer:
0000: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966391.735107] error | InputMessage.cpp | log_error | deserialization error | buffer:
0000: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
[1650966391.987020] error | InputMessage.cpp | log_error | deserialization error | buffer:
0000: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
RMW_UXRCE_MAX_HISTORY
is related to entities message queue. Check this tutorial on middleware configuration: link
Also, make sure you are not using the same serial port for debug (printf
statements, ...) and for micro-ROS communications.
Any update on this?
Any update on this? My apologies for the delay in responding,I don't have time to go on my study on micro-ROS , because I met some big troubles. At the moment, no progress has been made. I may work on micro-ROS in a few months later. Thank you a lot for your help.!
Issue template
Steps to reproduce the issue
Hi, Problem 1:
I estabulished a micro-ROS APP with: -1 node -16 publishers( sum,no more than 300byte), all are best_effort -1 subscriber( best_effort) -2 executors: one for publishers, add a timer(rclc_timer_init_default(&timer, &support, RCL_MS_TO_NS(5), publisher_timer_callback)));one for subscriber then I set:
Then I changed my code:
Expected behavior
The publish frequency is expected to be 200 HZ, how can I improve it?
Problem 2: I estabulished a micro-ROS APP with: -1 node -16 publishers( sum no more than 400byte), all are best_effort -2 services( best_effort) -2 executors: one for publishers, add a timer(rclc_timer_init_default(&timer, &support, RCL_MS_TO_NS(5), publisher_timer_callback)));one for services
ServiceTest.srv:
MyServiceMessage.srv
initialized services:
then I set:
I try to establish the communication between client and agent, but: the service returns 1,which means: Generic error to indicate operation could not complete successfully. This problem don't always exist, I changed nothing but test again, everything can be ok sometimes. I modified this problem by increasing "-DRMW_UXRCE_MAX_HISTORY" :"-DRMW_UXRCE_MAX_HISTORY=3" However, I have changed "-DUCLIENT_SERIAL_TRANSPORT_MTU=1024", The internal middleware layer uses a buffer of 1024x3 = 3072 Bytes, it is much larger than the data I wanted to transmit. There must be something wrong. This buff seems to be unrelated with the attributes.stack_size in freeRTOS task, how can it be optimized to save space? This problem may cause RAM not enough.
Problem 3: Test service with "ros2 service call" For ServiceTest, everything is ok. But for MyServiceMessage,fist time : I received this error: terminate called after throwing an instance of 'eprosima::fastcdr::exception::NotEnoughMemoryException' what(): Not enough memory in the buffer stream Aborted (core dumped) the second time "ros2 service call": this problem will not happen.
How can I slove this problem? it seems due to msg "string".
Problem4: The publish frequency is no more 60 HZ which is expected to be 200 HZ
Problem5: when I run a lot of programs in callback of service, if one node is enough to support 16 publisher and 2 services? I want to ask if micro-ros can support establish two or more tasks of freeRTOS in micro-ROS app main,or any other example to support "multi-threading".
Problem6: When I test service with "ros2 service call":
ros2 service call -r 0.5 /service_test service_test/srv/ServiceTest "{a: 1, b: 2}"
I can get the response several times and then there is no any response. The client-agent communication is still running.Problem7: Sometimes, I test service with "ros2 service call",the client-agent communication will stop: invalid client key The agent log: By the way, is there any way to reduce the compile time? It cost a lot of time to compile after I modified any code.