mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_Compass: Enable usec timestamps to be retrieved for specified instance
This commit is contained in:
parent
42b47acdfc
commit
6698d4379d
@ -293,6 +293,7 @@ public:
|
||||
|
||||
// return last update time in microseconds
|
||||
uint32_t last_update_usec(void) const { return _state[get_primary()].last_update_usec; }
|
||||
uint32_t last_update_usec(uint8_t i) const { return _state[i].last_update_usec; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user