mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AR_AttitudeControl: fix turn-rate controller timeout
This commit is contained in:
parent
4e8155f4e5
commit
a2b1807ca0
@ -207,7 +207,7 @@ float AR_AttitudeControl::get_steering_out_rate(float desired_rate, bool skid_st
|
||||
// calculate dt
|
||||
const uint32_t now = AP_HAL::millis();
|
||||
float dt = (now - _steer_turn_last_ms) / 1000.0f;
|
||||
if ((_steer_turn_last_ms == 0) || (dt > AR_ATTCONTROL_TIMEOUT_MS)) {
|
||||
if ((_steer_turn_last_ms == 0) || (dt > (AR_ATTCONTROL_TIMEOUT_MS / 1000.0f))) {
|
||||
dt = 0.0f;
|
||||
_steer_rate_pid.reset_filter();
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user