mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 14:38:44 -04:00
AP_HAL: Add system_time_was_set
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
17a0f6c3be
commit
a5c7303cd3
@ -101,6 +101,11 @@ void AP_HAL::Util::get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &se
|
||||
hour = hour_ms / (60 * 60 * 1000);
|
||||
}
|
||||
|
||||
bool AP_HAL::Util::system_time_was_set() const
|
||||
{
|
||||
return _system_time_was_set;
|
||||
}
|
||||
|
||||
// get milliseconds from now to a target time of day expressed as hour, min, sec, ms
|
||||
// match starts from first value that is not -1. I.e. specifying hour=-1, minutes=10 will ignore the hour and return time until 10 minutes past 12am (utc)
|
||||
uint32_t AP_HAL::Util::get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms) const
|
||||
|
@ -45,6 +45,11 @@ public:
|
||||
*/
|
||||
virtual void set_system_clock(uint64_t time_utc_usec) {}
|
||||
|
||||
/*
|
||||
check if system clock was already set
|
||||
*/
|
||||
bool system_time_was_set() const;
|
||||
|
||||
/*
|
||||
get system clock in UTC milliseconds
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user