mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: added last_message_time_ms() API
used to help GPS logging
This commit is contained in:
parent
f5d062d5ba
commit
786e4cf705
|
@ -148,6 +148,9 @@ public:
|
|||
// the time we got our last fix in system milliseconds
|
||||
uint32_t last_fix_time;
|
||||
|
||||
// the time we last processed a message in milliseconds
|
||||
uint32_t last_message_time_ms(void) { return _idleTimer; }
|
||||
|
||||
// return true if the GPS supports raw velocity values
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue