【first_try】audupilot自定义mavlink消息 与地面站通信
固件版本:ardupilot Plane4.1。
Ardupilot 部分代码修改
修改commom.xml
在 modules/mavlink/message_definitions/v1.0/common.xml 中添加 代码片1 内容:(注意不能和其他ID冲突)
代码片1
<message id="390" name="AVOID_TRY">
<description>receive the avoid data from Missionplanner.</description>
<field type="float" name="roll" units="rad">Roll angle (-pi..+pi).</field>
<field type="float" name="pitch" units="rad">Pitch angle (-pi..+pi)</field>
<field type="float" name="yaw" units="rad">Yaw angle (-pi..+pi)</field>
<field type="float" name="rollspeed" units="rad/s">Roll angular speed</field>
<field type="float" name="pitchspeed" units="rad/s">Pitch angular speed</field>
<field type="float" name="yawspeed" units="rad/s">Yaw angular speed</field>
</message>
更新mavlink消息
在modules/mavlink文件夹下,终端运行
python mavgenerate.py
运行结果如下图
XML 中选择上文中提到的 common.xml
Out 选择自己的数据路径
Language 选择 C
Protocol 如果id超过了150,那选择2.0
Generate进行输出
共得到2个文件夹**(common 和 minimal),7个.h头文件(图中的7个.h文件)**,如下图所示
将得到的文件复制到 build/mini-pix/lirbraries/GCS_MAVlink/include/mavlink/v2.0 中。
MavLink数据接收
在 GCS_Mavlink.cpp 中,handleMessage增添相应case:
case MAVLINK_MSG_ID_AVOID_TRY:
{
mavlink_avoid_try_t avoid_data_t;
mavlink_msg_avoid_try_decode(&msg,&avoid_data_t);
break;
}
读取相应数据。编译通过无报错。
MavLink数据发送
在 GCS_Common.cpp 中添加函数,并且在 try_sned_message 函数中的 case MEG_HEARTBEAT 中添加该函数(搭顺风车)
void GCS_MAVLINK :: send_avoid() const
{
mavlink_msg_avoid_try_send(参数);
}
借鉴博文:https://blog.ztluo.dev/post/0040-gen-new-mavlink-msg/
MissionPlanner 部分代码修改
在 ExtLibs\Mavlink\message_definitions 中找到 common.xml 文件,同样增加上述 代码片1修改内容,保存。
使用 ExtLibs\Mavlink 中 regenerate.bat (需要python2.7环境)进行更新,运行结束后会重新生成并更新 Mavlink.cs 。
与之前相比较,增加的部分如下所示:
new message_info(390, "AVOID_TRY", 29, 24, 24, typeof( mavlink_avoid_try_t )),
AVOID_TRY = 390,
/// extensions_start 0
[StructLayout(LayoutKind.Sequential,Pack=1,Size=24)]
///<summary> receive the avoid data from Missionplanner. </summary>
public struct mavlink_avoid_try_t
{
public mavlink_avoid_try_t(float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed)
{
this.roll = roll;
this.pitch = pitch;
this.yaw = yaw;
this.rollspeed = rollspeed;
this.pitchspeed = pitchspeed;
this.yawspeed = yawspeed;
}
/// <summary>Roll angle (-pi..+pi). [rad] </summary>
[Units("[rad]")]
[Description("Roll angle (-pi..+pi).")]
public float roll;
/// <summary>Pitch angle (-pi..+pi) [rad] </summary>
[Units("[rad]")]
[Description("Pitch angle (-pi..+pi)")]
public float pitch;
/// <summary>Yaw angle (-pi..+pi) [rad] </summary>
[Units("[rad]")]
[Description("Yaw angle (-pi..+pi)")]
public float yaw;
/// <summary>Roll angular speed [rad/s] </summary>
[Units("[rad/s]")]
[Description("Roll angular speed")]
public float rollspeed;
/// <summary>Pitch angular speed [rad/s] </summary>
[Units("[rad/s]")]
[Description("Pitch angular speed")]
public float pitchspeed;
/// <summary>Yaw angular speed [rad/s] </summary>
[Units("[rad/s]")]
[Description("Yaw angular speed")]
public float yawspeed;
};
消息发送方法:以 FlightData.cs 中发送避障部分数据为例说明
private MAVLinkInterface mav_aovid;//定义发送变量
mav_aovid.sendPacket(new MAVLink.mavlink_avoid_try_t()
{
roll = MainV2.tcpServerParse.data1,
pitch = MainV2.tcpServerParse.data2,
yaw = MainV2.tcpServerParse.data3,
rollspeed = MainV2.tcpServerParse.data4,
pitchspeed = MainV2.tcpServerParse.data5,
yawspeed = MainV2.tcpServerParse.data6
}, 255, 190);//通过mavlink进行发送 sysid和compid使用和心跳包一样的数值,不知会有什么影响
消息接收方法:在 CurrentState.cs 中添加如下内容
public static float avoid_receive = 0;
private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLinkMessage)该函数中添加以下case
case (uint)MAVLink.MAVLINK_MSG_ID.AVOID_TRY:
{
var avoiddata = mavLinkMessage.ToStructure<MAVLink.mavlink_avoid_try_t>();
avoid_receive = avoiddata.distance;
avoid_try = avoid_receive;
}
break;
之后就可以调用 avoid_receive 变量进行使用,还能进行快速变量浏览。例如
[DisplayText("avoid (meters)")]
public float avoid_try
{
get ;
set ;
}
借鉴博文:https://blog.csdn.net/MengHuanXinZuo/article/details/106387770