Browse Source

AP_Vehicle: update notch count.

master_rangefinder
Andy Piper 3 years ago committed by Andrew Tridgell
parent
commit
a560d1f2cc
  1. 4
      libraries/AP_Vehicle/AP_Vehicle.cpp

4
libraries/AP_Vehicle/AP_Vehicle.cpp

@ -511,13 +511,13 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch &notch) @@ -511,13 +511,13 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch &notch)
float notches[INS_MAX_NOTCHES];
const uint8_t num_notches = AP::esc_telem().get_motor_frequencies_hz(notch.num_dynamic_notches, notches);
// ESC telemetry will return 0 for missing data, but only after 1s
for (uint8_t i = 0; i < notch.num_dynamic_notches; i++) {
for (uint8_t i = 0; i < num_notches; i++) {
if (!is_zero(notches[i])) {
notches[i] = MAX(ref_freq, notches[i]);
}
}
if (num_notches > 0) {
notch.update_frequencies_hz(notch.num_dynamic_notches, notches);
notch.update_frequencies_hz(num_notches, notches);
} else { // throttle fallback
update_throttle_notch(notch);
}

Loading…
Cancel
Save