Ardupilot自定义mavlink消息

在ardupilot\modules\mavlink\message_definitions\v1.0\commom.xml文件结尾处添加自定义消息

<!-- 20220713WP:添加一个mavlink消息 -->
    <message id="255" name="MAV_MESSAGE_TEMP_TEST">
      <description>send test message to gcs</description>
      <field type="int16_t" name="message1">message1</field>
      <field type="int16_t" name="message2">message2</field>
      <field type="int16_t" name="message3">message3</field>
      <field type="int16_t" name="message4">message4</field>
    </message>

然后基于构型编译(./waf plane),生成头文件mavlink_msg_mav_message_temp_test.h,位置为

E:\GitHub\ardupilot4.1.1\build\fmuv3\libraries\GCS_MAVLink\include\mavlink\v2.0\common

在ardupilot/libraries/GCS_MAVLink/GCS.h中的GCS_MAVLINK类下声明函数

send_mav_message_temp_test()

    // common send functions
    // 声明自定义的mavlink信息发送函数
    void send_mav_message_temp_test(void);
    void send_heartbeat(void) const;
    void send_meminfo(void);
    void send_fence_status() const;

 在GCS_Common.cpp中实现

// 发送自定义信息数据
void GCS_MAVLINK::send_mav_message_temp_test(void)
{
    //该函数自动生成,包含四个变量    
    mavlink_msg_mav_message_temp_test_send(chan, 0x0a,0x0b,0x0c,0x0d);
}

添加相对应的ap_message msg_id

ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) const
{
    static const struct {
        uint32_t mavlink_id;
        ap_message msg_id;
    } map[] {
        ...
        { MAVLINK_MSG_ID_MAV_MESSAGE_TEMP_TEST, MSG_MAV_MESSAGE_TEMP_TEST},//自定义的mavlink
        ...
            };
}

在libraries/GCS_MAVLink/ap_message.h结尾添加

enum ap_message : uint8_t {
    ...
    MSG_MAV_MESSAGE_TEMP_TEST,// 自定义的mavlink消息
    ...
};

在ardupilot/arduplane/GCS_Mavlink.cpp中的try_send_message函数的添加case调用

bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
{
    switch (id) {
    ...  
    case MSG_MAV_MESSAGE_TEMP_TEST:
        CHECK_PAYLOAD_SIZE(MAV_MESSAGE_TEMP_TEST);
        send_mav_message_temp_test();// 调用自定义的信息发送函数send_mav_message_temp_test
        gcs().send_text(MAV_SEVERITY_DEBUG, "hahahahaha !!!");
        break;
    ...
}

并在ap_message STREAM_EXTRA1_msgs[]数组中加入MSG_MAV_MESSAGE_TEMP_TEST,否则无法发送到地面站

static const ap_message STREAM_EXTRA1_msgs[] = {
    MSG_ATTITUDE,
    MSG_SIMSTATE,
    MSG_AHRS2,
    MSG_RPM,
    MSG_AOA_SSA,
    MSG_PID_TUNING,
    MSG_LANDING,
    MSG_ESC_TELEMETRY,
    MSG_EFI_STATUS,
    MSG_MAV_MESSAGE_TEMP_TEST,// 这里至关重要,否则无法正常发送到地面站,但是没搞懂为什么
};

编译,烧录固件到飞控,连接地面站(否则一直发应答包,不会发数据包,检测不到),断开,然后打开串口助手获取16进制数据,在输出的mavlink消息中寻找定义的0x0a,0x0b,0x0c,0x0d数据。

 这里看到地面站hub界面输出 “hahahahaha !!!” 字体,说明程序成功运行到自定义的case中,并发送消息到地面站了

 但是在地面站 temp 界面中的MAVLink Inspector中并没有看到新定义的mavlink消息,这里猜测是地面站选择显示的消息,故猜想需要修改地面站代码(留待以后再说)。

添加message消息的整个流程如图。

  • 3
    点赞
  • 12
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值