AP_Scripting: added get_att_error_angle_deg binding for AC_AttitudeControl

This commit is contained in:
Andrew Tridgell 2024-12-17 08:35:04 +11:00
parent 106e131591
commit 9503744e6a
2 changed files with 5 additions and 0 deletions

View File

@ -3761,6 +3761,10 @@ AC_AttitudeControl = {}
---@return number -- yaw slew rate ---@return number -- yaw slew rate
function AC_AttitudeControl:get_rpy_srate() end function AC_AttitudeControl:get_rpy_srate() end
-- Return the angle between the target thrust vector and the current thrust vector in degrees.
---@return number -- attitude error
function AC_AttitudeControl:get_att_error_angle_deg() end
-- desc -- desc
AR_AttitudeControl = {} AR_AttitudeControl = {}

View File

@ -768,6 +768,7 @@ singleton AC_PrecLand method get_target_location boolean Location'Null
include AC_AttitudeControl/AC_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI 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 depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
singleton AC_AttitudeControl method get_rpy_srate void float'Ref float'Ref float'Ref singleton AC_AttitudeControl method get_rpy_srate void float'Ref float'Ref float'Ref
singleton AC_AttitudeControl method get_att_error_angle_deg float
include AC_AttitudeControl/AC_PosControl.h depends APM_BUILD_COPTER_OR_HELI include AC_AttitudeControl/AC_PosControl.h depends APM_BUILD_COPTER_OR_HELI
singleton AC_PosControl depends APM_BUILD_COPTER_OR_HELI singleton AC_PosControl depends APM_BUILD_COPTER_OR_HELI