AP_Scripting: add binding to set motors external limits

This commit is contained in:
Peter Hall 2022-10-22 00:47:15 +01:00 committed by Andrew Tridgell
parent bbb9e66196
commit 9ac488d500
2 changed files with 9 additions and 0 deletions

View File

@ -1060,6 +1060,14 @@ function motors:get_interlock() end
---@return number
function motors:get_lateral() end
-- set external limit flags for each axis to prevent integrator windup
---@param roll boolean
---@param pitch boolean
---@param yaw boolean
---@param throttle_lower boolean
---@param throttle_upper boolean
function motors:set_external_limits(roll, pitch, yaw, throttle_lower, throttle_upper) end
-- get forward motor output
---@return number
function motors:get_forward() end

View File

@ -559,6 +559,7 @@ 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
singleton AP::motors() method set_external_limits void boolean boolean boolean boolean boolean
include AP_Common/AP_FWVersion.h
singleton AP::fwversion() literal