AP_Scripting: added PDmod binding for quick tuning

This commit is contained in:
Andrew Tridgell 2022-04-26 19:07:40 +10:00
parent f8fe74f5fe
commit ed89acea66
2 changed files with 14 additions and 0 deletions

View File

@ -1955,6 +1955,16 @@ function ahrs:get_pitch() end
---@return number
function ahrs:get_roll() end
-- desc
---@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
-- desc
---@class follow
follow = {}

View File

@ -506,3 +506,7 @@ singleton AP_Follow method get_target_location_and_velocity boolean Location'Nul
singleton AP_Follow method get_target_location_and_velocity_ofs boolean Location'Null Vector3f'Null
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