AP_Scripting: Add high latency MAVLink control

This commit is contained in:
Stephen Dade 2022-12-21 11:39:20 +11:00 committed by Peter Barker
parent a39a933cbd
commit a3cdfd0e3c
2 changed files with 13 additions and 0 deletions

View File

@ -1882,6 +1882,15 @@ function gcs:send_named_float(name, value) end
---| '4' # Failed
function gcs:set_message_interval(port_num, msg_id, interval_us) end
-- set high latency control state. Analogous to MAV_CMD_CONTROL_HIGH_LATENCY
---@param enabled boolean -- true to enable or false to disable
---@return void
function gcs:enable_high_latency_connections(enabled) end
-- get the the current state of high latency control
---@return boolean
function gcs:get_high_latency_status() end
-- send text with severity level
---@param severity integer
---| '0' # Emergency: System is unusable. This is a "panic" condition.

View File

@ -226,6 +226,10 @@ singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV
singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t'skip_check int32_t -1 INT32_MAX
singleton GCS method send_named_float void string float'skip_check
singleton GCS depends HAL_HIGH_LATENCY2_ENABLED == 1
singleton GCS method get_high_latency_status boolean
singleton GCS method enable_high_latency_connections void boolean
include AP_ONVIF/AP_ONVIF.h depends ENABLE_ONVIF == 1
singleton AP_ONVIF depends ENABLE_ONVIF == 1
singleton AP_ONVIF rename onvif