Skip to content

px4消息通信机制(uORB)分析#

  • uORB 模块路径:px4/PX4_Autopilot/3rd/px4/platforms/common/uORB
.
|-- CMakeLists.txt
|-- Kconfig
|-- ORBSet.hpp  #  set 容器
|-- Publication.hpp # 发布者
|-- PublicationMulti.hpp # 发布者 同一 ORB_ID 的不同实例,方便 设备/驱动器的多个实例实现
|-- Subscription.cpp
|-- Subscription.hpp # 订阅者
|-- SubscriptionBlocking.hpp # 订阅者 回调注册(pthread_cond_signal(&_cv);) ,可以阻塞等待新数据 , updateBlocking(T &data, uint32_t timeout_us = 0)
|-- SubscriptionCallback.hpp # 订阅者 回调注册(_work_item->ScheduleNow();) , SubscriptionCallbackWorkItem
|-- SubscriptionInterval.hpp # 订阅者 加上时间间隔约束 , px4 中主要用于参数更新 , 无回调,需要主动检查updated() ,再copy(&) 出来使用
|-- SubscriptionMultiArray.hpp # 订阅者 同一 ORB_ID 的不同多个实例 订阅
|-- uORB.cpp
|-- uORB.h # c 接口封装 uORB::Manager::get_instance() 相关函数
|-- uORBCommon.hpp
|-- uORBCommunicator.hpp # remote 通信接口
|-- uORBDeviceMaster.cpp
|-- uORBDeviceMaster.hpp
|-- uORBDeviceNode.cpp
|-- uORBDeviceNode.hpp  # 一个 node 管理一个话题 实例(管理queue数据队列,管理SubscriptionCallback,实现发布publish,即通知sub) ,如:/obj/actuator_armed0 ([话题]+[实例id])
|-- uORBManager.cpp
|-- uORBManager.hpp  # 单例,管理 node
|-- uORBManagerUsr.cpp
|-- uORBTopics.h
|-- uORBUtils.cpp
|-- uORBUtils.hpp # 根据话题生成path,该path是唯一,如:/obj/actuator_armed0 ([话题]+[实例id])
  • uORB 的 topic 有点歧义,实际 /obj/actuator_armed0 ([话题]+[实例id]) 才是消息队列唯一标识,即PATH,可以通过uorb status 看到
  • 不要与 ros 中 topic 的概念弄混了

类图#

  • 由于 工具对宏的处理支持不太友好,类关系图仅供参考,大体上是可以的
  • 有时间后面再详细梳理一下重写手画

px4_uorb


Subscription#

  • 通知对应的队列处理
  • 没分析 remote 通信相关内容
/// SubscriptionCallbackWorkItem

 void call() override
 {
  // schedule immediately if updated (queue depth or subscription interval)
  if ((_required_updates == 0)
      || (Manager::updates_available(_subscription.get_node(), _subscription.get_last_generation()) >= _required_updates)) {
   if (updated()) {
    _work_item->ScheduleNow();
   }
  }
 }

/// SubscriptionBlocking
 void call() override
 {
  // signal immediately if no interval, otherwise only if interval has elapsed
  if ((_interval_us == 0) || (hrt_elapsed_time(&_last_update) >= _interval_us)) {
   pthread_cond_signal(&_cv);
  }
 }

整体流程#

  • 没啥时间,就简单分析下大体流程,后面有时间再完善下
      1. pub,sub 注册
      1. pub 发消息 publish(const T&data) --> Manager::orb_publish(get_topic(), _handle, &data) --> DeviceNode::publish --> DeviceNode::write --> for(auto item : _callbacks) {item->call();}
      2. SubscriptionCallbackWorkItem : _work_item->ScheduleNow();
      3. SubscriptionBlocking : pthread_cond_signal(&_cv);
      1. sub 收消息
      2. SubscriptionCallbackWorkItem :workqueue 处理 workitem 中 run() 实例,组件在 run()中通过 sub.update(&imu); 来使用数据
      3. SubscriptionBlocking : 在某个线程中阻塞等待新数据 updateBlocking(T &data, uint32_t timeout_us = 0)

uorb status 查看#

pxh> uorb status
TOPIC NAME              INST #SUB #Q SIZE PATH
actuator_armed             0    5  1   16 /obj/actuator_armed0
actuator_motors            0    0  1   72 /obj/actuator_motors0
actuator_servos            0    0  1   48 /obj/actuator_servos0
actuator_servos_trim       0    0  1   40 /obj/actuator_servos_trim0
control_allocator_status   0    0  1   56 /obj/control_allocator_status0
control_allocator_status   1    0  1   56 /obj/control_allocator_status1
cpuload                    0    3  1   16 /obj/cpuload0
estimator_selector_status  0    2  1  160 /obj/estimator_selector_status0
event                      0    1 16   40 /obj/event0
failsafe_flags             0    0  1   88 /obj/failsafe_flags0
failure_detector_status    0    1  1   24 /obj/failure_detector_status0
health_report              0    1  1   64 /obj/health_report0
led_control                0    0  8   16 /obj/led_control0
log_message                0    0  4  136 /obj/log_message0
manual_control_setpoint    0    4  1   64 /obj/manual_control_setpoint0
mavlink_log                0    1  8  136 /obj/mavlink_log0
parameter_update           0   22  1   40 /obj/parameter_update0
position_setpoint_triplet  0    3  1  224 /obj/position_setpoint_triplet0
rate_ctrl_status           0    0  1   24 /obj/rate_ctrl_status0
rtl_time_estimate          0    2  1   24 /obj/rtl_time_estimate0
sensor_combined            0    0  1   48 /obj/sensor_combined0
sensor_preflight_mag       0    1  1   16 /obj/sensor_preflight_mag0
sensor_selection           0    6  1   16 /obj/sensor_selection0
sensors_status_imu         0    2  1   96 /obj/sensors_status_imu0
takeoff_status             0    1  1   16 /obj/takeoff_status0
telemetry_status           0    1  1   88 /obj/telemetry_status0
transponder_report         0    2 32   80 /obj/transponder_report0
tune_control               0    0  4   24 /obj/tune_control0
vehicle_acceleration       0    1  1   32 /obj/vehicle_acceleration0
vehicle_air_data           0    5  1   40 /obj/vehicle_air_data0
vehicle_angular_velocity   0    5  1   40 /obj/vehicle_angular_velocity0
vehicle_attitude           0    6  1   56 /obj/vehicle_attitude0
vehicle_command            0    6  8   56 /obj/vehicle_command0
vehicle_control_mode       0    6  1   24 /obj/vehicle_control_mode0
vehicle_global_position    0    7  1   64 /obj/vehicle_global_position0
vehicle_gps_position       0    5  1  128 /obj/vehicle_gps_position0
vehicle_land_detected      0    5  1   24 /obj/vehicle_land_detected0
vehicle_local_position     0   17  1  168 /obj/vehicle_local_position0
vehicle_magnetometer       0    0  1   40 /obj/vehicle_magnetometer0
vehicle_odometry           0    0  1  112 /obj/vehicle_odometry0
vehicle_status             0   18  1   72 /obj/vehicle_status0
wind                       0    2  1   48 /obj/wind0

总结#

  • 大概就这样,整体的实现方案也是常见消息队列的方案,没啥特别的地方
  • 主要是不同的人在类命名上有些差异,需要先弄明白各个类实际的作用,再串起来就比较清晰了
  • 有些细节的地方后面再完善