【类 型】:fix 更换新mavlink库解析返航点
【原 因】: 【过 程】:case MAVLINK_MSG_ID_HOME_POSITION 后面没加break 242 49都有可能进入 【影 响】:
This commit is contained in:
parent
1dff1bfd33
commit
eb9a912844
File diff suppressed because one or more lines are too long
@ -6,7 +6,8 @@
|
|||||||
/*mqtt*/
|
/*mqtt*/
|
||||||
#include "PubSubClient.h"
|
#include "PubSubClient.h"
|
||||||
/*mavlink*/
|
/*mavlink*/
|
||||||
#include "mavlink.h"
|
#include "../lib/mavlink/ardupilotmega/mavlink.h"
|
||||||
|
#include "../lib/mavlink/common/mavlink.h"
|
||||||
/*json库*/
|
/*json库*/
|
||||||
#include "ArduinoJson.h"
|
#include "ArduinoJson.h"
|
||||||
/*异步库*/
|
/*异步库*/
|
||||||
|
@ -366,26 +366,37 @@ void mavlink_receiveCallback(uint8_t c)
|
|||||||
// printf("mav_id:%d\n",msg.msgid);
|
// printf("mav_id:%d\n",msg.msgid);
|
||||||
switch (msg.msgid)
|
switch (msg.msgid)
|
||||||
{
|
{
|
||||||
case 242: // #242 返航点位置MAVLINK_MSG_ID_HOME_POSITION
|
case MAVLINK_MSG_ID_HOME_POSITION: // #242 返航点位置
|
||||||
{
|
{
|
||||||
fc.pubMQTTmsg("demo", "242");
|
char buf[120];
|
||||||
}
|
mavlink_home_position_t home_pos;
|
||||||
break;
|
mavlink_msg_home_position_decode(&msg, &home_pos);
|
||||||
case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN: // #49 本应原点信息 改过飞控固件设置 现在放的是HOME点
|
|
||||||
{
|
// 返航点经纬高
|
||||||
mavlink_gps_global_origin_t gps_org; // 解构的数据放到这个对象
|
|
||||||
mavlink_msg_gps_global_origin_decode(&msg, &gps_org); // 解构msg数据
|
|
||||||
// home点经纬高
|
|
||||||
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
||||||
gps_org.longitude,
|
home_pos.longitude, // 经度,以degE7单位传递
|
||||||
gps_org.latitude,
|
home_pos.latitude, // 纬度,以degE7单位传递
|
||||||
(double)gps_org.altitude / 1000);
|
home_pos.z); // 相对高度,单位为米
|
||||||
|
|
||||||
if (topicPubMsg[17] != buf)
|
if (topicPubMsg[17] != buf)
|
||||||
{
|
{
|
||||||
topicPubMsg[17] = buf;
|
topicPubMsg[17] = buf;
|
||||||
}
|
}
|
||||||
fc.pubMQTTmsg("demo", "49");
|
}
|
||||||
|
case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN: // #49 飞机原点
|
||||||
|
{
|
||||||
|
mavlink_gps_global_origin_t gps_org; // 解构的数据放到这个对象
|
||||||
|
mavlink_msg_gps_global_origin_decode(&msg, &gps_org); // 解构msg数据
|
||||||
|
// 原点点经纬高
|
||||||
|
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
||||||
|
gps_org.longitude,
|
||||||
|
gps_org.latitude,
|
||||||
|
(double)gps_org.altitude / 1000);
|
||||||
|
|
||||||
|
// if (topicPubMsg[x] != buf)
|
||||||
|
// {
|
||||||
|
// topicPubMsg[x] = buf;
|
||||||
|
// }
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MAVLINK_MSG_ID_HEARTBEAT: // #0: Heartbeat 心跳
|
case MAVLINK_MSG_ID_HEARTBEAT: // #0: Heartbeat 心跳
|
||||||
|
Loading…
Reference in New Issue
Block a user