mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_GPS: added get_lag method to return expected lag from the GPS.
This commit is contained in:
parent
30aa104000
commit
50a97f3092
@ -35,6 +35,8 @@ public:
|
|||||||
static const prog_char _ublox_set_binary[];
|
static const prog_char _ublox_set_binary[];
|
||||||
static const uint8_t _ublox_set_binary_size;
|
static const uint8_t _ublox_set_binary_size;
|
||||||
|
|
||||||
|
float get_lag() { return 0.5; } // ublox lag is lower than the default 1second
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// u-blox UBX protocol essentials
|
// u-blox UBX protocol essentials
|
||||||
// XXX this is being ignored by the compiler #pragma pack(1)
|
// XXX this is being ignored by the compiler #pragma pack(1)
|
||||||
|
@ -135,6 +135,8 @@ public:
|
|||||||
return _last_ground_speed_cm * 0.01;
|
return _last_ground_speed_cm * 0.01;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// the expected lag (in seconds) in the position and velocity readings from the gps
|
||||||
|
virtual float get_lag() { return 1.0; }
|
||||||
|
|
||||||
// the time we got our last fix in system milliseconds
|
// the time we got our last fix in system milliseconds
|
||||||
uint32_t last_fix_time;
|
uint32_t last_fix_time;
|
||||||
|
Loading…
Reference in New Issue
Block a user