mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_GPS: populate extension fields in GPS2_RAW
This commit is contained in:
parent
9cc883a8c0
commit
a7e0c565dc
@ -1285,6 +1285,12 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
|
|
||||||
const Location &loc = location(1);
|
const Location &loc = location(1);
|
||||||
|
float hacc = 0.0f;
|
||||||
|
float vacc = 0.0f;
|
||||||
|
float sacc = 0.0f;
|
||||||
|
horizontal_accuracy(1, hacc);
|
||||||
|
vertical_accuracy(1, vacc);
|
||||||
|
speed_accuracy(1, sacc);
|
||||||
mavlink_msg_gps2_raw_send(
|
mavlink_msg_gps2_raw_send(
|
||||||
chan,
|
chan,
|
||||||
last_fix_time_ms(1)*(uint64_t)1000,
|
last_fix_time_ms(1)*(uint64_t)1000,
|
||||||
@ -1299,7 +1305,12 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
|||||||
num_sats(1),
|
num_sats(1),
|
||||||
state[1].rtk_num_sats,
|
state[1].rtk_num_sats,
|
||||||
state[1].rtk_age_ms,
|
state[1].rtk_age_ms,
|
||||||
gps_yaw_cdeg(1));
|
gps_yaw_cdeg(1),
|
||||||
|
0, // TODO: Elipsoid height in mm
|
||||||
|
hacc * 1000, // one-sigma standard deviation in mm
|
||||||
|
vacc * 1000, // one-sigma standard deviation in mm
|
||||||
|
sacc * 1000, // one-sigma standard deviation in mm/s
|
||||||
|
0); // TODO one-sigma heading accuracy standard deviation
|
||||||
}
|
}
|
||||||
#endif // GPS_MAX_RECEIVERS
|
#endif // GPS_MAX_RECEIVERS
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user