mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
RC_Channel: fix handling of rc_override_time of -1
This commit is contained in:
parent
fc0f6297a7
commit
a6fbee9820
@ -356,7 +356,7 @@ bool RC_Channel::has_override() const
|
|||||||
}
|
}
|
||||||
|
|
||||||
const float override_timeout_ms = rc().override_timeout_ms();
|
const float override_timeout_ms = rc().override_timeout_ms();
|
||||||
return is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms);
|
return (override_timeout_ms < 0) || (is_positive(override_timeout_ms) && ((AP_HAL::millis() - last_override_time) < (uint32_t)override_timeout_ms));
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user