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

#include <AirspeedValidator.hpp>

Collaboration diagram for AirspeedValidator:

Public Member Functions

 AirspeedValidator ()=default
 
 ~AirspeedValidator ()=default
 
void update_airspeed_validator (const airspeed_validator_update_data &input_data)
 
float get_IAS ()
 
float get_EAS ()
 
float get_TAS ()
 
bool get_airspeed_valid ()
 
float get_EAS_scale ()
 
wind_estimate_s get_wind_estimator_states (uint64_t timestamp)
 
void set_wind_estimator_wind_p_noise (float wind_sigma)
 
void set_wind_estimator_tas_scale_p_noise (float tas_scale_sigma)
 
void set_wind_estimator_tas_noise (float tas_sigma)
 
void set_wind_estimator_beta_noise (float beta_var)
 
void set_wind_estimator_tas_gate (uint8_t gate_size)
 
void set_wind_estimator_beta_gate (uint8_t gate_size)
 
void set_wind_estimator_scale_estimation_on (bool scale_estimation_on)
 
void set_airspeed_scale_manual (float airspeed_scale_manual)
 
void set_tas_innov_threshold (float tas_innov_threshold)
 
void set_tas_innov_integ_threshold (float tas_innov_integ_threshold)
 
void set_checks_fail_delay (float checks_fail_delay)
 
void set_checks_clear_delay (float checks_clear_delay)
 
void set_airspeed_stall (float airspeed_stall)
 

Private Member Functions

void update_in_fixed_wing_flight (bool in_fixed_wing_flight)
 
void update_wind_estimator (const uint64_t timestamp, float airspeed_true_raw, bool lpos_valid, float lpos_vx, float lpos_vy, float lpos_vz, float lpos_evh, float lpos_evv, const float att_q[4])
 
void update_EAS_scale ()
 
void update_EAS_TAS (float air_pressure_pa, float air_temperature_celsius)
 
void check_airspeed_innovation (uint64_t timestamp, float estimator_status_vel_test_ratio, float estimator_status_mag_test_ratio)
 
void check_load_factor (float accel_z)
 
void update_airspeed_valid_status (const uint64_t timestamp)
 

Private Attributes

WindEstimator _wind_estimator {}
 wind estimator instance running in this particular airspeedValidator More...
 
bool _wind_estimator_scale_estimation_on {false}
 online scale estimation (IAS–>CAS/EAS) is on More...
 
float _airspeed_scale_manual {1.0f}
 manually entered airspeed scale More...
 
bool _in_fixed_wing_flight {false}
 variable to bypass innovation and load factor checks More...
 
float _IAS {0.0f}
 indicated airsped in m/s More...
 
float _EAS {0.0f}
 equivalent airspeed in m/s More...
 
float _TAS {0.0f}
 true airspeed in m/s More...
 
float _EAS_scale {1.0f}
 scale factor from IAS to EAS More...
 
uint64_t _time_last_airspeed {0}
 time last airspeed measurement was received (uSec) More...
 
bool _data_stopped_failed {false}
 data_stopp check has detected failure More...
 
hrt_abstime _previous_airspeed_timestamp {0}
 timestamp from previous measurement input, to check validity of measurement More...
 
float _tas_gate {1.0f}
 gate size of airspeed innovation (to calculate tas_test_ratio) More...
 
bool _innovations_check_failed {false}
 true when airspeed innovations have failed consistency checks More...
 
float _tas_innov_threshold {1.0}
 innovation error threshold for triggering innovation check failure More...
 
float _tas_innov_integ_threshold {-1.0}
 integrator innovation error threshold for triggering innovation check failure More...
 
uint64_t _time_last_aspd_innov_check {0}
 time airspeed innovation was last checked (uSec) More...
 
uint64_t _time_last_tas_pass {0}
 last time innovation checks passed More...
 
uint64_t _time_last_tas_fail {0}
 last time innovation checks failed More...
 
float _apsd_innov_integ_state {0.0f}
 inegral of excess normalised airspeed innovation (sec) More...
 
uint64_t _time_wind_estimator_initialized {0}
 time last time wind estimator was initialized (uSec) More...
 
bool _load_factor_check_failed {false}
 load_factor check has detected failure More...
 
float _airspeed_stall {8.0f}
 stall speed of aircraft used for load factor check More...
 
float _load_factor_ratio {0.5f}
 ratio of maximum load factor predicted by stall speed to measured load factor More...
 
bool _airspeed_valid {false}
 airspeed valid (pitot or groundspeed-windspeed) More...
 
int _checks_fail_delay {3}
 delay for airspeed invalid declaration after single check failure (Sec) More...
 
int _checks_clear_delay {3}
 delay for airspeed valid declaration after all checks passed again (Sec) More...
 
bool _airspeed_failing {false}
 airspeed sensor checks have detected failure, but not yet declared failed More...
 
uint64_t _time_checks_passed {0}
 time the checks have last passed (uSec) More...
 
uint64_t _time_checks_failed {0}
 time the checks have last not passed (uSec) More...
 

Static Private Attributes

static constexpr uint64_t TAS_INNOV_FAIL_DELAY {1_s}
 time required for innovation levels to pass or fail (usec) More...
 

Detailed Description

Definition at line 73 of file AirspeedValidator.hpp.

Constructor & Destructor Documentation

◆ AirspeedValidator()

AirspeedValidator::AirspeedValidator ( )
default

◆ ~AirspeedValidator()

AirspeedValidator::~AirspeedValidator ( )
default

Member Function Documentation

◆ check_airspeed_innovation()

void AirspeedValidator::check_airspeed_innovation ( uint64_t  timestamp,
float  estimator_status_vel_test_ratio,
float  estimator_status_mag_test_ratio 
)
private

Definition at line 139 of file AirspeedValidator.cpp.

References _airspeed_valid, _apsd_innov_integ_state, _in_fixed_wing_flight, _innovations_check_failed, _tas_gate, _tas_innov_integ_threshold, _tas_innov_threshold, _time_last_aspd_innov_check, _time_last_tas_fail, _time_last_tas_pass, _time_wind_estimator_initialized, _wind_estimator, f(), WindEstimator::get_tas_innov(), WindEstimator::get_tas_innov_var(), WindEstimator::get_wind_estimator_reset(), math::max(), and TAS_INNOV_FAIL_DELAY.

Referenced by update_airspeed_validator().

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

◆ check_load_factor()

void AirspeedValidator::check_load_factor ( float  accel_z)
private

Definition at line 198 of file AirspeedValidator.cpp.

References _airspeed_stall, _EAS, _in_fixed_wing_flight, _load_factor_check_failed, _load_factor_ratio, math::constrain(), and f().

Referenced by update_airspeed_validator().

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

◆ get_airspeed_valid()

bool AirspeedValidator::get_airspeed_valid ( )
inline

Definition at line 84 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::select_airspeed_and_publish().

Here is the caller graph for this function:

◆ get_EAS()

float AirspeedValidator::get_EAS ( )
inline

Definition at line 82 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::select_airspeed_and_publish().

Here is the caller graph for this function:

◆ get_EAS_scale()

float AirspeedValidator::get_EAS_scale ( )
inline

Definition at line 85 of file AirspeedValidator.hpp.

◆ get_IAS()

float AirspeedValidator::get_IAS ( )
inline

Definition at line 81 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::select_airspeed_and_publish().

Here is the caller graph for this function:

◆ get_TAS()

float AirspeedValidator::get_TAS ( )
inline

Definition at line 83 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::select_airspeed_and_publish().

Here is the caller graph for this function:

◆ get_wind_estimator_states()

wind_estimate_s AirspeedValidator::get_wind_estimator_states ( uint64_t  timestamp)

◆ set_airspeed_scale_manual()

void AirspeedValidator::set_airspeed_scale_manual ( float  airspeed_scale_manual)

Definition at line 113 of file AirspeedValidator.cpp.

References _airspeed_scale_manual, _wind_estimator, WindEstimator::enforce_airspeed_scale(), and f().

Referenced by AirspeedModule::update_params().

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

◆ set_airspeed_stall()

void AirspeedValidator::set_airspeed_stall ( float  airspeed_stall)
inline

Definition at line 111 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_checks_clear_delay()

void AirspeedValidator::set_checks_clear_delay ( float  checks_clear_delay)
inline

Definition at line 109 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_checks_fail_delay()

void AirspeedValidator::set_checks_fail_delay ( float  checks_fail_delay)
inline

Definition at line 108 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_tas_innov_integ_threshold()

void AirspeedValidator::set_tas_innov_integ_threshold ( float  tas_innov_integ_threshold)
inline

Definition at line 107 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_tas_innov_threshold()

void AirspeedValidator::set_tas_innov_threshold ( float  tas_innov_threshold)
inline

Definition at line 106 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_wind_estimator_beta_gate()

void AirspeedValidator::set_wind_estimator_beta_gate ( uint8_t  gate_size)
inline

Definition at line 100 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_wind_estimator_beta_noise()

void AirspeedValidator::set_wind_estimator_beta_noise ( float  beta_var)
inline

Definition at line 93 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_wind_estimator_scale_estimation_on()

void AirspeedValidator::set_wind_estimator_scale_estimation_on ( bool  scale_estimation_on)
inline

Definition at line 101 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_wind_estimator_tas_gate()

void AirspeedValidator::set_wind_estimator_tas_gate ( uint8_t  gate_size)
inline

Definition at line 94 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_wind_estimator_tas_noise()

void AirspeedValidator::set_wind_estimator_tas_noise ( float  tas_sigma)
inline

Definition at line 92 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_wind_estimator_tas_scale_p_noise()

void AirspeedValidator::set_wind_estimator_tas_scale_p_noise ( float  tas_scale_sigma)
inline

Definition at line 91 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ set_wind_estimator_wind_p_noise()

void AirspeedValidator::set_wind_estimator_wind_p_noise ( float  wind_sigma)
inline

Definition at line 90 of file AirspeedValidator.hpp.

Referenced by AirspeedModule::update_params().

Here is the caller graph for this function:

◆ update_airspeed_valid_status()

void AirspeedValidator::update_airspeed_valid_status ( const uint64_t  timestamp)
private

Definition at line 227 of file AirspeedValidator.cpp.

References _airspeed_failing, _airspeed_valid, _checks_clear_delay, _checks_fail_delay, _data_stopped_failed, _innovations_check_failed, _load_factor_check_failed, _time_checks_failed, _time_checks_passed, and _time_last_airspeed.

Referenced by update_airspeed_validator().

Here is the caller graph for this function:

◆ update_airspeed_validator()

void AirspeedValidator::update_airspeed_validator ( const airspeed_validator_update_data input_data)

◆ update_EAS_scale()

void AirspeedValidator::update_EAS_scale ( )
private

Definition at line 120 of file AirspeedValidator.cpp.

References _airspeed_scale_manual, _EAS_scale, _wind_estimator, math::constrain(), WindEstimator::get_tas_scale(), and WindEstimator::is_estimate_valid().

Referenced by update_airspeed_validator().

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

◆ update_EAS_TAS()

void AirspeedValidator::update_EAS_TAS ( float  air_pressure_pa,
float  air_temperature_celsius 
)
private

Definition at line 132 of file AirspeedValidator.cpp.

References _EAS, _EAS_scale, _IAS, _TAS, calc_EAS_from_IAS(), and calc_TAS_from_EAS().

Referenced by update_airspeed_validator().

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

◆ update_in_fixed_wing_flight()

void AirspeedValidator::update_in_fixed_wing_flight ( bool  in_fixed_wing_flight)
inlineprivate

Definition at line 159 of file AirspeedValidator.hpp.

Referenced by update_airspeed_validator().

Here is the caller graph for this function:

◆ update_wind_estimator()

void AirspeedValidator::update_wind_estimator ( const uint64_t  timestamp,
float  airspeed_true_raw,
bool  lpos_valid,
float  lpos_vx,
float  lpos_vy,
float  lpos_vz,
float  lpos_evh,
float  lpos_evv,
const float  att_q[4] 
)
private

Definition at line 67 of file AirspeedValidator.cpp.

References _in_fixed_wing_flight, _wind_estimator, WindEstimator::fuse_airspeed(), WindEstimator::fuse_beta(), and WindEstimator::update().

Referenced by update_airspeed_validator().

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

Member Data Documentation

◆ _airspeed_failing

bool AirspeedValidator::_airspeed_failing {false}
private

airspeed sensor checks have detected failure, but not yet declared failed

Definition at line 155 of file AirspeedValidator.hpp.

Referenced by update_airspeed_valid_status().

◆ _airspeed_scale_manual

float AirspeedValidator::_airspeed_scale_manual {1.0f}
private

manually entered airspeed scale

Definition at line 119 of file AirspeedValidator.hpp.

Referenced by set_airspeed_scale_manual(), and update_EAS_scale().

◆ _airspeed_stall

float AirspeedValidator::_airspeed_stall {8.0f}
private

stall speed of aircraft used for load factor check

Definition at line 148 of file AirspeedValidator.hpp.

Referenced by check_load_factor().

◆ _airspeed_valid

bool AirspeedValidator::_airspeed_valid {false}
private

airspeed valid (pitot or groundspeed-windspeed)

Definition at line 152 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation(), and update_airspeed_valid_status().

◆ _apsd_innov_integ_state

float AirspeedValidator::_apsd_innov_integ_state {0.0f}
private

inegral of excess normalised airspeed innovation (sec)

Definition at line 142 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().

◆ _checks_clear_delay

int AirspeedValidator::_checks_clear_delay {3}
private

delay for airspeed valid declaration after all checks passed again (Sec)

Definition at line 154 of file AirspeedValidator.hpp.

Referenced by update_airspeed_valid_status().

◆ _checks_fail_delay

int AirspeedValidator::_checks_fail_delay {3}
private

delay for airspeed invalid declaration after single check failure (Sec)

Definition at line 153 of file AirspeedValidator.hpp.

Referenced by update_airspeed_valid_status().

◆ _data_stopped_failed

bool AirspeedValidator::_data_stopped_failed {false}
private

data_stopp check has detected failure

Definition at line 131 of file AirspeedValidator.hpp.

Referenced by update_airspeed_valid_status().

◆ _EAS

float AirspeedValidator::_EAS {0.0f}
private

equivalent airspeed in m/s

Definition at line 124 of file AirspeedValidator.hpp.

Referenced by check_load_factor(), and update_EAS_TAS().

◆ _EAS_scale

float AirspeedValidator::_EAS_scale {1.0f}
private

scale factor from IAS to EAS

Definition at line 126 of file AirspeedValidator.hpp.

Referenced by update_EAS_scale(), and update_EAS_TAS().

◆ _IAS

float AirspeedValidator::_IAS {0.0f}
private

indicated airsped in m/s

Definition at line 123 of file AirspeedValidator.hpp.

Referenced by update_airspeed_validator(), and update_EAS_TAS().

◆ _in_fixed_wing_flight

bool AirspeedValidator::_in_fixed_wing_flight {false}
private

variable to bypass innovation and load factor checks

Definition at line 122 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation(), check_load_factor(), and update_wind_estimator().

◆ _innovations_check_failed

bool AirspeedValidator::_innovations_check_failed {false}
private

true when airspeed innovations have failed consistency checks

Definition at line 136 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation(), and update_airspeed_valid_status().

◆ _load_factor_check_failed

bool AirspeedValidator::_load_factor_check_failed {false}
private

load_factor check has detected failure

Definition at line 147 of file AirspeedValidator.hpp.

Referenced by check_load_factor(), and update_airspeed_valid_status().

◆ _load_factor_ratio

float AirspeedValidator::_load_factor_ratio {0.5f}
private

ratio of maximum load factor predicted by stall speed to measured load factor

Definition at line 149 of file AirspeedValidator.hpp.

Referenced by check_load_factor().

◆ _previous_airspeed_timestamp

hrt_abstime AirspeedValidator::_previous_airspeed_timestamp {0}
private

timestamp from previous measurement input, to check validity of measurement

Definition at line 132 of file AirspeedValidator.hpp.

Referenced by update_airspeed_validator().

◆ _TAS

float AirspeedValidator::_TAS {0.0f}
private

true airspeed in m/s

Definition at line 125 of file AirspeedValidator.hpp.

Referenced by update_EAS_TAS().

◆ _tas_gate

float AirspeedValidator::_tas_gate {1.0f}
private

gate size of airspeed innovation (to calculate tas_test_ratio)

Definition at line 135 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().

◆ _tas_innov_integ_threshold

float AirspeedValidator::_tas_innov_integ_threshold {-1.0}
private

integrator innovation error threshold for triggering innovation check failure

Definition at line 138 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().

◆ _tas_innov_threshold

float AirspeedValidator::_tas_innov_threshold {1.0}
private

innovation error threshold for triggering innovation check failure

Definition at line 137 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().

◆ _time_checks_failed

uint64_t AirspeedValidator::_time_checks_failed {0}
private

time the checks have last not passed (uSec)

Definition at line 157 of file AirspeedValidator.hpp.

Referenced by update_airspeed_valid_status().

◆ _time_checks_passed

uint64_t AirspeedValidator::_time_checks_passed {0}
private

time the checks have last passed (uSec)

Definition at line 156 of file AirspeedValidator.hpp.

Referenced by update_airspeed_valid_status().

◆ _time_last_airspeed

uint64_t AirspeedValidator::_time_last_airspeed {0}
private

time last airspeed measurement was received (uSec)

Definition at line 128 of file AirspeedValidator.hpp.

Referenced by update_airspeed_valid_status(), and update_airspeed_validator().

◆ _time_last_aspd_innov_check

uint64_t AirspeedValidator::_time_last_aspd_innov_check {0}
private

time airspeed innovation was last checked (uSec)

Definition at line 139 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().

◆ _time_last_tas_fail

uint64_t AirspeedValidator::_time_last_tas_fail {0}
private

last time innovation checks failed

Definition at line 141 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().

◆ _time_last_tas_pass

uint64_t AirspeedValidator::_time_last_tas_pass {0}
private

last time innovation checks passed

Definition at line 140 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().

◆ _time_wind_estimator_initialized

uint64_t AirspeedValidator::_time_wind_estimator_initialized {0}
private

time last time wind estimator was initialized (uSec)

Definition at line 144 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().

◆ _wind_estimator

WindEstimator AirspeedValidator::_wind_estimator {}
private

wind estimator instance running in this particular airspeedValidator

Definition at line 115 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation(), get_wind_estimator_states(), set_airspeed_scale_manual(), update_EAS_scale(), and update_wind_estimator().

◆ _wind_estimator_scale_estimation_on

bool AirspeedValidator::_wind_estimator_scale_estimation_on {false}
private

online scale estimation (IAS–>CAS/EAS) is on

Definition at line 118 of file AirspeedValidator.hpp.

◆ TAS_INNOV_FAIL_DELAY

constexpr uint64_t AirspeedValidator::TAS_INNOV_FAIL_DELAY {1_s}
staticprivate

time required for innovation levels to pass or fail (usec)

Definition at line 143 of file AirspeedValidator.hpp.

Referenced by check_airspeed_innovation().


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