MAVLink消息

官网英文原文地址:https://dev.px4.io/mavlink-messaging.html

所有消息的概述可以在这里找到.

这篇教程是假设你已经在 msg/ca_trajectory.msg 有了一个自定义uORB ca_trajectory
消息,并且在 mavlink/include/mavlink/v1.0/custom_messages/mavlink_msg_ca_trajectory.h 有了一个自定义mavlink
ca_trajectory 消息(点击此处查看如何建立一个自定义mavlink消息以及头文件)。

这部分介绍如何使用一个自定义uORB消息并且作为mavlink消息发送。
添加mavlink的头文件和uorb消息到mavlink_messages.cpp

  1. #include <uORB/topics/ca_trajectory.h>
  2. #include <v1.0/custom_messages/mavlink_msg_ca_trajectory.h>

mavlink_messages.cpp中创建一个新的类

  1. class MavlinkStreamCaTrajectory : public MavlinkStream
  2. {
  3. public:
  4. const char *get_name() const
  5. {
  6. return MavlinkStreamCaTrajectory::get_name_static();
  7. }
  8. static const char *get_name_static()
  9. {
  10. return "CA_TRAJECTORY";
  11. }
  12. static uint8_t get_id_static()
  13. {
  14. return MAVLINK_MSG_ID_CA_TRAJECTORY;
  15. }
  16. uint8_t get_id()
  17. {
  18. return get_id_static();
  19. }
  20. static MavlinkStream *new_instance(Mavlink *mavlink)
  21. {
  22. return new MavlinkStreamCaTrajectory(mavlink);
  23. }
  24. unsigned get_size()
  25. {
  26. return MAVLINK_MSG_ID_CA_TRAJECTORY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
  27. }
  28. private:
  29. MavlinkOrbSubscription *_sub;
  30. uint64_t _ca_traj_time;
  31. /* do not allow top copying this class */
  32. MavlinkStreamCaTrajectory(MavlinkStreamCaTrajectory &);
  33. MavlinkStreamCaTrajectory& operator = (const MavlinkStreamCaTrajectory &);
  34. protected:
  35. explicit MavlinkStreamCaTrajectory(Mavlink *mavlink) : MavlinkStream(mavlink),
  36. _sub(_mavlink->add_orb_subscription(ORB_ID(ca_trajectory))), // make sure you enter the name of your uorb topic here
  37. _ca_traj_time(0)
  38. {}
  39. void send(const hrt_abstime t)
  40. {
  41. struct ca_trajectory_s _ca_trajectory; //make sure ca_trajectory_s is the definition of your uorb topic
  42. if (_sub->update(&_ca_traj_time, &_ca_trajectory)) {
  43. mavlink_ca_trajectory_t msg;//make sure mavlink_ca_trajectory_t is the definition of your custom mavlink message
  44. msg.timestamp = _ca_trajectory.timestamp;
  45. msg.time_start_usec = _ca_trajectory.time_start_usec;
  46. msg.time_stop_usec = _ca_trajectory.time_stop_usec;
  47. msg.coefficients =_ca_trajectory.coefficients;
  48. msg.seq_id = _ca_trajectory.seq_id;
  49. mavlink_msg_ca_trajectory_send_struct(_mavlink->get_channel(), &msg);
  50. }
  51. }
  52. };

最后附加流类streams_list的到mavlink_messages.cpp底部

  1. StreamListItem *streams_list[] = {
  2. ...
  3. new StreamListItem(&MavlinkStreamCaTrajectory::new_instance, &MavlinkStreamCaTrajectory::get_name_static),
  4. nullptr
  5. };

然后确保启用流,例如通过在启动脚本中添加以下行(-r配置流速率,-u标识UDP端口14556上的mavlink通道):

  1. mavlink stream -r 50 -s CA_TRAJECTORY -u 14556

这部分解释如何通过mavlink接收消息并将其发布到uORB。

mavlink_receiver.h中增加一个用来处理接收信息得函数

  1. #include <uORB/topics/ca_trajectory.h>
  2. #include <v1.0/custom_messages/mavlink_msg_ca_trajectory.h>

mavlink_receiver.h中增加一个处理类MavlinkReceiver 中的输入mavlink消息的函数

  1. void handle_message_ca_trajectory_msg(mavlink_message_t *msg);

mavlink_receiver.h中加入一个类MavlinkReceiver中的uORB消息发布者

  1. orb_advert_t _ca_traj_msg_pub;

mavlink_receiver.cpp中实现handle_message_ca_trajectory_msg功能

  1. void
  2. MavlinkReceiver::handle_message_ca_trajectory_msg(mavlink_message_t *msg)
  3. {
  4. mavlink_ca_trajectory_t traj;
  5. mavlink_msg_ca_trajectory_decode(msg, &traj);
  6. struct ca_trajectory_s f;
  7. memset(&f, 0, sizeof(f));
  8. f.timestamp = hrt_absolute_time();
  9. f.seq_id = traj.seq_id;
  10. f.time_start_usec = traj.time_start_usec;
  11. f.time_stop_usec = traj.time_stop_usec;
  12. for(int i=0;i<28;i++)
  13. f.coefficients[i] = traj.coefficients[i];
  14. if (_ca_traj_msg_pub == nullptr) {
  15. _ca_traj_msg_pub = orb_advertise(ORB_ID(ca_trajectory), &f);
  16. } else {
  17. orb_publish(ORB_ID(ca_trajectory), _ca_traj_msg_pub, &f);
  18. }
  19. }

最后确定函数在MavlinkReceiver::handle_message()中被调用

  1. MavlinkReceiver::handle_message(mavlink_message_t *msg)
  2. {
  3. switch (msg->msgid) {
  4. ...
  5. case MAVLINK_MSG_ID_CA_TRAJECTORY:
  6. handle_message_ca_trajectory_msg(msg);
  7. break;
  8. ...
  9. }

一般情况

设置流速率

有时,增加单个主题的流速率(例如,为例在QGC中检查)是有用的。这可以通过下面这行代码来实现

  1. mavlink stream -u <port number> -s <mavlink topic name> -r <rate>

你可以通过mavlink status找到端口号,相应地将输出(在其他消息之间)transport protocol: UDP (<port number>)。例如你可能得到

  1. mavlink stream -u 14556 -s OPTICAL_FLOW_RAD -r 300