Browse Source

AC_AttitudeControl: reduce alt hold min lean angle to 5deg on plane

apm_2208
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
ecc86b6a4b
  1. 2
      libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
  2. 1
      libraries/AC_AttitudeControl/AC_AttitudeControl.h

2
libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

@ -6,9 +6,11 @@ extern const AP_HAL::HAL& hal; @@ -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;

1
libraries/AC_AttitudeControl/AC_AttitudeControl.h

@ -35,7 +35,6 @@ @@ -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

Loading…
Cancel
Save