Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Scripting: add binding for GCS last seen time #25444

Merged
merged 1 commit into from
Nov 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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 = {}
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down