Your method of setting a parameter is incorrect (and probably misled, since a parameter with the current time is rather strange…).
See here for the proper way to initiate a custom parameter via Lua.
The following series of functions and snippets may prove useful regarding real-world time calculations in ArduPilot Lua. Note, I have not thoroughly tested any of it, but it seems to work ok in SITL.
-- ported to Lua from https://gwosc.org/static/js/gpstimeutil.js
-- Yuri - Oct 2023
local LOCAL_TIMEZONE_OFFSET = -5
local MONTH_NAMES = { 'Jan', 'Feb', 'Mar', 'Apr', 'May', 'Jun',
'Jul', 'Aug', 'Sep', 'Oct', 'Nov', 'Dec' }
local LEAP_SECONDS = { 46828800, 78364801, 109900802, 173059203, 252028804,
315187205, 346723206, 393984007, 425520008, 457056009, 504489610,
551750411, 599184012, 820108813, 914803214, 1025136015, 1119744016,
1167264017 }
-- test to see if a GPS second is a leap second
local function isleap(gpsTimeSeconds)
for _, leap in ipairs(LEAP_SECONDS) do
if (gpsTimeSeconds == leap) then return true end
end
return false
end
-- count number of leap seconds that have passed
local function countleaps(gpsTimeSeconds, accum_leaps)
local nleaps = 0
if (accum_leaps) then
for i, leap in ipairs(LEAP_SECONDS) do
if (gpsTimeSeconds + i - 1 >= leap) then
nleaps = nleaps + 1
end
end
else
for _, leap in ipairs(LEAP_SECONDS) do
if (gpsTimeSeconds >= leap) then
nleaps = nleaps + 1
end
end
end
return nleaps
end
-- convert GPS Time to Unix Time
local function gps2unix(gpsTimeSeconds)
local fpart = gpsTimeSeconds % 1
local ipart = math.floor(gpsTimeSeconds)
local unixTimeSeconds = ipart + 315964800 - countleaps(ipart, false)
if isleap(ipart + 1) then
unixTimeSeconds = unixTimeSeconds + fpart / 2
elseif isleap(ipart) then
unixTimeSeconds = unixTimeSeconds + (fpart + 1) / 2
else
unixTimeSeconds = unixTimeSeconds + fpart
end
return unixTimeSeconds
end
local function unix2str(unixTimeSeconds, tz_offset)
local epoch = 946684800 -- January 1, 2000, 00:00:00 (UTC)
local secondsInDay = 86400
local offset = tz_offset or 0 -- default to UTC if tz_offset not specified
unixTimeSeconds = unixTimeSeconds + offset * 3600
local days = math.floor((unixTimeSeconds - epoch) / secondsInDay)
local secondsLeft = (unixTimeSeconds - epoch) % secondsInDay
local year = 2000
local month, day = 1, 1
while true do
local daysInMonth = 31
if month == 4 or month == 6 or month == 9 or month == 11 then
daysInMonth = 30
elseif month == 2 then
if year % 4 == 0 and (year % 100 ~= 0 or year % 400 == 0) then
daysInMonth = 29
else
daysInMonth = 28
end
end
if days >= daysInMonth then
days = days - daysInMonth
month = month + 1
else
day = days + 1
break
end
if month > 12 then
month = 1
year = year + 1
end
end
local hours = math.floor(secondsLeft / 3600)
local minutes = math.floor((secondsLeft % 3600) / 60)
local seconds = secondsLeft % 60
local tz = 'UTC'
if offset > 0 then tz = ('%s+%.1f'):format(tz, offset) end
if offset < 0 then tz = ('%s%.1f'):format(tz, offset) end
return ('%02d %s %04d %02d:%02d:%02d %s'):format(day, MONTH_NAMES[month], year, hours, minutes, seconds, tz)
end
local function getGpsTimeSeconds() -- in seconds
local SECONDS_IN_WEEK = 604800
return gps:time_week(0) * SECONDS_IN_WEEK + tonumber(tostring(gps:time_week_ms(0))) / 1000
end
function update()
local utc = gps2unix(getGpsTimeSeconds())
gcs:send_text(6, unix2str(utc))
gcs:send_text(6, unix2str(utc, LOCAL_TIMEZONE_OFFSET))
return update, 1000
end
return update()