mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Vehicle: make sure notches are not spurious disabled when not using throttle notch
This commit is contained in:
parent
ce3ea9f2e9
commit
4cc6bee720
@ -459,11 +459,6 @@ void AP_Vehicle::update_throttle_notch(AP_InertialSensor::HarmonicNotch ¬ch)
|
||||
const float min_ratio = notch.params.freq_min_ratio();
|
||||
|
||||
const AP_Motors* motors = AP::motors();
|
||||
if (motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN) {
|
||||
notch.set_inactive(true);
|
||||
} else {
|
||||
notch.set_inactive(false);
|
||||
}
|
||||
const float motors_throttle = motors != nullptr ? MAX(0,motors->get_throttle_out()) : 0;
|
||||
float throttle_freq = ref_freq * MAX(min_ratio, sqrtf(motors_throttle / ref));
|
||||
|
||||
@ -485,6 +480,13 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch)
|
||||
return;
|
||||
}
|
||||
|
||||
const AP_Motors* motors = AP::motors();
|
||||
if (motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN) {
|
||||
notch.set_inactive(true);
|
||||
} else {
|
||||
notch.set_inactive(false);
|
||||
}
|
||||
|
||||
switch (notch.params.tracking_mode()) {
|
||||
case HarmonicNotchDynamicMode::UpdateThrottle: // throttle based tracking
|
||||
// set the harmonic notch filter frequency approximately scaled on motor rpm implied by throttle
|
||||
|
Loading…
Reference in New Issue
Block a user