Skip to content

Commit

Permalink
AP_InertialSensor: Add config error for helis trying to use throttle …
Browse files Browse the repository at this point in the history
…notch
  • Loading branch information
MattKear committed Dec 5, 2024
1 parent 6e26353 commit 9063fb8
Showing 1 changed file with 10 additions and 0 deletions.
10 changes: 10 additions & 0 deletions libraries/AP_InertialSensor/AP_InertialSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1006,6 +1006,16 @@ AP_InertialSensor::init(uint16_t loop_rate)
#endif

#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED

#if APM_BUILD_TYPE(APM_BUILD_Heli)
// Throttle tracking does not make sense with heli because "throttle" is actually collective position in AP_MotorsHeli
for (auto &notch : harmonic_notches) {
if (notch.params.enabled() && notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateThrottle) {
AP_BoardConfig::config_error("Throttle notch unavailable with heli");
}
}
#endif

// the center frequency of the harmonic notch is always taken from the calculated value so that it can be updated
// dynamically, the calculated value is always some multiple of the configured center frequency, so start with the
// configured value
Expand Down

0 comments on commit 9063fb8

Please sign in to comment.