Browse Source

AR_AttitudeControl: set throttle speed pid dt

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
40bb2b0ad9
  1. 2
      libraries/APM_Control/AR_AttitudeControl.cpp

2
libraries/APM_Control/AR_AttitudeControl.cpp

@ -320,6 +320,8 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor @@ -320,6 +320,8 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor
if (_speed_last_ms == 0 || dt > 0.1f) {
dt = 0.0f;
_throttle_speed_pid.reset_filter();
} else {
_throttle_speed_pid.set_dt(dt);
}
_speed_last_ms = now;

Loading…
Cancel
Save