mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Filter: return active harmonics based on dynamic harmonic enablement
This commit is contained in:
parent
eb4c69ed88
commit
a93821110e
@ -20,6 +20,7 @@
|
|||||||
#include "NotchFilter.h"
|
#include "NotchFilter.h"
|
||||||
|
|
||||||
#define HNF_MAX_HARMONICS 8
|
#define HNF_MAX_HARMONICS 8
|
||||||
|
#define HNF_MAX_HMNC_BITSET 0xF
|
||||||
|
|
||||||
/*
|
/*
|
||||||
a filter that manages a set of notch filters targetted at a fundamental center frequency
|
a filter that manages a set of notch filters targetted at a fundamental center frequency
|
||||||
@ -87,7 +88,7 @@ public:
|
|||||||
// set the fundamental center frequency of the harmonic notch
|
// set the fundamental center frequency of the harmonic notch
|
||||||
void set_center_freq_hz(float center_freq) { _center_freq_hz.set(center_freq); }
|
void set_center_freq_hz(float center_freq) { _center_freq_hz.set(center_freq); }
|
||||||
// harmonics enabled on the harmonic notch
|
// harmonics enabled on the harmonic notch
|
||||||
uint8_t harmonics(void) const { return _harmonics; }
|
uint8_t harmonics(void) const { return hasOption(Options::DynamicHarmonic) ? HNF_MAX_HMNC_BITSET : _harmonics; }
|
||||||
// reference value of the harmonic notch
|
// reference value of the harmonic notch
|
||||||
float reference(void) const { return _reference; }
|
float reference(void) const { return _reference; }
|
||||||
// notch options
|
// notch options
|
||||||
@ -97,7 +98,7 @@ public:
|
|||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// notch harmonics
|
// configured notch harmonics
|
||||||
AP_Int8 _harmonics;
|
AP_Int8 _harmonics;
|
||||||
// notch reference value
|
// notch reference value
|
||||||
AP_Float _reference;
|
AP_Float _reference;
|
||||||
|
Loading…
Reference in New Issue
Block a user