mirror of https://github.com/ArduPilot/ardupilot
AP_RTC: tighten types on get_system_clock_utc
None of these components should ever be negative - given its source is only ever seconds-since-epoch.
This commit is contained in:
parent
4492c09b3b
commit
46c880089c
|
@ -72,7 +72,7 @@ bool AP_RTC::get_utc_usec(uint64_t &usec) const
|
|||
return true;
|
||||
}
|
||||
|
||||
bool AP_RTC::get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &sec, int32_t &ms)
|
||||
bool AP_RTC::get_system_clock_utc(uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms)
|
||||
{
|
||||
// get time of day in ms
|
||||
uint64_t time_ms = 0;
|
||||
|
@ -115,7 +115,8 @@ uint32_t AP_RTC::get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms
|
|||
}
|
||||
|
||||
// get start_time_ms as h, m, s, ms
|
||||
int32_t curr_hour, curr_min, curr_sec, curr_ms;
|
||||
uint8_t curr_hour, curr_min, curr_sec;
|
||||
uint16_t curr_ms;
|
||||
if (!get_system_clock_utc(curr_hour, curr_min, curr_sec, curr_ms)) {
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -37,7 +37,7 @@ public:
|
|||
/*
|
||||
get time in UTC hours, minutes, seconds and milliseconds
|
||||
*/
|
||||
bool get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &sec, int32_t &ms);
|
||||
bool get_system_clock_utc(uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms);
|
||||
|
||||
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms);
|
||||
|
||||
|
|
|
@ -70,7 +70,8 @@ void loop(void)
|
|||
}
|
||||
{ // generally make sure time is moving forward / initial time
|
||||
// offset looks right
|
||||
int32_t hour, min, sec, ms;
|
||||
uint8_t hour, min, sec;
|
||||
uint16_t ms;
|
||||
if (!rtc.get_system_clock_utc(hour, min, sec, ms)) {
|
||||
failed("Failed to get hour/min/sec/ms");
|
||||
return;
|
||||
|
|
Loading…
Reference in New Issue