mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ESC_Telem: Correct a regression with calclulating active_esc_mask
Credit to @casrya on github for spotting this (#24665), and investigating. The intent here was to bail out only if no data was within the timeout, which I had messed up in a bad refactor.
This commit is contained in:
parent
e8517d8e5d
commit
a0efcc7bdc
@ -108,7 +108,7 @@ uint32_t AP_ESC_Telem::get_active_esc_mask() const {
|
||||
continue;
|
||||
}
|
||||
if (now - _telem_data[i].last_update_ms >= ESC_TELEM_DATA_TIMEOUT_MS
|
||||
&& rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) {
|
||||
&& !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) {
|
||||
continue;
|
||||
}
|
||||
ret |= (1U << i);
|
||||
|
Loading…
Reference in New Issue
Block a user