mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 01:44:00 -04:00
AP_GPS: Broadcast vDOP data over mavlink
This commit is contained in:
parent
0e3a188f6f
commit
9f02834f6d
@ -551,7 +551,7 @@ AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
|
|||||||
loc.lng, // in 1E7 degrees
|
loc.lng, // in 1E7 degrees
|
||||||
loc.alt * 10UL, // in mm
|
loc.alt * 10UL, // in mm
|
||||||
get_hdop(0),
|
get_hdop(0),
|
||||||
65535,
|
get_vdop(0),
|
||||||
ground_speed(0)*100, // cm/s
|
ground_speed(0)*100, // cm/s
|
||||||
ground_course_cd(0), // 1/100 degrees,
|
ground_course_cd(0), // 1/100 degrees,
|
||||||
num_sats(0));
|
num_sats(0));
|
||||||
@ -580,7 +580,7 @@ AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
|||||||
loc.lng,
|
loc.lng,
|
||||||
loc.alt * 10UL,
|
loc.alt * 10UL,
|
||||||
get_hdop(1),
|
get_hdop(1),
|
||||||
65535,
|
get_vdop(1),
|
||||||
ground_speed(1)*100, // cm/s
|
ground_speed(1)*100, // cm/s
|
||||||
ground_course_cd(1), // 1/100 degrees,
|
ground_course_cd(1), // 1/100 degrees,
|
||||||
num_sats(1),
|
num_sats(1),
|
||||||
|
@ -282,6 +282,14 @@ public:
|
|||||||
return get_hdop(primary_instance);
|
return get_hdop(primary_instance);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// vertical dilution of precision
|
||||||
|
uint16_t get_vdop(uint8_t instance) const {
|
||||||
|
return _GPS_STATE(instance).vdop;
|
||||||
|
}
|
||||||
|
uint16_t get_vdop() const {
|
||||||
|
return get_vdop(primary_instance);
|
||||||
|
}
|
||||||
|
|
||||||
// the time we got our last fix in system milliseconds. This is
|
// the time we got our last fix in system milliseconds. This is
|
||||||
// used when calculating how far we might have moved since that fix
|
// used when calculating how far we might have moved since that fix
|
||||||
uint32_t last_fix_time_ms(uint8_t instance) const {
|
uint32_t last_fix_time_ms(uint8_t instance) const {
|
||||||
|
Loading…
Reference in New Issue
Block a user