AP_GPS: added last_message_time_ms() API

used to help GPS logging
This commit is contained in:
Andrew Tridgell 2013-04-28 14:53:02 +10:00
parent f5d062d5ba
commit 786e4cf705
1 changed files with 3 additions and 0 deletions

View File

@ -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