【类 型】:feat 飞控里面获取 home点的经纬高
【原 因】: 【过 程】: 【影 响】:是从id49 原本49是原点 因为娶不到id242的home点 所以从原点取的(改的飞控固件 用原点发过来的)
This commit is contained in:
parent
ee62c47558
commit
31ab4ec8b3
@ -366,6 +366,26 @@ void mavlink_receiveCallback(uint8_t c)
|
||||
// printf("mav_id:%d\n",msg.msgid);
|
||||
switch (msg.msgid)
|
||||
{
|
||||
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数据
|
||||
// 精 维 高
|
||||
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
||||
gps_org.latitude,
|
||||
gps_org.longitude,
|
||||
(double)gps_org.altitude);
|
||||
|
||||
if (topicPubMsg[17] != buf)
|
||||
{
|
||||
topicPubMsg[17] = buf;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case 242: // #242 返航点位置MAVLINK_MSG_ID_HOME_POSITION
|
||||
{
|
||||
}
|
||||
break;
|
||||
case MAVLINK_MSG_ID_HEARTBEAT: // #0: Heartbeat 心跳
|
||||
{
|
||||
mavlink_heartbeat_t heartbeat; // 解构的数据放到这个对象
|
||||
@ -504,7 +524,7 @@ void mavlink_receiveCallback(uint8_t c)
|
||||
{
|
||||
topicPubMsg[4] = buf;
|
||||
}
|
||||
// 海拔高度
|
||||
// 经纬 海拔高度
|
||||
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
||||
global_position_int.lon,
|
||||
global_position_int.lat,
|
||||
@ -517,28 +537,6 @@ void mavlink_receiveCallback(uint8_t c)
|
||||
}
|
||||
break;
|
||||
|
||||
case 242: // #242 返航点位置MAVLINK_MSG_ID_HOME_POSITION
|
||||
{
|
||||
fc.pubMQTTmsg("demo", "homep");
|
||||
// mavlink_home_position_t home_position;
|
||||
// mavlink_msg_home_position_decode(&msg, &home_position);
|
||||
|
||||
// // 提取经纬度并转换为度数
|
||||
// double latitude = home_position.latitude / 1e7;
|
||||
// double longitude = home_position.longitude / 1e7;
|
||||
|
||||
// // 格式化为 JSON 字符串,包含经纬度
|
||||
// sprintf(buf, "{\"lng\":%.7f,\"lat\":%.7f}",
|
||||
// longitude, latitude);
|
||||
|
||||
// // 更新 topicPubMsg 中的相关字段
|
||||
// if (topicPubMsg[17] != buf)
|
||||
// {
|
||||
// topicPubMsg[17] = buf;
|
||||
// }
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_STATUSTEXT: // #253 文本信息
|
||||
{
|
||||
char buf[51]; // 定义一个局部缓冲区,大小为 51
|
||||
|
Loading…
Reference in New Issue
Block a user