【类 型】:factor 经度字段 lng 改为lon
【原 因】:和前端统一命名 【过 程】: 【影 响】:
This commit is contained in:
parent
6ecf99d19a
commit
956a258966
@ -418,7 +418,7 @@ void mavlink_receiveCallback(uint8_t c)
|
|||||||
mavlink_msg_home_position_decode(&msg, &home_pos);
|
mavlink_msg_home_position_decode(&msg, &home_pos);
|
||||||
|
|
||||||
// 返航点经纬高
|
// 返航点经纬高
|
||||||
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
sprintf(buf, "{\"lon\":%d,\"lat\":%d,\"alt\":%.2f}",
|
||||||
home_pos.longitude, // 经度,以degE7单位传递
|
home_pos.longitude, // 经度,以degE7单位传递
|
||||||
home_pos.latitude, // 纬度,以degE7单位传递
|
home_pos.latitude, // 纬度,以degE7单位传递
|
||||||
home_pos.z); // 相对高度,单位为米
|
home_pos.z); // 相对高度,单位为米
|
||||||
@ -430,7 +430,7 @@ void mavlink_receiveCallback(uint8_t c)
|
|||||||
mavlink_gps_global_origin_t gps_org; // 解构的数据放到这个对象
|
mavlink_gps_global_origin_t gps_org; // 解构的数据放到这个对象
|
||||||
mavlink_msg_gps_global_origin_decode(&msg, &gps_org); // 解构msg数据
|
mavlink_msg_gps_global_origin_decode(&msg, &gps_org); // 解构msg数据
|
||||||
// 原点点经纬高
|
// 原点点经纬高
|
||||||
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
sprintf(buf, "{\"lon\":%d,\"lat\":%d,\"alt\":%.2f}",
|
||||||
gps_org.longitude,
|
gps_org.longitude,
|
||||||
gps_org.latitude,
|
gps_org.latitude,
|
||||||
(double)gps_org.altitude / 1000);
|
(double)gps_org.altitude / 1000);
|
||||||
@ -619,7 +619,7 @@ void mavlink_receiveCallback(uint8_t c)
|
|||||||
topicPubMsg[4] = buf;
|
topicPubMsg[4] = buf;
|
||||||
}
|
}
|
||||||
// 经纬高
|
// 经纬高
|
||||||
sprintf(buf, "{\"lng\":%d,\"lat\":%d,\"alt\":%.2f}",
|
sprintf(buf, "{\"lon\":%d,\"lat\":%d,\"alt\":%.2f}",
|
||||||
global_position_int.lon,
|
global_position_int.lon,
|
||||||
global_position_int.lat,
|
global_position_int.lat,
|
||||||
(double)global_position_int.relative_alt / 1000);
|
(double)global_position_int.relative_alt / 1000);
|
||||||
|
Loading…
Reference in New Issue
Block a user