mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AC_AttitudeControl: relax_bf_rate_controller resets rate integrators
This commit is contained in:
parent
3ad9b1a06b
commit
e2383581cc
@ -95,6 +95,10 @@ void AC_AttitudeControl::relax_bf_rate_controller()
|
|||||||
// ensure zero error in body frame rate controllers
|
// ensure zero error in body frame rate controllers
|
||||||
const Vector3f& gyro = _ahrs.get_gyro();
|
const Vector3f& gyro = _ahrs.get_gyro();
|
||||||
_rate_bf_target = gyro * AC_ATTITUDE_CONTROL_DEGX100;
|
_rate_bf_target = gyro * AC_ATTITUDE_CONTROL_DEGX100;
|
||||||
|
|
||||||
|
_pid_rate_roll.reset_I();
|
||||||
|
_pid_rate_pitch.reset_I();
|
||||||
|
_pid_rate_yaw.reset_I();
|
||||||
}
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user