micro_ros自定义话题发布频率

Published: less than 1 minute read, with 172 words. Post views:

micro_ros自定义话题发布频率

测试环境:

  • vmware虚拟机+ubuntu20.04+ros2 foxy
  • esp32 (micro_ros_arduino)

0. 写在前面

  • micro_ros可以将MCU与ros系统进行无缝集成,实现话题的订阅、发布,服务的建立等;
  • 实际使用中,我们可能需要通过micro_ros实现高频的数据传输or通讯;
  • 本文基于串口通讯实现micro_ros的话题发布;
  • 影响micro_ros话题发布频率的有:串口波特率、定时器频率、QoS策略等;

1. 话题发布频率影响因素

1.1 串口波特率

  • 串口通讯中,越高的串口波特率代表单位时间可以传输的数据量更大。
  • micro_ros_arduino默认的串口波特率为115200;
  • 想要修改默认的波特率,可以自行修改相关的代码;
  • 打开micro_ros_arduino文件夹,文件路径:C:\Users\你自己的用户文件夹\Documents\Arduino\libraries\micro_ros_arduino-2.0.5-foxy\src
  • 打开default_transport.cpp,将下图中的115200修改为自定义的波特率
  • 可能并非所有波特率都支持,在实测过程中,我使用250000波特率无法实现通讯,使用921600反而可以,官方也并未进行详细解释说明;
  • 遇到自定义波特率通讯不成功的问题,可以在micro_ros_arduino提issue;
 bool arduino_transport_open(struct uxrCustomTransport * transport)
  {
    Serial.begin(115200); //修改115200为自定义波特率,如409600、921600等
    return true;
  }
  • 重新编译代码即可;

1.2 定时器频率

  • 打开micro_ros中的示例代码:micro-ros_publisher.ino
  // create timer,
  const unsigned int timer_timeout = 1000;// 修改timer_timeout
  RCCHECK(rclc_timer_init_default(
    &timer,
    &support,
    RCL_MS_TO_NS(timer_timeout),
    timer_callback));
  • 修改timer_timeout;若timer_timeout=1000,则代表1000ms的定时器,即1000ms发布一次;若timer_timeout=500,则代表500ms的定时器,即500ms发布一次;
  • 若tiemr_timeout的值小于100,即希望话题发布的频率>10Hz,需要注释掉loop循环中的delay(100);
void loop() {
//  delay(100);
  RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
}

1.3 QoS策略

  • QoS策略参考官方文档
  • 简而言之:
    1. 若话题发布频率较低,如10~30Hz,使用rclc_publisher_init_default
    2. 若话题发布频率较高,如>30Hz,使用rclc_publisher_init_best_effort
  // create publisher
  RCCHECK(rclc_publisher_init_default( /*高频数据传输使用rclc_publisher_init_best_effort*/
    &publisher,
    &node,
    ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
    "micro_ros_arduino_node_publisher"));
  • 注意QoS的兼容性,best_effort的publisher必须对应best_effort的subscription; QoS兼容性

2. 实测话题发布频率

  • 下面的测试需要注释loop循环中的**delay(100);

2.1 默认波特率+default QoS(rclc_publisher_init_default)

  • 基于micro_ros中的示例代码:micro-ros_publisher.ino
  • 使用默认波特率115200,仅通过修改timer_timeout改变话题发布频率;依次修改timer_timeout的值为100、10、1,即话题发布频率分别为10Hz、100Hz、1000Hz;
  • 使用ros2 topic hz /micro_ros_arduino_node_publisher 查看发布发布频率;

2.2 自定义波特率+default QoS(rclc_publisher_init_default)

  • 基于micro_ros中的示例代码:micro-ros_publisher.ino
  • 修改波特率为921600,依次修改timer_timeout的值为100、10、1,即话题发布频率分别为10Hz、100Hz、1000Hz;
  • 运行micro_agent时需要指定波特率,利用-b设置波特率参数:ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0 -b 921600
  • 使用ros2 topic hz /micro_ros_arduino_node_publisher 查看发布发布频率;

2.3 默认波特率+best_effort QoS(rclc_publisher_init_best_effort)

  • 基于micro_ros中的示例代码:micro-ros_publisher.ino
  • 修改rclc_publisher_init_defaultrclc_publisher_init_best_effort
  • 使用默认波特率115200,仅通过修改timer_timeout改变话题发布频率;依次修改timer_timeout的值为100、10、1,即话题发布频率分别为10Hz、100Hz、1000Hz;
  • 使用ros2 topic hz /micro_ros_arduino_node_publisher 查看发布发布频率;

2.4 自定义波特率+best_effort QoS(rclc_publisher_init_best_effort)

  • 基于micro_ros中的示例代码:micro-ros_publisher.ino
  • 修改rclc_publisher_init_defaultrclc_publisher_init_best_effort
  • 使用自定义波特率921600,仅通过修改timer_timeout改变话题发布频率;依次修改timer_timeout的值为100、10、1,即话题发布频率分别为10Hz、100Hz、1000Hz;
  • 运行micro_agent时需要指定波特率,利用-b设置波特率参数:ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0 -b 921600
  • 使用ros2 topic hz /micro_ros_arduino_node_publisher 查看发布发布频率;

2.5 极限发布频率实测

  • 基于micro_ros中的示例代码:micro-ros_publisher.ino
  • 修改rclc_publisher_init_defaultrclc_publisher_init_best_effort
  • 使用自定义波特率921600,设置timer_timeout=0.1,即理论定时器频率10000Hz;
  • 运行micro_agent时需要指定波特率,利用-b设置波特率参数:ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0 -b 921600
  • 使用ros2 topic hz /micro_ros_arduino_node_publisher 查看发布发布频率;

3. 总结

  • default模式下,单个int32数据发布极限在300Hz(921600bps下)
  • best_effort模式下,单个int32数据发布极限在约3600Hz(921600bps下)
  • 一个int32占用4个byte,3600Hz的发布频率对应波特率为:
3600*4*(10/8)*8=144000b/s
  • 跟921600bps差别较大,因此波特率已经不是数据发布频率的限制因素了,猜测是定时器;
  • 可以参考官方issue
  • 但是稳定的1000Hz数据传输应该满足我们绝大部分需求了

Tags: , ,

Categories:

Comments