mirror of https://github.com/ArduPilot/ardupilot
AC_AttControl: add ANGLE_BOOST param
This allows disabling angle boost
This commit is contained in:
parent
6c458b07cb
commit
5ddd332277
|
@ -59,6 +59,13 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
|
|||
|
||||
// IDs 8,9,10,11 RESERVED (in use on Solo)
|
||||
|
||||
// @Param: ANGLE_BOOST
|
||||
// @DisplayName: Angle Boost
|
||||
// @Description: Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude
|
||||
// @Values: 0:Disabled, 1:Enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ANGLE_BOOST", 12, AC_AttitudeControl, _angle_boost_enabled, 1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -293,6 +293,9 @@ protected:
|
|||
// Enable/Disable body frame rate feed forward
|
||||
AP_Int8 _rate_bf_ff_enabled;
|
||||
|
||||
// Enable/Disable angle boost
|
||||
AP_Int8 _angle_boost_enabled;
|
||||
|
||||
// Intersampling period in seconds
|
||||
float _dt;
|
||||
|
||||
|
|
|
@ -16,6 +16,10 @@ float AC_AttitudeControl_Multi::get_althold_lean_angle_max() const
|
|||
// throttle value should be 0 ~ 1000
|
||||
float AC_AttitudeControl_Multi::get_boosted_throttle(float throttle_in)
|
||||
{
|
||||
if (!_angle_boost_enabled) {
|
||||
return throttle_in;
|
||||
_angle_boost = 0;
|
||||
}
|
||||
// inverted_factor is 1 for tilt angles below 60 degrees
|
||||
// reduces as a function of angle beyond 60 degrees
|
||||
// becomes zero at 90 degrees
|
||||
|
|
Loading…
Reference in New Issue