44 #include <px4_platform_common/log.h> 45 #include <px4_platform_common/defines.h> 75 PX4_ERR(
"SimpleAnalyzer: Unknown mode.");
104 if ((
_n < update_rate *
_window) && (update_rate > 1.0f)) {
110 PX4_DEBUG(
"SimpleAnalyzer: Result is not finite, reset the analyzer.");
127 return get() * scalingfactor;
135 }
else if (x < min) {
152 if (in > UINT16_MAX) {
159 out =
static_cast<uint16_t
>(in);
165 if (in > INT16_MAX) {
168 }
else if (in < INT16_MIN) {
172 out =
static_cast<int16_t
>(in);
SimpleAnalyzer(Mode mode, float window=60.0f)
Constructor.
float get() const
Get the current result of the analyzer.
void reset()
Reset the analyzer to the initial state.
float get_scaled(float scalingfactor) const
Get the scaled value of the current result of the analyzer.
void check_limits(float &x, float min, float max) const
constexpr _Tp min(_Tp a, _Tp b)
bool valid() const
Returns true if at least one value has been added to the analyzer.
constexpr _Tp max(_Tp a, _Tp b)
unsigned int _n
The number of added samples.
void convert_limit_safe(float in, uint16_t &out)
void int_round(float &x) const
float _result
The result of the analyzed data.
void add_value(float val, float update_rate)
Add a new value to the analyzer and update the result according to the mode.
Mode _mode
The mode of the simple analyzer.
float _window
The window size for the moving average filter [s].