mirror of https://github.com/ArduPilot/ardupilot
APM_Control: AP_YawController: update pid_info with integrator reset for logging purposes
This commit is contained in:
parent
9d8bf5004e
commit
545cf0504a
|
@ -343,7 +343,8 @@ float AP_YawController::get_rate_out(float desired_rate, float scaler, bool disa
|
|||
|
||||
void AP_YawController::reset_I()
|
||||
{
|
||||
_integrator = 0;
|
||||
_integrator = 0.0;
|
||||
_pid_info.I = 0.0;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue