mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Scripting: add binding for GCS last seen time
This commit is contained in:
parent
55040175e6
commit
66b8fd95ad
@ -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 = {}
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user