Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Do not allow users to set throttle-based notch in Heli #28843

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
10 changes: 9 additions & 1 deletion libraries/Filter/HarmonicNotchFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "HarmonicNotchFilter.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>

#define HNF_MAX_FILTERS HAL_HNF_MAX_FILTERS // must be even for double-notch filters

Expand Down Expand Up @@ -48,6 +49,13 @@
*/
#define NOTCHFILTER_ATTENUATION_CUTOFF 0.25

#if APM_BUILD_TYPE(APM_BUILD_Heli)
// We cannot use throttle based notch on helis
#define NOTCHFILTER_DEFAULT_MODE 0 // fixed
#else
#define NOTCHFILTER_DEFAULT_MODE 1 // throttle based
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Think this should be int8_t(HarmonicNotchDynamicMode::UpdateThrottle) etc

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

All defaults are floats.

#endif


// table of user settable parameters
const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
Expand Down Expand Up @@ -120,7 +128,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
// @Range: 0 5
// @Values: 0:Fixed,1:Throttle,2:RPM Sensor,3:ESC Telemetry,4:Dynamic FFT,5:Second RPM Sensor
// @User: Advanced
AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, int8_t(HarmonicNotchDynamicMode::UpdateThrottle)),
AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, NOTCHFILTER_DEFAULT_MODE),

// @Param: OPTS
// @DisplayName: Harmonic Notch Filter options
Expand Down
Loading