mirror of https://github.com/ArduPilot/ardupilot
AP_RTC: get-date-and-time returns milliseconds
This commit is contained in:
parent
4b96c2f568
commit
b5cbefc43a
|
@ -206,8 +206,8 @@ uint32_t AP_RTC::get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms
|
||||||
}
|
}
|
||||||
|
|
||||||
// get date and time. Returns true on success and fills in year, month, day, hour, min, sec and ms
|
// get date and time. Returns true on success and fills in year, month, day, hour, min, sec and ms
|
||||||
// year is the regular Gregorian year, month is 0~11, day is 1~31, hour is 0~23, minute is 0~59, second is 0~60 (1 leap second)
|
// year is the regular Gregorian year, month is 0~11, day is 1~31, hour is 0~23, minute is 0~59, second is 0~60 (1 leap second), ms is 0~999
|
||||||
bool AP_RTC::get_date_and_time_utc(uint16_t& year, uint8_t& month, uint8_t& day, uint8_t &hour, uint8_t &min, uint8_t &sec) const
|
bool AP_RTC::get_date_and_time_utc(uint16_t& year, uint8_t& month, uint8_t& day, uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms) const
|
||||||
{
|
{
|
||||||
// get local time of day in ms
|
// get local time of day in ms
|
||||||
uint64_t time_us = 0;
|
uint64_t time_us = 0;
|
||||||
|
@ -225,6 +225,7 @@ bool AP_RTC::get_date_and_time_utc(uint16_t& year, uint8_t& month, uint8_t& day,
|
||||||
hour = tm->tm_hour; /* Hours. [0-23] */
|
hour = tm->tm_hour; /* Hours. [0-23] */
|
||||||
min = tm->tm_min; /* Minutes. [0-59] */
|
min = tm->tm_min; /* Minutes. [0-59] */
|
||||||
sec = tm->tm_sec; /* Seconds. [0-60] (1 leap second) */
|
sec = tm->tm_sec; /* Seconds. [0-60] (1 leap second) */
|
||||||
|
ms = time_us / 1000U; /* milliseconds [0-999] */
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -45,8 +45,8 @@ public:
|
||||||
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms);
|
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms);
|
||||||
|
|
||||||
// get date and time. Returns true on success and fills in year, month, day, hour, min, sec and ms
|
// get date and time. Returns true on success and fills in year, month, day, hour, min, sec and ms
|
||||||
// year is the regular Gregorian year, month is 0~11, day is 1~31, hour is 0~23, minute is 0~59, second is 0~60 (1 leap second)
|
// year is the regular Gregorian year, month is 0~11, day is 1~31, hour is 0~23, minute is 0~59, second is 0~60 (1 leap second), ms is 0~999
|
||||||
bool get_date_and_time_utc(uint16_t& year, uint8_t& month, uint8_t& day, uint8_t &hour, uint8_t &min, uint8_t &sec) const;
|
bool get_date_and_time_utc(uint16_t& year, uint8_t& month, uint8_t& day, uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms) const;
|
||||||
|
|
||||||
// get singleton instance
|
// get singleton instance
|
||||||
static AP_RTC *get_singleton() {
|
static AP_RTC *get_singleton() {
|
||||||
|
|
Loading…
Reference in New Issue