mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
AP_GPS: make time_epoch_usec const
This commit is contained in:
parent
db7c8439c6
commit
7f59279670
@ -346,7 +346,7 @@ uint64_t AP_GPS::time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
|
||||
/**
|
||||
calculate current time since the unix epoch in microseconds
|
||||
*/
|
||||
uint64_t AP_GPS::time_epoch_usec(uint8_t instance)
|
||||
uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const
|
||||
{
|
||||
const GPS_State &istate = state[instance];
|
||||
if (istate.last_gps_time_ms == 0) {
|
||||
|
@ -373,8 +373,8 @@ public:
|
||||
void send_blob_update(uint8_t instance);
|
||||
|
||||
// return last fix time since the 1/1/1970 in microseconds
|
||||
uint64_t time_epoch_usec(uint8_t instance);
|
||||
uint64_t time_epoch_usec(void) {
|
||||
uint64_t time_epoch_usec(uint8_t instance) const;
|
||||
uint64_t time_epoch_usec(void) const {
|
||||
return time_epoch_usec(primary_instance);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user