PX4 Firmware
PX4 Autopilot Software http://px4.io
common.h File Reference
#include <matrix/math.hpp>
Include dependency graph for common.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  estimator::gps_message
 
struct  estimator::flow_message
 
struct  estimator::ext_vision_message
 
struct  estimator::outputSample
 
struct  estimator::outputVert
 
struct  estimator::imuSample
 
struct  estimator::gpsSample
 
struct  estimator::magSample
 
struct  estimator::baroSample
 
struct  estimator::rangeSample
 
struct  estimator::airspeedSample
 
struct  estimator::flowSample
 
struct  estimator::extVisionSample
 
struct  estimator::dragSample
 
struct  estimator::auxVelSample
 
struct  estimator::parameters
 
struct  estimator::stateSample
 
union  estimator::fault_status_u
 
union  estimator::innovation_fault_status_u
 
union  estimator::gps_check_fail_status_u
 
union  estimator::filter_control_status_u
 
union  estimator::ekf_solution_status
 

Namespaces

 estimator
 

Macros

#define VDIST_SENSOR_BARO   0
 Use baro height. More...
 
#define VDIST_SENSOR_GPS   1
 Use GPS height. More...
 
#define VDIST_SENSOR_RANGE   2
 Use range finder height. More...
 
#define VDIST_SENSOR_EV   3
 Use external vision. More...
 
#define MASK_USE_GEO_DECL   (1<<0)
 set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value More...
 
#define MASK_SAVE_GEO_DECL   (1<<1)
 set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library More...
 
#define MASK_FUSE_DECL   (1<<2)
 set to true if the declination is always fused as an observation to constrain drift when 3-axis fusion is performed More...
 
#define MASK_USE_GPS   (1<<0)
 set to true to use GPS data More...
 
#define MASK_USE_OF   (1<<1)
 set to true to use optical flow data More...
 
#define MASK_INHIBIT_ACC_BIAS   (1<<2)
 set to true to inhibit estimation of accelerometer delta velocity bias More...
 
#define MASK_USE_EVPOS   (1<<3)
 set to true to use external vision position data More...
 
#define MASK_USE_EVYAW   (1<<4)
 set to true to use external vision quaternion data for yaw More...
 
#define MASK_USE_DRAG   (1<<5)
 set to true to use the multi-rotor drag model to estimate wind More...
 
#define MASK_ROTATE_EV   (1<<6)
 set to true to if the EV observations are in a non NED reference frame and need to be rotated before being used More...
 
#define MASK_USE_GPSYAW   (1<<7)
 set to true to use GPS yaw data if available More...
 
#define MASK_USE_EVVEL   (1<<8)
 sset to true to use external vision velocity data More...
 
#define MAG_FUSE_TYPE_AUTO   0
 The selection of either heading or 3D magnetometer fusion will be automatic. More...
 
#define MAG_FUSE_TYPE_HEADING   1
 Simple yaw angle fusion will always be used. This is less accurate, but less affected by earth field distortions. It should not be used for pitch angles outside the range from -60 to +60 deg. More...
 
#define MAG_FUSE_TYPE_3D   2
 Magnetometer 3-axis fusion will always be used. This is more accurate, but more affected by localised earth field distortions. More...
 
#define MAG_FUSE_TYPE_UNUSED   3
 Not implemented. More...
 
#define MAG_FUSE_TYPE_INDOOR   4
 The same as option 0, but magnetometer or yaw fusion will not be used unless earth frame external aiding (GPS or External Vision) is being used. This prevents inconsistent magnetic fields associated with indoor operation degrading state estimates. More...
 
#define MAG_FUSE_TYPE_NONE   5
 Do not use magnetometer under any circumstance. Other sources of yaw may be used if selected via the EKF2_AID_MASK parameter. More...
 
#define GPS_MAX_INTERVAL   (uint64_t)5e5
 Maximum allowable time interval between GPS measurements (uSec) More...
 
#define BARO_MAX_INTERVAL   (uint64_t)2e5
 Maximum allowable time interval between pressure altitude measurements (uSec) More...
 
#define RNG_MAX_INTERVAL   (uint64_t)2e5
 Maximum allowable time interval between range finder measurements (uSec) More...
 
#define EV_MAX_INTERVAL   (uint64_t)2e5
 Maximum allowable time interval between external vision system measurements (uSec) More...
 
#define BADACC_PROBATION   (uint64_t)10e6
 Period of time that accel data declared bad must continuously pass checks to be declared good again (uSec) More...
 
#define BADACC_BIAS_PNOISE   4.9f
 The delta velocity process noise is set to this when accel data is declared bad (m/sec**2) More...
 
#define GNDEFFECT_TIMEOUT   10E6
 Maximum period of time that ground effect protection will be active after it was last turned on (uSec) More...
 

Macro Definition Documentation

◆ BADACC_BIAS_PNOISE

#define BADACC_BIAS_PNOISE   4.9f

The delta velocity process noise is set to this when accel data is declared bad (m/sec**2)

Definition at line 215 of file common.h.

Referenced by Ekf::predictCovariance().

◆ BADACC_PROBATION

#define BADACC_PROBATION   (uint64_t)10e6

Period of time that accel data declared bad must continuously pass checks to be declared good again (uSec)

Definition at line 214 of file common.h.

Referenced by Ekf::controlHeightSensorTimeouts().

◆ BARO_MAX_INTERVAL

#define BARO_MAX_INTERVAL   (uint64_t)2e5

Maximum allowable time interval between pressure altitude measurements (uSec)

Definition at line 209 of file common.h.

Referenced by Ekf::controlFusionModes(), Ekf::controlHeightSensorTimeouts(), and Ekf::resetHeight().

◆ EV_MAX_INTERVAL

#define EV_MAX_INTERVAL   (uint64_t)2e5

Maximum allowable time interval between external vision system measurements (uSec)

Definition at line 211 of file common.h.

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

◆ GNDEFFECT_TIMEOUT

#define GNDEFFECT_TIMEOUT   10E6

Maximum period of time that ground effect protection will be active after it was last turned on (uSec)

Definition at line 218 of file common.h.

Referenced by Ekf::controlHeightFusion().

◆ GPS_MAX_INTERVAL

#define GPS_MAX_INTERVAL   (uint64_t)5e5

Maximum allowable time interval between GPS measurements (uSec)

Definition at line 208 of file common.h.

Referenced by Ekf::controlFusionModes(), Ekf::controlGpsFusion(), Ekf::controlHeightSensorTimeouts(), and Ekf::resetHeight().

◆ MAG_FUSE_TYPE_3D

#define MAG_FUSE_TYPE_3D   2

Magnetometer 3-axis fusion will always be used. This is more accurate, but more affected by localised earth field distortions.

Definition at line 202 of file common.h.

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

◆ MAG_FUSE_TYPE_AUTO

#define MAG_FUSE_TYPE_AUTO   0

The selection of either heading or 3D magnetometer fusion will be automatic.

Definition at line 200 of file common.h.

Referenced by Ekf::controlMagFusion().

◆ MAG_FUSE_TYPE_HEADING

#define MAG_FUSE_TYPE_HEADING   1

Simple yaw angle fusion will always be used. This is less accurate, but less affected by earth field distortions. It should not be used for pitch angles outside the range from -60 to +60 deg.

Definition at line 201 of file common.h.

Referenced by Ekf::controlMagFusion().

◆ MAG_FUSE_TYPE_INDOOR

#define MAG_FUSE_TYPE_INDOOR   4

The same as option 0, but magnetometer or yaw fusion will not be used unless earth frame external aiding (GPS or External Vision) is being used. This prevents inconsistent magnetic fields associated with indoor operation degrading state estimates.

Definition at line 204 of file common.h.

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

◆ MAG_FUSE_TYPE_NONE

#define MAG_FUSE_TYPE_NONE   5

Do not use magnetometer under any circumstance. Other sources of yaw may be used if selected via the EKF2_AID_MASK parameter.

Definition at line 205 of file common.h.

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

◆ MAG_FUSE_TYPE_UNUSED

#define MAG_FUSE_TYPE_UNUSED   3

Not implemented.

Definition at line 203 of file common.h.

◆ MASK_FUSE_DECL

#define MASK_FUSE_DECL   (1<<2)

set to true if the declination is always fused as an observation to constrain drift when 3-axis fusion is performed

Definition at line 186 of file common.h.

Referenced by Ekf::checkMagDeclRequired().

◆ MASK_INHIBIT_ACC_BIAS

#define MASK_INHIBIT_ACC_BIAS   (1<<2)

set to true to inhibit estimation of accelerometer delta velocity bias

Definition at line 191 of file common.h.

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

◆ MASK_ROTATE_EV

#define MASK_ROTATE_EV   (1<<6)

set to true to if the EV observations are in a non NED reference frame and need to be rotated before being used

Definition at line 195 of file common.h.

Referenced by Ekf::controlExternalVisionFusion(), Ekf::controlGpsFusion(), Ekf::resetGpsAntYaw(), Ekf::resetMagHeading(), Ekf::resetPosition(), and Ekf::resetVelocity().

◆ MASK_SAVE_GEO_DECL

#define MASK_SAVE_GEO_DECL   (1<<1)

set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library

Definition at line 185 of file common.h.

Referenced by EstimatorInterface::get_mag_decl_deg().

◆ MASK_USE_DRAG

#define MASK_USE_DRAG   (1<<5)

set to true to use the multi-rotor drag model to estimate wind

Definition at line 194 of file common.h.

Referenced by Ekf::controlAirDataFusion(), Ekf::controlBetaFusion(), Ekf::controlDragFusion(), and EstimatorInterface::setIMUData().

◆ MASK_USE_EVPOS

#define MASK_USE_EVPOS   (1<<3)

set to true to use external vision position data

Definition at line 192 of file common.h.

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

◆ MASK_USE_EVVEL

#define MASK_USE_EVVEL   (1<<8)

sset to true to use external vision velocity data

Definition at line 197 of file common.h.

Referenced by Ekf::controlExternalVisionFusion().

◆ MASK_USE_EVYAW

#define MASK_USE_EVYAW   (1<<4)

set to true to use external vision quaternion data for yaw

Definition at line 193 of file common.h.

Referenced by Ekf::controlExternalVisionFusion().

◆ MASK_USE_GEO_DECL

#define MASK_USE_GEO_DECL   (1<<0)

set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value

Definition at line 184 of file common.h.

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

◆ MASK_USE_GPS

#define MASK_USE_GPS   (1<<0)

◆ MASK_USE_GPSYAW

#define MASK_USE_GPSYAW   (1<<7)

set to true to use GPS yaw data if available

Definition at line 196 of file common.h.

Referenced by Ekf::controlGpsFusion().

◆ MASK_USE_OF

#define MASK_USE_OF   (1<<1)

set to true to use optical flow data

Definition at line 190 of file common.h.

Referenced by Ekf::controlOpticalFlowFusion().

◆ RNG_MAX_INTERVAL

#define RNG_MAX_INTERVAL   (uint64_t)2e5

Maximum allowable time interval between range finder measurements (uSec)

Definition at line 210 of file common.h.

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

◆ VDIST_SENSOR_BARO

#define VDIST_SENSOR_BARO   0

Use baro height.

Definition at line 178 of file common.h.

Referenced by Ekf::controlHeightFusion().

◆ VDIST_SENSOR_EV

#define VDIST_SENSOR_EV   3

Use external vision.

Definition at line 181 of file common.h.

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

◆ VDIST_SENSOR_GPS

#define VDIST_SENSOR_GPS   1

Use GPS height.

Definition at line 179 of file common.h.

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

◆ VDIST_SENSOR_RANGE

#define VDIST_SENSOR_RANGE   2

Use range finder height.

Definition at line 180 of file common.h.

Referenced by Ekf::controlHeightFusion().