mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_ESC_Telem: keep RPM updates in the correct order
This commit is contained in:
parent
40f8424ab6
commit
7d5162181f
@ -67,7 +67,10 @@ 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[valid_escs++] = rpm * (1.0f / 60.0f);
|
||||
freqs[i] = rpm * (1.0f / 60.0f);
|
||||
valid_escs++;
|
||||
} else {
|
||||
freqs[i] = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user