mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 16:53:57 -04:00
RC_Channel: treat UINT16_MAX as a value of 0 in set_override
Addresses ignore R/C override issue documented here: https://github.com/ArduPilot/ardupilot/issues/1667
This commit is contained in:
parent
8d3e1e45a7
commit
199412adf2
@ -316,6 +316,9 @@ bool RC_Channel::in_trim_dz()
|
|||||||
void RC_Channel::set_override(const uint16_t v, const uint32_t timestamp_us)
|
void RC_Channel::set_override(const uint16_t v, const uint32_t timestamp_us)
|
||||||
{
|
{
|
||||||
last_override_time = timestamp_us != 0 ? timestamp_us : AP_HAL::millis();
|
last_override_time = timestamp_us != 0 ? timestamp_us : AP_HAL::millis();
|
||||||
|
if (v == UINT16_MAX) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
override_value = v;
|
override_value = v;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user