mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_Vehicle: add and use AP_RPM_ENABLED
... and backend-specific equivalents
This commit is contained in:
parent
63c551ce13
commit
4758fabe0d
@ -491,6 +491,7 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch)
|
|||||||
update_throttle_notch(notch);
|
update_throttle_notch(notch);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
case HarmonicNotchDynamicMode::UpdateRPM: // rpm sensor based tracking
|
case HarmonicNotchDynamicMode::UpdateRPM: // rpm sensor based tracking
|
||||||
case HarmonicNotchDynamicMode::UpdateRPM2: {
|
case HarmonicNotchDynamicMode::UpdateRPM2: {
|
||||||
const auto *rpm_sensor = AP::rpm();
|
const auto *rpm_sensor = AP::rpm();
|
||||||
@ -504,6 +505,7 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
#endif // AP_RPM_ENABLED
|
||||||
#if HAL_WITH_ESC_TELEM
|
#if HAL_WITH_ESC_TELEM
|
||||||
case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking
|
case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking
|
||||||
// set the harmonic notch filter frequency scaled on measured frequency
|
// set the harmonic notch filter frequency scaled on measured frequency
|
||||||
|
Loading…
Reference in New Issue
Block a user