Browse Source

AC_AttitudeControl: relax_bf_rate_controller resets rate integrators

mission-4.1.18
Jonathan Challinger 10 years ago committed by Randy Mackay
parent
commit
e2383581cc
  1. 4
      libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

4
libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

@ -95,6 +95,10 @@ void AC_AttitudeControl::relax_bf_rate_controller() @@ -95,6 +95,10 @@ void AC_AttitudeControl::relax_bf_rate_controller()
// ensure zero error in body frame rate controllers
const Vector3f& gyro = _ahrs.get_gyro();
_rate_bf_target = gyro * AC_ATTITUDE_CONTROL_DEGX100;
_pid_rate_roll.reset_I();
_pid_rate_pitch.reset_I();
_pid_rate_yaw.reset_I();
}
//

Loading…
Cancel
Save