From 9503744e6ade0e11c284caba330ac5ae4070ccac Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 17 Dec 2024 08:35:04 +1100 Subject: [PATCH] AP_Scripting: added get_att_error_angle_deg binding for AC_AttitudeControl --- libraries/AP_Scripting/docs/docs.lua | 4 ++++ libraries/AP_Scripting/generator/description/bindings.desc | 1 + 2 files changed, 5 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index da3eda133e..4e15c6d33d 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3761,6 +3761,10 @@ AC_AttitudeControl = {} ---@return number -- yaw slew rate 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 AR_AttitudeControl = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 08a48ecb58..a9decc2c92 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -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 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_att_error_angle_deg float include AC_AttitudeControl/AC_PosControl.h depends APM_BUILD_COPTER_OR_HELI singleton AC_PosControl depends APM_BUILD_COPTER_OR_HELI