PX4 Firmware
PX4 Autopilot Software http://px4.io
estimator::parameters Struct Reference

#include <common.h>

Collaboration diagram for estimator::parameters:

Public Attributes

int32_t fusion_mode {MASK_USE_GPS}
 bitmasked integer that selects which aiding sources will be used More...
 
int32_t vdist_sensor_type {VDIST_SENSOR_BARO}
 selects the primary source for height data More...
 
int32_t sensor_interval_min_ms {20}
 minimum time of arrival difference between non IMU sensor updates. Sets the size of the observation buffers. (mSec) More...
 
float min_delay_ms {0.0f}
 Maximum time delay of any sensor used to increase buffer length to handle large timing jitter (mSec) More...
 
float mag_delay_ms {0.0f}
 magnetometer measurement delay relative to the IMU (mSec) More...
 
float baro_delay_ms {0.0f}
 barometer height measurement delay relative to the IMU (mSec) More...
 
float gps_delay_ms {110.0f}
 GPS measurement delay relative to the IMU (mSec) More...
 
float airspeed_delay_ms {100.0f}
 airspeed measurement delay relative to the IMU (mSec) More...
 
float flow_delay_ms {5.0f}
 optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval More...
 
float range_delay_ms {5.0f}
 range finder measurement delay relative to the IMU (mSec) More...
 
float ev_delay_ms {100.0f}
 off-board vision measurement delay relative to the IMU (mSec) More...
 
float auxvel_delay_ms {0.0f}
 auxiliary velocity measurement delay relative to the IMU (mSec) More...
 
float gyro_noise {1.5e-2f}
 IMU angular rate noise used for covariance prediction (rad/sec) More...
 
float accel_noise {3.5e-1f}
 IMU acceleration noise use for covariance prediction (m/sec**2) More...
 
float gyro_bias_p_noise {1.0e-3f}
 process noise for IMU rate gyro bias prediction (rad/sec**2) More...
 
float accel_bias_p_noise {6.0e-3f}
 process noise for IMU accelerometer bias prediction (m/sec**3) More...
 
float mage_p_noise {1.0e-3f}
 process noise for earth magnetic field prediction (Gauss/sec) More...
 
float magb_p_noise {1.0e-4f}
 process noise for body magnetic field prediction (Gauss/sec) More...
 
float wind_vel_p_noise {1.0e-1f}
 process noise for wind velocity prediction (m/sec**2) More...
 
float wind_vel_p_noise_scaler {0.5f}
 scaling of wind process noise with vertical velocity More...
 
float terrain_p_noise {5.0f}
 process noise for terrain offset (m/sec) More...
 
float terrain_gradient {0.5f}
 gradient of terrain used to estimate process noise due to changing position (m/m) More...
 
float switch_on_gyro_bias {0.1f}
 1-sigma gyro bias uncertainty at switch on (rad/sec) More...
 
float switch_on_accel_bias {0.2f}
 1-sigma accelerometer bias uncertainty at switch on (m/sec**2) More...
 
float initial_tilt_err {0.1f}
 1-sigma tilt error after initial alignment using gravity vector (rad) More...
 
float initial_wind_uncertainty {1.0f}
 1-sigma initial uncertainty in wind velocity (m/sec) More...
 
float gps_vel_noise {5.0e-1f}
 minimum allowed observation noise for gps velocity fusion (m/sec) More...
 
float gps_pos_noise {0.5f}
 minimum allowed observation noise for gps position fusion (m) More...
 
float pos_noaid_noise {10.0f}
 observation noise for non-aiding position fusion (m) More...
 
float baro_noise {2.0f}
 observation noise for barometric height fusion (m) More...
 
float baro_innov_gate {5.0f}
 barometric and GPS height innovation consistency gate size (STD) More...
 
float gps_pos_innov_gate {5.0f}
 GPS horizontal position innovation consistency gate size (STD) More...
 
float gps_vel_innov_gate {5.0f}
 GPS velocity innovation consistency gate size (STD) More...
 
float gnd_effect_deadzone {5.0f}
 Size of deadzone applied to negative baro innovations when ground effect compensation is active (m) More...
 
float gnd_effect_max_hgt {0.5f}
 Height above ground at which baro ground effect becomes insignificant (m) More...
 
float mag_heading_noise {3.0e-1f}
 measurement noise used for simple heading fusion (rad) More...
 
float mag_noise {5.0e-2f}
 measurement noise used for 3-axis magnetoemeter fusion (Gauss) More...
 
float mag_declination_deg {0.0f}
 magnetic declination (degrees) More...
 
float heading_innov_gate {2.6f}
 heading fusion innovation consistency gate size (STD) More...
 
float mag_innov_gate {3.0f}
 magnetometer fusion innovation consistency gate size (STD) More...
 
int32_t mag_declination_source {7}
 bitmask used to control the handling of declination data More...
 
int32_t mag_fusion_type {0}
 integer used to specify the type of magnetometer fusion used More...
 
float mag_acc_gate {0.5f}
 when in auto select mode, heading fusion will be used when manoeuvre accel is lower than this (m/sec**2) More...
 
float mag_yaw_rate_gate {0.25f}
 yaw rate threshold used by mode select logic (rad/sec) More...
 
float tas_innov_gate {5.0f}
 True Airspeed innovation consistency gate size (STD) More...
 
float eas_noise {1.4f}
 EAS measurement noise standard deviation used for airspeed fusion (m/s) More...
 
float beta_innov_gate {5.0f}
 synthetic sideslip innovation consistency gate size in standard deviation (STD) More...
 
float beta_noise {0.3f}
 synthetic sideslip noise (rad) More...
 
float beta_avg_ft_us {150000.0f}
 The average time between synthetic sideslip measurements (uSec) More...
 
float range_noise {0.1f}
 observation noise for range finder measurements (m) More...
 
float range_innov_gate {5.0f}
 range finder fusion innovation consistency gate size (STD) More...
 
float rng_gnd_clearance {0.1f}
 minimum valid value for range when on ground (m) More...
 
float rng_sens_pitch {0.0f}
 Pitch offset of the range sensor (rad). Sensor points out along Z axis when offset is zero. Positive rotation is RH about Y axis. More...
 
float range_noise_scaler {0.0f}
 scaling from range measurement to noise (m/m) More...
 
float vehicle_variance_scaler {0.0f}
 gain applied to vehicle height variance used in calculation of height above ground observation variance More...
 
float max_hagl_for_range_aid {5.0f}
 maximum height above ground for which we allow to use the range finder as height source (if range_aid == 1) More...
 
float max_vel_for_range_aid {1.0f}
 maximum ground velocity for which we allow to use the range finder as height source (if range_aid == 1) More...
 
int32_t range_aid {0}
 allow switching primary height source to range finder if certain conditions are met More...
 
float range_aid_innov_gate {1.0f}
 gate size used for innovation consistency checks for range aid fusion More...
 
float range_cos_max_tilt {0.7071f}
 cosine of the maximum tilt angle from the vertical that permits use of range finder and flow data More...
 
float range_stuck_threshold {0.1f}
 minimum variation in range finder reading required to declare a range finder 'unstuck' when readings recommence after being out of range (m) More...
 
int32_t range_signal_hysteresis_ms {1000}
 minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (ms) More...
 
float ev_vel_innov_gate {3.0f}
 vision velocity fusion innovation consistency gate size (STD) More...
 
float ev_pos_innov_gate {5.0f}
 vision position fusion innovation consistency gate size (STD) More...
 
float flow_noise {0.15f}
 observation noise for optical flow LOS rate measurements (rad/sec) More...
 
float flow_noise_qual_min {0.5f}
 observation noise for optical flow LOS rate measurements when flow sensor quality is at the minimum useable (rad/sec) More...
 
int32_t flow_qual_min {1}
 minimum acceptable quality integer from the flow sensor More...
 
float flow_innov_gate {3.0f}
 optical flow fusion innovation consistency gate size (STD) More...
 
int32_t gps_check_mask {21}
 bitmask used to control which GPS quality checks are used More...
 
float req_hacc {5.0f}
 maximum acceptable horizontal position error (m) More...
 
float req_vacc {8.0f}
 maximum acceptable vertical position error (m) More...
 
float req_sacc {1.0f}
 maximum acceptable speed error (m/s) More...
 
int32_t req_nsats {6}
 minimum acceptable satellite count More...
 
float req_pdop {2.0f}
 maximum acceptable position dilution of precision More...
 
float req_hdrift {0.3f}
 maximum acceptable horizontal drift speed (m/s) More...
 
float req_vdrift {0.5f}
 maximum acceptable vertical drift speed (m/s) More...
 
Vector3f imu_pos_body
 xyz position of IMU in body frame (m) More...
 
Vector3f gps_pos_body
 xyz position of the GPS antenna in body frame (m) More...
 
Vector3f rng_pos_body
 xyz position of range sensor in body frame (m) More...
 
Vector3f flow_pos_body
 xyz position of range sensor focal point in body frame (m) More...
 
Vector3f ev_pos_body
 xyz position of VI-sensor focal point in body frame (m) More...
 
float vel_Tau {0.25f}
 velocity state correction time constant (1/sec) More...
 
float pos_Tau {0.25f}
 position state correction time constant (1/sec) More...
 
float acc_bias_lim {0.4f}
 maximum accel bias magnitude (m/sec**2) More...
 
float acc_bias_learn_acc_lim {25.0f}
 learning is disabled if the magnitude of the IMU acceleration vector is greater than this (m/sec**2) More...
 
float acc_bias_learn_gyr_lim {3.0f}
 learning is disabled if the magnitude of the IMU angular rate vector is greater than this (rad/sec) More...
 
float acc_bias_learn_tc {0.5f}
 time constant used to control the decaying envelope filters applied to the accel and gyro magnitudes (sec) More...
 
unsigned reset_timeout_max {7000000}
 maximum time we allow horizontal inertial dead reckoning before attempting to reset the states to the measurement or change _control_status if the data is unavailable (uSec) More...
 
unsigned no_aid_timeout_max {1000000}
 maximum lapsed time from last fusion of a measurement that constrains horizontal velocity drift before the EKF will determine that the sensor is no longer contributing to aiding (uSec) More...
 
int32_t valid_timeout_max {5000000}
 amount of time spent inertial dead reckoning before the estimator reports the state estimates as invalid (uSec) More...
 
float drag_noise {2.5f}
 observation noise variance for drag specific force measurements (m/sec**2)**2 More...
 
float bcoef_x {25.0f}
 ballistic coefficient along the X-axis (kg/m**2) More...
 
float bcoef_y {25.0f}
 ballistic coefficient along the Y-axis (kg/m**2) More...
 
float vert_innov_test_lim {4.5f}
 Number of standard deviations allowed before the combined vertical velocity and position test is declared as failed. More...
 
int bad_acc_reset_delay_us {500000}
 Continuous time that the vertical position and velocity innovation test must fail before the states are reset (uSec) More...
 
float auxvel_noise {0.5f}
 minimum observation noise, uses reported noise if greater (m/s) More...
 
float auxvel_gate {5.0f}
 velocity fusion innovation consistency gate size (STD) More...
 
float is_moving_scaler {1.0f}
 gain scaler used to adjust the threshold for the on-ground movement detection. Larger values make the test less sensitive. More...
 
int32_t synthesize_mag_z {0}
 
int32_t check_mag_strength {0}
 

Detailed Description

Definition at line 220 of file common.h.

Member Data Documentation

◆ acc_bias_learn_acc_lim

float estimator::parameters::acc_bias_learn_acc_lim {25.0f}

learning is disabled if the magnitude of the IMU acceleration vector is greater than this (m/sec**2)

Definition at line 337 of file common.h.

Referenced by Ekf::predictCovariance().

◆ acc_bias_learn_gyr_lim

float estimator::parameters::acc_bias_learn_gyr_lim {3.0f}

learning is disabled if the magnitude of the IMU angular rate vector is greater than this (rad/sec)

Definition at line 338 of file common.h.

Referenced by Ekf::predictCovariance().

◆ acc_bias_learn_tc

float estimator::parameters::acc_bias_learn_tc {0.5f}

time constant used to control the decaying envelope filters applied to the accel and gyro magnitudes (sec)

Definition at line 339 of file common.h.

Referenced by Ekf::predictCovariance().

◆ acc_bias_lim

float estimator::parameters::acc_bias_lim {0.4f}

maximum accel bias magnitude (m/sec**2)

Definition at line 336 of file common.h.

Referenced by Ekf::constrainStates(), and Ekf::fixCovarianceErrors().

◆ accel_bias_p_noise

float estimator::parameters::accel_bias_p_noise {6.0e-3f}

process noise for IMU accelerometer bias prediction (m/sec**3)

Definition at line 243 of file common.h.

Referenced by Ekf::predictCovariance().

◆ accel_noise

float estimator::parameters::accel_noise {3.5e-1f}

IMU acceleration noise use for covariance prediction (m/sec**2)

Definition at line 239 of file common.h.

Referenced by Ekf::predictCovariance().

◆ airspeed_delay_ms

float estimator::parameters::airspeed_delay_ms {100.0f}

airspeed measurement delay relative to the IMU (mSec)

Definition at line 231 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and EstimatorInterface::setAirspeedData().

◆ auxvel_delay_ms

float estimator::parameters::auxvel_delay_ms {0.0f}

auxiliary velocity measurement delay relative to the IMU (mSec)

Definition at line 235 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and EstimatorInterface::setAuxVelData().

◆ auxvel_gate

float estimator::parameters::auxvel_gate {5.0f}

velocity fusion innovation consistency gate size (STD)

Definition at line 357 of file common.h.

Referenced by Ekf::controlAuxVelFusion().

◆ auxvel_noise

float estimator::parameters::auxvel_noise {0.5f}

minimum observation noise, uses reported noise if greater (m/s)

Definition at line 356 of file common.h.

◆ bad_acc_reset_delay_us

int estimator::parameters::bad_acc_reset_delay_us {500000}

Continuous time that the vertical position and velocity innovation test must fail before the states are reset (uSec)

Definition at line 353 of file common.h.

Referenced by Ekf::controlHeightSensorTimeouts().

◆ baro_delay_ms

float estimator::parameters::baro_delay_ms {0.0f}

barometer height measurement delay relative to the IMU (mSec)

Definition at line 229 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and EstimatorInterface::setBaroData().

◆ baro_innov_gate

float estimator::parameters::baro_innov_gate {5.0f}

barometric and GPS height innovation consistency gate size (STD)

Definition at line 262 of file common.h.

Referenced by Ekf::controlHeightSensorTimeouts(), and Ekf::fuseVelPosHeight().

◆ baro_noise

float estimator::parameters::baro_noise {2.0f}

observation noise for barometric height fusion (m)

Definition at line 261 of file common.h.

Referenced by Ekf::controlHeightSensorTimeouts(), Ekf::fuseVelPosHeight(), Ekf::initialiseCovariance(), and Ekf::resetHeight().

◆ bcoef_x

float estimator::parameters::bcoef_x {25.0f}

ballistic coefficient along the X-axis (kg/m**2)

Definition at line 348 of file common.h.

Referenced by Ekf::fuseDrag().

◆ bcoef_y

float estimator::parameters::bcoef_y {25.0f}

ballistic coefficient along the Y-axis (kg/m**2)

Definition at line 349 of file common.h.

Referenced by Ekf::fuseDrag().

◆ beta_avg_ft_us

float estimator::parameters::beta_avg_ft_us {150000.0f}

The average time between synthetic sideslip measurements (uSec)

Definition at line 286 of file common.h.

Referenced by Ekf::controlBetaFusion().

◆ beta_innov_gate

float estimator::parameters::beta_innov_gate {5.0f}

synthetic sideslip innovation consistency gate size in standard deviation (STD)

Definition at line 284 of file common.h.

Referenced by Ekf::fuseSideslip().

◆ beta_noise

float estimator::parameters::beta_noise {0.3f}

synthetic sideslip noise (rad)

Definition at line 285 of file common.h.

Referenced by Ekf::fuseSideslip().

◆ check_mag_strength

int32_t estimator::parameters::check_mag_strength {0}

Definition at line 364 of file common.h.

Referenced by Ekf::checkMagFieldStrength().

◆ drag_noise

float estimator::parameters::drag_noise {2.5f}

observation noise variance for drag specific force measurements (m/sec**2)**2

Definition at line 347 of file common.h.

Referenced by Ekf::fuseDrag().

◆ eas_noise

float estimator::parameters::eas_noise {1.4f}

EAS measurement noise standard deviation used for airspeed fusion (m/s)

Definition at line 281 of file common.h.

Referenced by Ekf::fuseAirspeed(), and Ekf::resetWindCovariance().

◆ ev_delay_ms

float estimator::parameters::ev_delay_ms {100.0f}

off-board vision measurement delay relative to the IMU (mSec)

Definition at line 234 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and EstimatorInterface::setExtVisionData().

◆ ev_pos_body

Vector3f estimator::parameters::ev_pos_body

xyz position of VI-sensor focal point in body frame (m)

Definition at line 329 of file common.h.

Referenced by Ekf::controlExternalVisionFusion().

◆ ev_pos_innov_gate

float estimator::parameters::ev_pos_innov_gate {5.0f}

vision position fusion innovation consistency gate size (STD)

Definition at line 305 of file common.h.

Referenced by Ekf::controlExternalVisionFusion(), and Ekf::fuseVelPosHeight().

◆ ev_vel_innov_gate

float estimator::parameters::ev_vel_innov_gate {3.0f}

vision velocity fusion innovation consistency gate size (STD)

Definition at line 304 of file common.h.

Referenced by Ekf::controlExternalVisionFusion().

◆ flow_delay_ms

float estimator::parameters::flow_delay_ms {5.0f}

optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval

Definition at line 232 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and EstimatorInterface::setOpticalFlowData().

◆ flow_innov_gate

float estimator::parameters::flow_innov_gate {3.0f}

optical flow fusion innovation consistency gate size (STD)

Definition at line 311 of file common.h.

Referenced by Ekf::fuseFlowForTerrain(), and Ekf::fuseOptFlow().

◆ flow_noise

float estimator::parameters::flow_noise {0.15f}

observation noise for optical flow LOS rate measurements (rad/sec)

Definition at line 308 of file common.h.

Referenced by Ekf::calcOptFlowMeasVar().

◆ flow_noise_qual_min

float estimator::parameters::flow_noise_qual_min {0.5f}

observation noise for optical flow LOS rate measurements when flow sensor quality is at the minimum useable (rad/sec)

Definition at line 309 of file common.h.

Referenced by Ekf::calcOptFlowMeasVar().

◆ flow_pos_body

Vector3f estimator::parameters::flow_pos_body

xyz position of range sensor focal point in body frame (m)

Definition at line 328 of file common.h.

Referenced by Ekf::fuseFlowForTerrain(), and Ekf::fuseOptFlow().

◆ flow_qual_min

int32_t estimator::parameters::flow_qual_min {1}

minimum acceptable quality integer from the flow sensor

Definition at line 310 of file common.h.

Referenced by Ekf::calcOptFlowMeasVar(), Ekf::controlOpticalFlowFusion(), and EstimatorInterface::setOpticalFlowData().

◆ fusion_mode

◆ gnd_effect_deadzone

float estimator::parameters::gnd_effect_deadzone {5.0f}

Size of deadzone applied to negative baro innovations when ground effect compensation is active (m)

Definition at line 265 of file common.h.

Referenced by Ekf::fuseVelPosHeight().

◆ gnd_effect_max_hgt

float estimator::parameters::gnd_effect_max_hgt {0.5f}

Height above ground at which baro ground effect becomes insignificant (m)

Definition at line 266 of file common.h.

◆ gps_check_mask

int32_t estimator::parameters::gps_check_mask {21}

bitmask used to control which GPS quality checks are used

Definition at line 315 of file common.h.

Referenced by Ekf::gps_is_good(), and Ekf2::Run().

◆ gps_delay_ms

float estimator::parameters::gps_delay_ms {110.0f}

GPS measurement delay relative to the IMU (mSec)

Definition at line 230 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and EstimatorInterface::setGpsData().

◆ gps_pos_body

Vector3f estimator::parameters::gps_pos_body

xyz position of the GPS antenna in body frame (m)

Definition at line 326 of file common.h.

Referenced by Ekf::controlGpsFusion().

◆ gps_pos_innov_gate

float estimator::parameters::gps_pos_innov_gate {5.0f}

GPS horizontal position innovation consistency gate size (STD)

Definition at line 263 of file common.h.

Referenced by Ekf::controlGpsFusion().

◆ gps_pos_noise

float estimator::parameters::gps_pos_noise {0.5f}

minimum allowed observation noise for gps position fusion (m)

Definition at line 259 of file common.h.

Referenced by Ekf::controlGpsFusion(), Ekf::controlVelPosFusion(), Ekf::fuseVelPosHeight(), and Ekf::initialiseCovariance().

◆ gps_vel_innov_gate

float estimator::parameters::gps_vel_innov_gate {5.0f}

GPS velocity innovation consistency gate size (STD)

Definition at line 264 of file common.h.

Referenced by Ekf::controlGpsFusion().

◆ gps_vel_noise

float estimator::parameters::gps_vel_noise {5.0e-1f}

minimum allowed observation noise for gps velocity fusion (m/sec)

Definition at line 258 of file common.h.

Referenced by Ekf::controlGpsFusion(), and Ekf::initialiseCovariance().

◆ gyro_bias_p_noise

float estimator::parameters::gyro_bias_p_noise {1.0e-3f}

process noise for IMU rate gyro bias prediction (rad/sec**2)

Definition at line 242 of file common.h.

Referenced by Ekf::predictCovariance().

◆ gyro_noise

float estimator::parameters::gyro_noise {1.5e-2f}

IMU angular rate noise used for covariance prediction (rad/sec)

Definition at line 238 of file common.h.

Referenced by Ekf::predictCovariance().

◆ heading_innov_gate

float estimator::parameters::heading_innov_gate {2.6f}

heading fusion innovation consistency gate size (STD)

Definition at line 272 of file common.h.

Referenced by Ekf::fuseGpsAntYaw(), and Ekf::fuseHeading().

◆ imu_pos_body

Vector3f estimator::parameters::imu_pos_body

◆ initial_tilt_err

float estimator::parameters::initial_tilt_err {0.1f}

1-sigma tilt error after initial alignment using gravity vector (rad)

Definition at line 254 of file common.h.

Referenced by Ekf::initialiseCovariance().

◆ initial_wind_uncertainty

float estimator::parameters::initial_wind_uncertainty {1.0f}

1-sigma initial uncertainty in wind velocity (m/sec)

Definition at line 255 of file common.h.

Referenced by Ekf::initialiseCovariance(), and Ekf::predictCovariance().

◆ is_moving_scaler

float estimator::parameters::is_moving_scaler {1.0f}

gain scaler used to adjust the threshold for the on-ground movement detection. Larger values make the test less sensitive.

Definition at line 360 of file common.h.

Referenced by EstimatorInterface::setIMUData().

◆ mag_acc_gate

float estimator::parameters::mag_acc_gate {0.5f}

when in auto select mode, heading fusion will be used when manoeuvre accel is lower than this (m/sec**2)

Definition at line 276 of file common.h.

Referenced by Ekf::checkYawAngleObservability().

◆ mag_declination_deg

float estimator::parameters::mag_declination_deg {0.0f}

magnetic declination (degrees)

Definition at line 271 of file common.h.

Referenced by Ekf::getMagDeclination(), and Ekf::limitDeclination().

◆ mag_declination_source

int32_t estimator::parameters::mag_declination_source {7}

bitmask used to control the handling of declination data

Definition at line 274 of file common.h.

Referenced by Ekf::checkMagDeclRequired(), Ekf::controlFusionModes(), Ekf::getMagDeclination(), and Ekf::limitDeclination().

◆ mag_delay_ms

float estimator::parameters::mag_delay_ms {0.0f}

magnetometer measurement delay relative to the IMU (mSec)

Definition at line 228 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and EstimatorInterface::setMagData().

◆ mag_fusion_type

int32_t estimator::parameters::mag_fusion_type {0}

integer used to specify the type of magnetometer fusion used

Definition at line 275 of file common.h.

Referenced by Ekf::controlMagFusion(), Ekf::initialiseFilter(), Ekf::resetMagHeading(), and Ekf::shouldInhibitMag().

◆ mag_heading_noise

float estimator::parameters::mag_heading_noise {3.0e-1f}

measurement noise used for simple heading fusion (rad)

Definition at line 269 of file common.h.

Referenced by Ekf::fuseGpsAntYaw(), Ekf::fuseHeading(), Ekf::initialiseFilter(), Ekf::resetGpsAntYaw(), and Ekf::resetMagHeading().

◆ mag_innov_gate

float estimator::parameters::mag_innov_gate {3.0f}

magnetometer fusion innovation consistency gate size (STD)

Definition at line 273 of file common.h.

Referenced by Ekf::fuseMag().

◆ mag_noise

float estimator::parameters::mag_noise {5.0e-2f}

measurement noise used for 3-axis magnetoemeter fusion (Gauss)

Definition at line 270 of file common.h.

Referenced by Ekf::fuseMag(), Ekf::initialiseCovariance(), Ekf::realignYawGPS(), Ekf::resetMagHeading(), and Ekf::resetMagRelatedCovariances().

◆ mag_yaw_rate_gate

float estimator::parameters::mag_yaw_rate_gate {0.25f}

yaw rate threshold used by mode select logic (rad/sec)

Definition at line 277 of file common.h.

Referenced by Ekf::checkMagBiasObservability().

◆ magb_p_noise

float estimator::parameters::magb_p_noise {1.0e-4f}

process noise for body magnetic field prediction (Gauss/sec)

Definition at line 245 of file common.h.

Referenced by Ekf::predictCovariance().

◆ mage_p_noise

float estimator::parameters::mage_p_noise {1.0e-3f}

process noise for earth magnetic field prediction (Gauss/sec)

Definition at line 244 of file common.h.

Referenced by Ekf::predictCovariance().

◆ max_hagl_for_range_aid

float estimator::parameters::max_hagl_for_range_aid {5.0f}

maximum height above ground for which we allow to use the range finder as height source (if range_aid == 1)

Definition at line 295 of file common.h.

Referenced by Ekf::checkRangeAidSuitability().

◆ max_vel_for_range_aid

float estimator::parameters::max_vel_for_range_aid {1.0f}

maximum ground velocity for which we allow to use the range finder as height source (if range_aid == 1)

Definition at line 296 of file common.h.

Referenced by Ekf::checkRangeAidSuitability().

◆ min_delay_ms

float estimator::parameters::min_delay_ms {0.0f}

Maximum time delay of any sensor used to increase buffer length to handle large timing jitter (mSec)

Definition at line 227 of file common.h.

Referenced by EstimatorInterface::initialise_interface().

◆ no_aid_timeout_max

unsigned estimator::parameters::no_aid_timeout_max {1000000}

maximum lapsed time from last fusion of a measurement that constrains horizontal velocity drift before the EKF will determine that the sensor is no longer contributing to aiding (uSec)

Definition at line 342 of file common.h.

Referenced by Ekf::update_deadreckoning_status().

◆ pos_noaid_noise

float estimator::parameters::pos_noaid_noise {10.0f}

observation noise for non-aiding position fusion (m)

Definition at line 260 of file common.h.

Referenced by Ekf::controlGpsFusion(), Ekf::controlVelPosFusion(), Ekf::fuseVelPosHeight(), Ekf::initialiseCovariance(), and Ekf::resetPosition().

◆ pos_Tau

float estimator::parameters::pos_Tau {0.25f}

position state correction time constant (1/sec)

Definition at line 333 of file common.h.

Referenced by Ekf::calculateOutputStates().

◆ range_aid

int32_t estimator::parameters::range_aid {0}

allow switching primary height source to range finder if certain conditions are met

Definition at line 297 of file common.h.

Referenced by Ekf::controlHeightFusion(), and Ekf::get_ekf_ctrl_limits().

◆ range_aid_innov_gate

float estimator::parameters::range_aid_innov_gate {1.0f}

gate size used for innovation consistency checks for range aid fusion

Definition at line 298 of file common.h.

Referenced by Ekf::checkRangeAidSuitability().

◆ range_cos_max_tilt

float estimator::parameters::range_cos_max_tilt {0.7071f}

cosine of the maximum tilt angle from the vertical that permits use of range finder and flow data

Definition at line 299 of file common.h.

Referenced by Ekf::controlFusionModes(), Ekf::fuseHagl(), Ekf::fuseVelPosHeight(), Ekf::initHagl(), and Ekf::updateRangeDataValidity().

◆ range_delay_ms

float estimator::parameters::range_delay_ms {5.0f}

range finder measurement delay relative to the IMU (mSec)

Definition at line 233 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and EstimatorInterface::setRangeData().

◆ range_innov_gate

float estimator::parameters::range_innov_gate {5.0f}

range finder fusion innovation consistency gate size (STD)

Definition at line 290 of file common.h.

Referenced by Ekf::fuseHagl(), and Ekf::fuseVelPosHeight().

◆ range_noise

float estimator::parameters::range_noise {0.1f}

observation noise for range finder measurements (m)

Definition at line 289 of file common.h.

Referenced by Ekf::fuseHagl(), Ekf::fuseVelPosHeight(), Ekf::initHagl(), Ekf::initialiseCovariance(), and Ekf::resetHeight().

◆ range_noise_scaler

float estimator::parameters::range_noise_scaler {0.0f}

scaling from range measurement to noise (m/m)

Definition at line 293 of file common.h.

Referenced by Ekf::fuseHagl(), and Ekf::fuseVelPosHeight().

◆ range_signal_hysteresis_ms

int32_t estimator::parameters::range_signal_hysteresis_ms {1000}

minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (ms)

Definition at line 301 of file common.h.

Referenced by Ekf::updateRangeDataValidity().

◆ range_stuck_threshold

float estimator::parameters::range_stuck_threshold {0.1f}

minimum variation in range finder reading required to declare a range finder 'unstuck' when readings recommence after being out of range (m)

Definition at line 300 of file common.h.

Referenced by Ekf::updateRangeDataStuck().

◆ req_hacc

float estimator::parameters::req_hacc {5.0f}

maximum acceptable horizontal position error (m)

Definition at line 316 of file common.h.

Referenced by Ekf::gps_is_good().

◆ req_hdrift

float estimator::parameters::req_hdrift {0.3f}

maximum acceptable horizontal drift speed (m/s)

Definition at line 321 of file common.h.

Referenced by Ekf::gps_is_good().

◆ req_nsats

int32_t estimator::parameters::req_nsats {6}

minimum acceptable satellite count

Definition at line 319 of file common.h.

Referenced by Ekf::gps_is_good().

◆ req_pdop

float estimator::parameters::req_pdop {2.0f}

maximum acceptable position dilution of precision

Definition at line 320 of file common.h.

Referenced by Ekf::gps_is_good().

◆ req_sacc

float estimator::parameters::req_sacc {1.0f}

maximum acceptable speed error (m/s)

Definition at line 318 of file common.h.

Referenced by Ekf::gps_is_good().

◆ req_vacc

float estimator::parameters::req_vacc {8.0f}

maximum acceptable vertical position error (m)

Definition at line 317 of file common.h.

Referenced by Ekf::controlHeightSensorTimeouts(), and Ekf::gps_is_good().

◆ req_vdrift

float estimator::parameters::req_vdrift {0.5f}

maximum acceptable vertical drift speed (m/s)

Definition at line 322 of file common.h.

Referenced by Ekf::gps_is_good().

◆ reset_timeout_max

unsigned estimator::parameters::reset_timeout_max {7000000}

maximum time we allow horizontal inertial dead reckoning before attempting to reset the states to the measurement or change _control_status if the data is unavailable (uSec)

Definition at line 341 of file common.h.

Referenced by Ekf::controlExternalVisionFusion(), Ekf::controlGpsFusion(), and Ekf::controlOpticalFlowFusion().

◆ rng_gnd_clearance

float estimator::parameters::rng_gnd_clearance {0.1f}

◆ rng_pos_body

Vector3f estimator::parameters::rng_pos_body

xyz position of range sensor in body frame (m)

Definition at line 327 of file common.h.

Referenced by Ekf::controlFusionModes().

◆ rng_sens_pitch

float estimator::parameters::rng_sens_pitch {0.0f}

Pitch offset of the range sensor (rad). Sensor points out along Z axis when offset is zero. Positive rotation is RH about Y axis.

Definition at line 292 of file common.h.

Referenced by Ekf::reset(), and Ekf::runTerrainEstimator().

◆ sensor_interval_min_ms

int32_t estimator::parameters::sensor_interval_min_ms {20}

minimum time of arrival difference between non IMU sensor updates. Sets the size of the observation buffers. (mSec)

Definition at line 224 of file common.h.

Referenced by EstimatorInterface::initialise_interface(), and Ekf2::Run().

◆ switch_on_accel_bias

float estimator::parameters::switch_on_accel_bias {0.2f}

1-sigma accelerometer bias uncertainty at switch on (m/sec**2)

Definition at line 253 of file common.h.

Referenced by Ekf::initialiseCovariance(), and Ekf::reset_imu_bias().

◆ switch_on_gyro_bias

float estimator::parameters::switch_on_gyro_bias {0.1f}

1-sigma gyro bias uncertainty at switch on (rad/sec)

Definition at line 252 of file common.h.

Referenced by Ekf::controlGpsFusion(), Ekf::initialiseCovariance(), and Ekf::reset_imu_bias().

◆ synthesize_mag_z

int32_t estimator::parameters::synthesize_mag_z {0}

Definition at line 363 of file common.h.

Referenced by Ekf::controlFusionModes().

◆ tas_innov_gate

float estimator::parameters::tas_innov_gate {5.0f}

True Airspeed innovation consistency gate size (STD)

Definition at line 280 of file common.h.

Referenced by Ekf::fuseAirspeed().

◆ terrain_gradient

float estimator::parameters::terrain_gradient {0.5f}

gradient of terrain used to estimate process noise due to changing position (m/m)

Definition at line 249 of file common.h.

Referenced by Ekf::runTerrainEstimator().

◆ terrain_p_noise

float estimator::parameters::terrain_p_noise {5.0f}

process noise for terrain offset (m/sec)

Definition at line 248 of file common.h.

Referenced by Ekf::runTerrainEstimator().

◆ valid_timeout_max

int32_t estimator::parameters::valid_timeout_max {5000000}

amount of time spent inertial dead reckoning before the estimator reports the state estimates as invalid (uSec)

Definition at line 344 of file common.h.

Referenced by Ekf::update_deadreckoning_status().

◆ vdist_sensor_type

int32_t estimator::parameters::vdist_sensor_type {VDIST_SENSOR_BARO}

selects the primary source for height data

Definition at line 223 of file common.h.

Referenced by Ekf::controlExternalVisionFusion(), Ekf::controlHeightFusion(), Ekf::initialiseFilter(), and EstimatorInterface::setGpsData().

◆ vehicle_variance_scaler

float estimator::parameters::vehicle_variance_scaler {0.0f}

gain applied to vehicle height variance used in calculation of height above ground observation variance

Definition at line 294 of file common.h.

Referenced by Ekf::fuseHagl().

◆ vel_Tau

float estimator::parameters::vel_Tau {0.25f}

velocity state correction time constant (1/sec)

Definition at line 332 of file common.h.

Referenced by Ekf::calculateOutputStates().

◆ vert_innov_test_lim

float estimator::parameters::vert_innov_test_lim {4.5f}

Number of standard deviations allowed before the combined vertical velocity and position test is declared as failed.

Definition at line 352 of file common.h.

Referenced by Ekf::controlHeightSensorTimeouts().

◆ wind_vel_p_noise

float estimator::parameters::wind_vel_p_noise {1.0e-1f}

process noise for wind velocity prediction (m/sec**2)

Definition at line 246 of file common.h.

Referenced by Ekf::predictCovariance().

◆ wind_vel_p_noise_scaler

float estimator::parameters::wind_vel_p_noise_scaler {0.5f}

scaling of wind process noise with vertical velocity

Definition at line 247 of file common.h.

Referenced by Ekf::predictCovariance().


The documentation for this struct was generated from the following file: