mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: Rebase to Master
This commit is contained in:
parent
88957235d2
commit
94d1cb3dcf
@ -3637,6 +3637,22 @@ function rtc:date_fields_to_clock_s(year, month, day, hour, min, sec) end
|
|||||||
---@return integer|nil -- weekday 0-6, sunday is 0
|
---@return integer|nil -- weekday 0-6, sunday is 0
|
||||||
function rtc:clock_s_to_date_fields(param1) end
|
function rtc:clock_s_to_date_fields(param1) end
|
||||||
|
|
||||||
|
-- desc
|
||||||
|
-- fills in year, month, day, hour, min, sec and ms from internal RTC
|
||||||
|
-- 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
|
||||||
|
-- values are nil if there is no valid time source
|
||||||
|
-- usage : year, month, day, hour, min, sec, ms = rtc:get_date_and_time_utc()
|
||||||
|
---@return integer|nil -- year
|
||||||
|
---@return integer|nil -- month 0-11
|
||||||
|
---@return integer|nil -- day
|
||||||
|
---@return integer|nil -- hour
|
||||||
|
---@return integer|nil -- minute
|
||||||
|
---@return integer|nil -- second
|
||||||
|
---@return integer|nil -- millisecond
|
||||||
|
function rtc:get_date_and_time_utc() end
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
fs = {}
|
fs = {}
|
||||||
|
|
||||||
|
20
libraries/AP_Scripting/examples/utc_datetime.lua
Normal file
20
libraries/AP_Scripting/examples/utc_datetime.lua
Normal file
@ -0,0 +1,20 @@
|
|||||||
|
-- Get UTC date and Time from the HAL
|
||||||
|
-- You can set BRD_RTC_TYPE for the acceptable time sources (GPS, GCS, Hardware)
|
||||||
|
|
||||||
|
-- rtc:get_date_and_time_utc()
|
||||||
|
-- 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), ms is 0~999
|
||||||
|
-- values are nil if there is no valid time source
|
||||||
|
|
||||||
|
function update()
|
||||||
|
|
||||||
|
year, month, day, hour, min, sec, ms = rtc:get_date_and_time_utc()
|
||||||
|
if year ~= nil then
|
||||||
|
gcs:send_text(0,string.format("%i %i %i %i:%i:%i:%i", year, month, day, hour, min, sec, ms))
|
||||||
|
end
|
||||||
|
|
||||||
|
|
||||||
|
return update, 1000
|
||||||
|
end
|
||||||
|
|
||||||
|
return update()
|
@ -964,6 +964,7 @@ singleton AP_RTC depends AP_RTC_ENABLED
|
|||||||
singleton AP_RTC rename rtc
|
singleton AP_RTC rename rtc
|
||||||
singleton AP_RTC method clock_s_to_date_fields boolean uint32_t'skip_check uint16_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null
|
singleton AP_RTC method clock_s_to_date_fields boolean uint32_t'skip_check uint16_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null
|
||||||
singleton AP_RTC method date_fields_to_clock_s uint32_t uint16_t'skip_check int8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check
|
singleton AP_RTC method date_fields_to_clock_s uint32_t uint16_t'skip_check int8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check
|
||||||
|
singleton AP_RTC method get_date_and_time_utc boolean uint16_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint16_t'Null
|
||||||
|
|
||||||
include AP_Networking/AP_Networking.h depends AP_NETWORKING_ENABLED
|
include AP_Networking/AP_Networking.h depends AP_NETWORKING_ENABLED
|
||||||
include AP_Networking/AP_Networking_Config.h
|
include AP_Networking/AP_Networking_Config.h
|
||||||
|
Loading…
Reference in New Issue
Block a user