AP_Scripting: Fixup examples for mavlink receive timestamp as uint32

This commit is contained in:
Iampete1 2023-06-20 22:32:56 +01:00 committed by Andrew Tridgell
parent ceca374f23
commit 87b2000d5c
2 changed files with 3 additions and 3 deletions

View File

@ -2308,9 +2308,9 @@ local function mavlink_receiver()
local msg,_,timestamp_ms = mavlink.receive_chan()
if msg then
local parsed_msg = mavlink_msgs.decode(msg, msg_map)
if parsed_msg.msgid == NAMED_VALUE_FLOAT_msgid then
if (parsed_msg ~= nil) and (parsed_msg.msgid == NAMED_VALUE_FLOAT_msgid) then
-- convert remote timestamp to local timestamp with jitter correction
local time_boot_ms = jitter_correction.correct_offboard_timestamp_msec(parsed_msg.time_boot_ms, timestamp_ms)
local time_boot_ms = jitter_correction.correct_offboard_timestamp_msec(parsed_msg.time_boot_ms, timestamp_ms:toint())
local value = parsed_msg.value
local name = bytes_to_string(parsed_msg.name)
return time_boot_ms, name, value, parsed_msg.sysid

View File

@ -21,7 +21,7 @@ end
function update()
local msg,chan,timestamp_ms = mavlink.receive_chan()
if msg then
gcs:send_text(6, string.format("Received message on channel %d at %d", chan, timestamp_ms))
gcs:send_text(6, string.format("Received message on channel %d at %s", chan, tostring(timestamp_ms)))
local parsed_msg = mavlink_msgs.decode(msg, msg_map)
if parsed_msg.msgid == heartbeat_msgid then
gcs:send_text(6, string.format("Received heartbeat from %d", parsed_msg.sysid))