PX4 Firmware
PX4 Autopilot Software http://px4.io
SimpleAnalyzer Class Reference

SimpleAnalyzer. More...

#include <mavlink_simple_analyzer.h>

Collaboration diagram for SimpleAnalyzer:

Public Types

enum  Mode { AVERAGE = 0, MIN, MAX }
 

Public Member Functions

 SimpleAnalyzer (Mode mode, float window=60.0f)
 Constructor. More...
 
void reset ()
 Reset the analyzer to the initial state. More...
 
void add_value (float val, float update_rate)
 Add a new value to the analyzer and update the result according to the mode. More...
 
bool valid () const
 Returns true if at least one value has been added to the analyzer. More...
 
float get () const
 Get the current result of the analyzer. More...
 
float get_scaled (float scalingfactor) const
 Get the scaled value of the current result of the analyzer. More...
 
void get_scaled (uint8_t &ret, float scalingfactor) const
 Get the rounded scaled value casted to the input template type. More...
 
void get_scaled (int8_t &ret, float scalingfactor) const
 

Private Member Functions

void check_limits (float &x, float min, float max) const
 
void int_round (float &x) const
 

Private Attributes

unsigned int _n = 0
 The number of added samples. More...
 
float _window = 60.0f
 The window size for the moving average filter [s]. More...
 
Mode _mode = AVERAGE
 The mode of the simple analyzer. More...
 
float _result = 0.0f
 The result of the analyzed data. More...
 

Detailed Description

SimpleAnalyzer.

Class used for simple analysis of data streams. The data can be analyzed in the following three modes:

AVERAGE: The average value is computed at the beginning. Based on the number of analyzed values, the update rate and the window size the switch to the moving average is determined.

MIN: The minimum value is tracked.

MAX: The maximum value is tracked.

Definition at line 61 of file mavlink_simple_analyzer.h.

Member Enumeration Documentation

◆ Mode

Enumerator
AVERAGE 
MIN 
MAX 

Definition at line 64 of file mavlink_simple_analyzer.h.

Constructor & Destructor Documentation

◆ SimpleAnalyzer()

SimpleAnalyzer::SimpleAnalyzer ( Mode  mode,
float  window = 60.0f 
)

Constructor.

Defines the mode of the analyzer and the window size in case of the averaging mode.

Parameters
[in]modeThe mode of the analyzer
[in]windowThe window size in seconds. Only used in the averaging mode.

Definition at line 47 of file mavlink_simple_analyzer.cpp.

References reset().

Here is the call graph for this function:

Member Function Documentation

◆ add_value()

void SimpleAnalyzer::add_value ( float  val,
float  update_rate 
)

Add a new value to the analyzer and update the result according to the mode.

Parameters
[in]valThe value to process
[in]update_rateThe update rate in [1/s] for which new value are added. Used in the averaging mode to determine when to switch from averaging to the moving average.

Definition at line 79 of file mavlink_simple_analyzer.cpp.

References _mode, _n, _result, _window, AVERAGE, MAX, MIN, and reset().

Referenced by MavlinkStreamHighLatency2::update_airspeed(), MavlinkStreamHighLatency2::update_battery_status(), MavlinkStreamHighLatency2::update_global_position(), MavlinkStreamHighLatency2::update_gps(), MavlinkStreamHighLatency2::update_tecs_status(), MavlinkStreamHighLatency2::update_vehicle_status(), and MavlinkStreamHighLatency2::update_wind_estimate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ check_limits()

void SimpleAnalyzer::check_limits ( float &  x,
float  min,
float  max 
) const
private

Definition at line 130 of file mavlink_simple_analyzer.cpp.

References math::max(), and math::min().

Referenced by get_scaled().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get()

float SimpleAnalyzer::get ( ) const

Get the current result of the analyzer.

Definition at line 120 of file mavlink_simple_analyzer.cpp.

References _result.

◆ get_scaled() [1/3]

float SimpleAnalyzer::get_scaled ( float  scalingfactor) const

Get the scaled value of the current result of the analyzer.

Parameters
[in]scalingfactorThe factor used to scale the result.

Definition at line 125 of file mavlink_simple_analyzer.cpp.

Referenced by get_scaled(), and MavlinkStreamHighLatency2::send().

Here is the caller graph for this function:

◆ get_scaled() [2/3]

void SimpleAnalyzer::get_scaled ( uint8_t &  ret,
float  scalingfactor 
) const
inline

Get the rounded scaled value casted to the input template type.

Should only be used to return integer types.

Parameters
[out]retThe scaled and rounded value of the current analyzer result. [in] scalingfactor: The factor which is used to scale the result.

Definition at line 119 of file mavlink_simple_analyzer.h.

References check_limits(), get_scaled(), and int_round().

Here is the call graph for this function:

◆ get_scaled() [3/3]

void SimpleAnalyzer::get_scaled ( int8_t &  ret,
float  scalingfactor 
) const
inline

Definition at line 128 of file mavlink_simple_analyzer.h.

References check_limits(), get_scaled(), and int_round().

Here is the call graph for this function:

◆ int_round()

void SimpleAnalyzer::int_round ( float &  x) const
private

Definition at line 140 of file mavlink_simple_analyzer.cpp.

Referenced by get_scaled().

Here is the caller graph for this function:

◆ reset()

void SimpleAnalyzer::reset ( void  )

Reset the analyzer to the initial state.

Definition at line 54 of file mavlink_simple_analyzer.cpp.

References _mode, _n, _result, AVERAGE, MAX, and MIN.

Referenced by add_value(), MavlinkStreamHighLatency2::reset_analysers(), and SimpleAnalyzer().

Here is the caller graph for this function:

◆ valid()

bool SimpleAnalyzer::valid ( ) const

Returns true if at least one value has been added to the analyzer.

Definition at line 115 of file mavlink_simple_analyzer.cpp.

References _n.

Referenced by MavlinkStreamHighLatency2::send().

Here is the caller graph for this function:

Member Data Documentation

◆ _mode

Mode SimpleAnalyzer::_mode = AVERAGE
private

The mode of the simple analyzer.

Definition at line 140 of file mavlink_simple_analyzer.h.

Referenced by add_value(), and reset().

◆ _n

unsigned int SimpleAnalyzer::_n = 0
private

The number of added samples.

Definition at line 138 of file mavlink_simple_analyzer.h.

Referenced by add_value(), reset(), and valid().

◆ _result

float SimpleAnalyzer::_result = 0.0f
private

The result of the analyzed data.

Definition at line 141 of file mavlink_simple_analyzer.h.

Referenced by add_value(), get(), and reset().

◆ _window

float SimpleAnalyzer::_window = 60.0f
private

The window size for the moving average filter [s].

Definition at line 139 of file mavlink_simple_analyzer.h.

Referenced by add_value().


The documentation for this class was generated from the following files: