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

#include <data_validator_group.h>

Collaboration diagram for DataValidatorGroup:

Public Member Functions

 DataValidatorGroup (unsigned siblings)
 
 ~DataValidatorGroup ()
 
DataValidatoradd_new_validator ()
 Create a new Validator (with index equal to the number of currently existing validators) More...
 
void put (unsigned index, uint64_t timestamp, const float val[3], uint64_t error_count, int priority)
 Put an item into the validator group. More...
 
float * get_best (uint64_t timestamp, int *index)
 Get the best data triplet of the group. More...
 
float get_vibration_factor (uint64_t timestamp)
 Get the RMS / vibration factor. More...
 
float get_vibration_offset (uint64_t timestamp, int axis)
 Get the vibration offset in the sensor unit. More...
 
unsigned failover_count () const
 Get the number of failover events. More...
 
int failover_index ()
 Get the index of the failed sensor in the group. More...
 
uint32_t failover_state ()
 Get the error state of the failed sensor in the group. More...
 
void print ()
 Print the validator value. More...
 
void set_timeout (uint32_t timeout_interval_us)
 Set the timeout value for the whole group. More...
 
void set_equal_value_threshold (uint32_t threshold)
 Set the equal count threshold for the whole group. More...
 

Private Member Functions

 DataValidatorGroup (const DataValidatorGroup &)
 
DataValidatorGroup operator= (const DataValidatorGroup &)
 

Private Attributes

DataValidator_first {nullptr}
 first node in the group More...
 
DataValidator_last {nullptr}
 last node in the group More...
 
uint32_t _timeout_interval_us {0}
 currently set timeout More...
 
int _curr_best {-1}
 currently best index More...
 
int _prev_best {-1}
 the previous best index More...
 
uint64_t _first_failover_time {0}
 timestamp where the first failover occured or zero if none occured More...
 
unsigned _toggle_count {0}
 number of back and forth switches between two sensors More...
 

Static Private Attributes

static constexpr float MIN_REGULAR_CONFIDENCE = 0.9f
 

Detailed Description

Definition at line 46 of file data_validator_group.h.

Constructor & Destructor Documentation

◆ DataValidatorGroup() [1/2]

DataValidatorGroup::DataValidatorGroup ( unsigned  siblings)
Parameters
siblingsinitial number of DataValidator's. Must be > 0.

Definition at line 46 of file data_validator_group.cpp.

References _first, _last, _timeout_interval_us, DataValidator::get_timeout(), and DataValidator::setSibling().

Here is the call graph for this function:

◆ ~DataValidatorGroup()

DataValidatorGroup::~DataValidatorGroup ( )

Definition at line 71 of file data_validator_group.cpp.

References _first, and DataValidator::sibling().

Here is the call graph for this function:

◆ DataValidatorGroup() [2/2]

DataValidatorGroup::DataValidatorGroup ( const DataValidatorGroup )
private

Member Function Documentation

◆ add_new_validator()

DataValidator * DataValidatorGroup::add_new_validator ( )

Create a new Validator (with index equal to the number of currently existing validators)

Returns
the newly created DataValidator or nullptr on error

Definition at line 80 of file data_validator_group.cpp.

References _last, _timeout_interval_us, DataValidator::set_timeout(), and DataValidator::setSibling().

Referenced by add_validator_to_group(), and sensors::VotedSensorsUpdate::initSensorClass().

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

◆ failover_count()

unsigned DataValidatorGroup::failover_count ( ) const
inline

Get the number of failover events.

Returns
the number of failovers

Definition at line 98 of file data_validator_group.h.

References _toggle_count, failover_index(), failover_state(), print(), set_equal_value_threshold(), and set_timeout().

Referenced by sensors::VotedSensorsUpdate::checkFailover(), setup_base_group(), test_priority_switch(), and test_simple_failover().

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

◆ failover_index()

int DataValidatorGroup::failover_index ( )

Get the index of the failed sensor in the group.

Returns
index of the failed sensor

Definition at line 307 of file data_validator_group.cpp.

References _first, _prev_best, DataValidator::ERROR_FLAG_NO_ERROR, DataValidator::sibling(), DataValidator::state(), and DataValidator::used().

Referenced by sensors::VotedSensorsUpdate::checkFailover(), failover_count(), setup_base_group(), test_sensor_failure(), and test_simple_failover().

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

◆ failover_state()

uint32_t DataValidatorGroup::failover_state ( )

Get the error state of the failed sensor in the group.

Returns
bitmask with erro states of the failed sensor

Definition at line 325 of file data_validator_group.cpp.

References _first, _prev_best, DataValidator::ERROR_FLAG_NO_ERROR, DataValidator::sibling(), DataValidator::state(), and DataValidator::used().

Referenced by sensors::VotedSensorsUpdate::checkFailover(), failover_count(), setup_base_group(), and test_simple_failover().

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

◆ get_best()

float * DataValidatorGroup::get_best ( uint64_t  timestamp,
int *  index 
)

Get the best data triplet of the group.

Returns
pointer to the array of best values

Definition at line 137 of file data_validator_group.cpp.

References _curr_best, _first, _first_failover_time, _prev_best, _toggle_count, DataValidator::confidence(), f(), FLT_EPSILON, MIN_REGULAR_CONFIDENCE, DataValidator::priority(), DataValidator::reset_state(), DataValidator::sibling(), and DataValidator::value().

Referenced by sensors::VotedSensorsUpdate::accelPoll(), sensors::VotedSensorsUpdate::baroPoll(), fill_one_with_valid_data(), fill_two_with_valid_data(), sensors::VotedSensorsUpdate::gyroPoll(), sensors::VotedSensorsUpdate::magPoll(), test_init(), test_priority_switch(), test_put(), test_sensor_failure(), and test_simple_failover().

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

◆ get_vibration_factor()

float DataValidatorGroup::get_vibration_factor ( uint64_t  timestamp)

Get the RMS / vibration factor.

Returns
float value representing the RMS, which a valid indicator for vibration

Definition at line 226 of file data_validator_group.cpp.

References _first, DataValidator::confidence(), DataValidator::rms(), and DataValidator::sibling().

Referenced by setup_base_group(), and test_vibration().

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

◆ get_vibration_offset()

float DataValidatorGroup::get_vibration_offset ( uint64_t  timestamp,
int  axis 
)

Get the vibration offset in the sensor unit.

Returns
float value representing the vibration offset

Definition at line 252 of file data_validator_group.cpp.

References _first, DataValidator::confidence(), f(), DataValidator::sibling(), and DataValidator::vibration_offset().

Referenced by setup_base_group(), and test_vibration().

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

◆ operator=()

DataValidatorGroup DataValidatorGroup::operator= ( const DataValidatorGroup )
private

◆ print()

void DataValidatorGroup::print ( )

Print the validator value.

Definition at line 276 of file data_validator_group.cpp.

References _curr_best, _first, _prev_best, _toggle_count, ECL_INFO, DataValidator::ERROR_FLAG_HIGH_ERRCOUNT, DataValidator::ERROR_FLAG_HIGH_ERRDENSITY, DataValidator::ERROR_FLAG_NO_DATA, DataValidator::ERROR_FLAG_NO_ERROR, DataValidator::ERROR_FLAG_STALE_DATA, DataValidator::ERROR_FLAG_TIMEOUT, DataValidator::print(), DataValidator::priority(), DataValidator::sibling(), DataValidator::state(), and DataValidator::used().

Referenced by failover_count(), sensors::VotedSensorsUpdate::printStatus(), and setup_base_group().

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

◆ put()

void DataValidatorGroup::put ( unsigned  index,
uint64_t  timestamp,
const float  val[3],
uint64_t  error_count,
int  priority 
)

Put an item into the validator group.

Parameters
indexSensor index
timestampThe timestamp of the measurement
valThe 3D vector
error_countThe current error count of the sensor
priorityThe priority of the sensor

Definition at line 120 of file data_validator_group.cpp.

References _first, DataValidator::put(), and DataValidator::sibling().

Referenced by sensors::VotedSensorsUpdate::accelPoll(), sensors::VotedSensorsUpdate::baroPoll(), fill_one_with_valid_data(), fill_two_with_valid_data(), sensors::VotedSensorsUpdate::gyroPoll(), sensors::VotedSensorsUpdate::magPoll(), test_priority_switch(), and test_simple_failover().

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

◆ set_equal_value_threshold()

void DataValidatorGroup::set_equal_value_threshold ( uint32_t  threshold)

Set the equal count threshold for the whole group.

Parameters
thresholdThe number of equal values before considering the sensor stale

Definition at line 108 of file data_validator_group.cpp.

References _first, DataValidator::set_equal_value_threshold(), and DataValidator::sibling().

Referenced by failover_count(), setup_base_group(), and sensors::VotedSensorsUpdate::VotedSensorsUpdate().

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

◆ set_timeout()

void DataValidatorGroup::set_timeout ( uint32_t  timeout_interval_us)

Set the timeout value for the whole group.

Parameters
timeout_interval_usThe timeout interval in microseconds

Definition at line 95 of file data_validator_group.cpp.

References _first, _timeout_interval_us, DataValidator::set_timeout(), and DataValidator::sibling().

Referenced by failover_count(), setup_base_group(), and sensors::VotedSensorsUpdate::VotedSensorsUpdate().

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

Member Data Documentation

◆ _curr_best

int DataValidatorGroup::_curr_best {-1}
private

currently best index

Definition at line 141 of file data_validator_group.h.

Referenced by get_best(), and print().

◆ _first

◆ _first_failover_time

uint64_t DataValidatorGroup::_first_failover_time {0}
private

timestamp where the first failover occured or zero if none occured

Definition at line 144 of file data_validator_group.h.

Referenced by get_best().

◆ _last

DataValidator* DataValidatorGroup::_last {nullptr}
private

last node in the group

Definition at line 137 of file data_validator_group.h.

Referenced by add_new_validator(), and DataValidatorGroup().

◆ _prev_best

int DataValidatorGroup::_prev_best {-1}
private

the previous best index

Definition at line 142 of file data_validator_group.h.

Referenced by failover_index(), failover_state(), get_best(), and print().

◆ _timeout_interval_us

uint32_t DataValidatorGroup::_timeout_interval_us {0}
private

currently set timeout

Definition at line 139 of file data_validator_group.h.

Referenced by add_new_validator(), DataValidatorGroup(), and set_timeout().

◆ _toggle_count

unsigned DataValidatorGroup::_toggle_count {0}
private

number of back and forth switches between two sensors

Definition at line 146 of file data_validator_group.h.

Referenced by failover_count(), get_best(), and print().

◆ MIN_REGULAR_CONFIDENCE

constexpr float DataValidatorGroup::MIN_REGULAR_CONFIDENCE = 0.9f
staticprivate

Definition at line 148 of file data_validator_group.h.

Referenced by get_best().


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