mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: added get_rpy_srate binding
and remove dmod binding
This commit is contained in:
parent
99a6cb69f8
commit
77a985182c
|
@ -1963,11 +1963,11 @@ function ahrs:get_roll() end
|
|||
---@class AC_AttitudeControl
|
||||
AC_AttitudeControl = {}
|
||||
|
||||
-- return PD modifier for VTOL controller
|
||||
---@return number -- roll PDmod
|
||||
---@return number -- pitch PDmod
|
||||
---@return number -- yaw PDmod
|
||||
function AC_AttitudeControl:get_rpy_PDmod() end
|
||||
-- return slew rates for VTOL controller
|
||||
---@return number -- roll slew rate
|
||||
---@return number -- pitch slew rate
|
||||
---@return number -- yaw slew rate
|
||||
function AC_AttitudeControl:get_rpy_srate() end
|
||||
|
||||
-- desc
|
||||
---@class follow
|
||||
|
|
|
@ -509,5 +509,4 @@ singleton AP_Follow method get_target_heading_deg boolean float'Null
|
|||
|
||||
include AC_AttitudeControl/AC_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||
singleton AC_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||
singleton AC_AttitudeControl method get_rpy_PDmod void float'Ref float'Ref float'Ref
|
||||
|
||||
singleton AC_AttitudeControl method get_rpy_srate void float'Ref float'Ref float'Ref
|
||||
|
|
Loading…
Reference in New Issue