Skip to content

Commit

Permalink
AR_AttitudeControl: reset I if speed controller not called recently
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Sep 4, 2018
1 parent 135e37e commit 9609758
Showing 1 changed file with 1 addition and 0 deletions.
1 change: 1 addition & 0 deletions libraries/APM_Control/AR_AttitudeControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -391,6 +391,7 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor
const uint32_t now = AP_HAL::millis();
if (!speed_control_active()) {
_throttle_speed_pid.reset_filter();
_throttle_speed_pid.reset_I();
_desired_speed = speed;
}
_speed_last_ms = now;
Expand Down

0 comments on commit 9609758

Please sign in to comment.