mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-15 12:23:58 -04:00
Revert "AP_ESC_Telem: keep RPM updates in the correct order"
This reverts commit db43b18829
.
reverted as it breaks non-contiguous motors for quadplanes
This commit is contained in:
parent
ed9c28bec5
commit
d4d10922cd
@ -67,10 +67,7 @@ uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) con
|
||||
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS && i < nfreqs; i++) {
|
||||
float rpm;
|
||||
if (get_rpm(i, rpm)) {
|
||||
freqs[i] = rpm * (1.0f / 60.0f);
|
||||
valid_escs++;
|
||||
} else {
|
||||
freqs[i] = 0.0f;
|
||||
freqs[valid_escs++] = rpm * (1.0f / 60.0f);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user