AP_Scripting: add binding for GCS last seen time

This commit is contained in:
Iampete1 2023-11-02 16:20:33 +00:00 committed by Andrew Tridgell
parent 55040175e6
commit 66b8fd95ad
2 changed files with 6 additions and 0 deletions

View File

@ -2312,6 +2312,10 @@ function gcs:get_high_latency_status() end
---@param text string
function gcs:send_text(severity, text) end
-- Return the system time when a gcs with id of SYSID_MYGCS was last seen
---@return uint32_t_ud -- system time in milliseconds
function gcs:last_seen() end
-- desc
---@class relay
relay = {}

View File

@ -248,6 +248,8 @@ singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM
singleton GCS method send_named_float void string float'skip_check
singleton GCS method frame_type MAV_TYPE'enum
singleton GCS method get_hud_throttle int16_t
singleton GCS method sysid_myggcs_last_seen_time_ms uint32_t
singleton GCS method sysid_myggcs_last_seen_time_ms rename last_seen
singleton GCS method get_high_latency_status boolean
singleton GCS method get_high_latency_status depends HAL_HIGH_LATENCY2_ENABLED == 1