diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 0350e4b1e9..ee2709a12b 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -191,9 +191,9 @@ void AC_AttitudeControl::reset_rate_controller_I_terms() // reset rate controller I terms smoothly to zero in 0.5 seconds void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly() { - get_rate_roll_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC);; - get_rate_pitch_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC);; - get_rate_yaw_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC);; + get_rate_roll_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC); + get_rate_pitch_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC); + get_rate_yaw_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC); } // The attitude controller works around the concept of the desired attitude, target attitude