diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index b88227fdbbfaf..e1560bbd8e4e6 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -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 = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 69a2d1f27f347..038db48be8b99 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -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