From b201c5b23863be943b1ad71b48b11b2d43dd0590 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 25 May 2022 15:03:36 +0100 Subject: [PATCH] AC_AttitudeControl: reduce alt hold min lean angle to 5deg on plane --- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 2 ++ libraries/AC_AttitudeControl/AC_AttitudeControl.h | 1 - 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 053a719e61..2b325667ad 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -6,9 +6,11 @@ extern const AP_HAL::HAL& hal; #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) // default gains for Plane # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft + #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 5.0 // Min lean angle so that vehicle can maintain limited control #else // default gains for Copter and Sub # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium + #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0 // Min lean angle so that vehicle can maintain limited control #endif AC_AttitudeControl *AC_AttitudeControl::_singleton; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 4b9c6d63f1..bad3b970bb 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -35,7 +35,6 @@ #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT 1.0f // Time constant used to limit lean angle so that vehicle does not lose altitude #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX 0.8f // Max throttle used to limit lean angle so that vehicle does not lose altitude -#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0f // Min lean angle so that vehicle can maintain limited control #define AC_ATTITUDE_CONTROL_MIN_DEFAULT 0.1f // minimum throttle mix default #define AC_ATTITUDE_CONTROL_MAN_DEFAULT 0.1f // manual throttle mix default