mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AC_AttitudeControl: reduce alt hold min lean angle to 5deg on plane
This commit is contained in:
parent
132431a75e
commit
b201c5b238
@ -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;
|
||||
|
@ -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…
Reference in New Issue
Block a user