AP_Scripting: add bindings to get throttle, forward, lateral and spool state from motors

This commit is contained in:
Peter Hall 2022-10-20 23:16:28 +01:00 committed by Andrew Tridgell
parent bc3fc9a317
commit 23fb73085a
2 changed files with 25 additions and 0 deletions

View File

@ -1056,6 +1056,27 @@ motors = {}
---| false # motors inactive
function motors:get_interlock() end
-- get lateral motor output
---@return number
function motors:get_lateral() end
-- get forward motor output
---@return number
function motors:get_forward() end
-- get throttle motor output
---@return number
function motors:get_throttle() end
-- get throttle motor output
---@return integer
---| '0' # Shut down
---| '1' # Ground idle
---| '2' # Spooling up
---| '3' # Throttle unlimited
---| '4' # Spooling down
function motors:get_spool_state() end
-- desc
---@param param1 string
function motors:set_frame_string(param1) end

View File

@ -555,6 +555,10 @@ singleton AP::motors() method get_pitch float
singleton AP::motors() method get_pitch_ff float
singleton AP::motors() method get_yaw float
singleton AP::motors() method get_yaw_ff float
singleton AP::motors() method get_throttle float
singleton AP::motors() method get_forward float
singleton AP::motors() method get_lateral float
singleton AP::motors() method get_spool_state uint8_t
include AP_Common/AP_FWVersion.h
singleton AP::fwversion() literal