AP_Vehicle: add and use AP_RPM_ENABLED

... and backend-specific equivalents
This commit is contained in:
Peter Barker 2022-07-15 21:53:41 +10:00 committed by Andrew Tridgell
parent 63c551ce13
commit 4758fabe0d
1 changed files with 2 additions and 0 deletions

View File

@ -491,6 +491,7 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch &notch)
update_throttle_notch(notch);
break;
#if AP_RPM_ENABLED
case HarmonicNotchDynamicMode::UpdateRPM: // rpm sensor based tracking
case HarmonicNotchDynamicMode::UpdateRPM2: {
const auto *rpm_sensor = AP::rpm();
@ -504,6 +505,7 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch &notch)
}
break;
}
#endif // AP_RPM_ENABLED
#if HAL_WITH_ESC_TELEM
case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking
// set the harmonic notch filter frequency scaled on measured frequency