mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: added docs for new bindings
This commit is contained in:
parent
2e5c5074af
commit
64810f5713
|
@ -1047,6 +1047,9 @@ function motors:get_interlock() end
|
||||||
---@param param1 string
|
---@param param1 string
|
||||||
function motors:set_frame_string(param1) end
|
function motors:set_frame_string(param1) end
|
||||||
|
|
||||||
|
-- desc
|
||||||
|
---@return integer
|
||||||
|
function motors:get_desired_spool_state() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@class FWVersion
|
---@class FWVersion
|
||||||
|
@ -1255,6 +1258,14 @@ function quadplane:in_assisted_flight() end
|
||||||
---@return boolean
|
---@return boolean
|
||||||
function quadplane:in_vtol_mode() end
|
function quadplane:in_vtol_mode() end
|
||||||
|
|
||||||
|
-- true in descent phase of VTOL landing
|
||||||
|
---@return boolean
|
||||||
|
function quadplane:in_vtol_land_descent() end
|
||||||
|
|
||||||
|
-- abort a VTOL landing, climbing back up
|
||||||
|
---@return boolean
|
||||||
|
function quadplane:abort_landing() end
|
||||||
|
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@class LED
|
---@class LED
|
||||||
|
@ -1621,6 +1632,11 @@ function serialLED:set_num_neopixel(chan, num_leds) end
|
||||||
---@class vehicle
|
---@class vehicle
|
||||||
vehicle = {}
|
vehicle = {}
|
||||||
|
|
||||||
|
-- override landing descent rate, times out in 1s
|
||||||
|
---@param rate number
|
||||||
|
---@return boolean
|
||||||
|
function vehicle:set_land_descent_rate(rate) end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@param rudder_pct number
|
---@param rudder_pct number
|
||||||
---@param run_yaw_rate_control boolean
|
---@param run_yaw_rate_control boolean
|
||||||
|
|
Loading…
Reference in New Issue