mirror of https://github.com/ArduPilot/ardupilot
AP_RTC: add local time support
This commit is contained in:
parent
d3d4dff9ba
commit
1821fc9594
|
@ -28,6 +28,13 @@ const AP_Param::GroupInfo AP_RTC::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("_TYPES", 1, AP_RTC, allowed_types, 1),
|
||||
|
||||
// @Param: _TZ_MIN
|
||||
// @DisplayName: Timezone offset from UTC
|
||||
// @Description: Adds offset in +- minutes from UTC to calculate local time
|
||||
// @Range: -720 +840
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_TZ_MIN", 2, AP_RTC, tz_min, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -102,6 +109,31 @@ bool AP_RTC::get_system_clock_utc(uint8_t &hour, uint8_t &min, uint8_t &sec, uin
|
|||
return true;
|
||||
}
|
||||
|
||||
bool AP_RTC::get_local_time(uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms)
|
||||
{
|
||||
// get local time of day in ms
|
||||
uint64_t time_ms = 0;
|
||||
uint64_t ms_local = 0;
|
||||
if (!get_utc_usec(time_ms)) {
|
||||
return false;
|
||||
}
|
||||
time_ms /= 1000U;
|
||||
ms_local = time_ms + (tz_min * 60000);
|
||||
|
||||
// separate time into ms, sec, min, hour and days but all expressed in milliseconds
|
||||
ms = ms_local % 1000;
|
||||
uint32_t sec_ms = (ms_local % (60 * 1000)) - ms;
|
||||
uint32_t min_ms = (ms_local % (60 * 60 * 1000)) - sec_ms - ms;
|
||||
uint32_t hour_ms = (ms_local % (24 * 60 * 60 * 1000)) - min_ms - sec_ms - ms;
|
||||
|
||||
// convert times as milliseconds into appropriate units
|
||||
sec = sec_ms / 1000;
|
||||
min = min_ms / (60 * 1000);
|
||||
hour = hour_ms / (60 * 60 * 1000);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// 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
|
||||
|
|
|
@ -13,6 +13,7 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
AP_Int8 allowed_types;
|
||||
AP_Int16 tz_min;
|
||||
|
||||
// ordering is important in source_type; lower-numbered is
|
||||
// considered a better time source. These values are documented
|
||||
|
@ -38,6 +39,8 @@ public:
|
|||
get time in UTC hours, minutes, seconds and milliseconds
|
||||
*/
|
||||
bool get_system_clock_utc(uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms);
|
||||
|
||||
bool get_local_time(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);
|
||||
|
||||
|
|
Loading…
Reference in New Issue