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

Go to the source code of this file.

Enumerations

enum  AIRSPEED_SENSOR_MODEL { AIRSPEED_SENSOR_MODEL_MEMBRANE = 0, AIRSPEED_SENSOR_MODEL_SDP3X }
 
enum  AIRSPEED_COMPENSATION_MODEL { AIRSPEED_COMPENSATION_MODEL_PITOT = 0, AIRSPEED_COMPENSATION_MODEL_NO_PITOT = 1, AIRSPEED_COMPENSATION_TUBE_PRESSURE_LOSS = 2 }
 

Functions

__EXPORT float calc_IAS_corrected (enum AIRSPEED_COMPENSATION_MODEL pmodel, enum AIRSPEED_SENSOR_MODEL smodel, float tube_len, float tube_dia_mm, float differential_pressure, float pressure_ambient, float temperature_celsius)
 Calculate indicated airspeed (IAS). More...
 
__EXPORT float calc_IAS (float differential_pressure)
 Calculate indicated airspeed (IAS). More...
 
__EXPORT float calc_TAS_from_EAS (float speed_indicated, float pressure_ambient, float temperature_celsius)
 Calculate true airspeed (TAS) from equivalent airspeed (EAS). More...
 
__EXPORT float calc_EAS_from_IAS (float speed_indicated, float scale)
 Calculate equivalent airspeed (EAS) from indicated airspeed (IAS). More...
 
__EXPORT float calc_TAS (float total_pressure, float static_pressure, float temperature_celsius)
 Directly calculate true airspeed (TAS) More...
 
__EXPORT float get_air_density (float static_pressure, float temperature_celsius)
 Calculates air density. More...
 
__EXPORT float calc_EAS_from_TAS (float speed_true, float pressure_ambient, float temperature_celsius)
 Calculate equivalent airspeed (EAS) from true airspeed (TAS). More...
 

Enumeration Type Documentation

◆ AIRSPEED_COMPENSATION_MODEL

Enumerator
AIRSPEED_COMPENSATION_MODEL_PITOT 
AIRSPEED_COMPENSATION_MODEL_NO_PITOT 
AIRSPEED_COMPENSATION_TUBE_PRESSURE_LOSS 

Definition at line 54 of file airspeed.h.

◆ AIRSPEED_SENSOR_MODEL

Enumerator
AIRSPEED_SENSOR_MODEL_MEMBRANE 
AIRSPEED_SENSOR_MODEL_SDP3X 

Definition at line 49 of file airspeed.h.

Function Documentation

◆ calc_EAS_from_IAS()

__EXPORT float calc_EAS_from_IAS ( float  speed_indicated,
float  scale 
)

Calculate equivalent airspeed (EAS) from indicated airspeed (IAS).

Note that we neglect the conversion from CAS (calibrated airspeed) to EAS.

Parameters
speed_indicatedcurrent indicated airspeed
scalescale from IAS to CAS (accounting for instrument and pitot position erros)
Returns
EAS in m/s

Definition at line 232 of file airspeed.cpp.

Referenced by MavlinkReceiver::handle_message_hil_sensor(), and AirspeedValidator::update_EAS_TAS().

Here is the caller graph for this function:

◆ calc_EAS_from_TAS()

__EXPORT float calc_EAS_from_TAS ( float  speed_true,
float  pressure_ambient,
float  temperature_celsius 
)

Calculate equivalent airspeed (EAS) from true airspeed (TAS).

It is the inverse function to calc_TAS_from_EAS()

Parameters
speed_truecurrent true airspeed
pressure_ambientpressure at the side of the tube/airplane
temperature_celsiusair temperature in degrees celcius
Returns
EAS in m/s

Definition at line 282 of file airspeed.cpp.

References CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C, and get_air_density().

Referenced by AirspeedModule::update_ground_minus_wind_airspeed().

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

◆ calc_IAS()

__EXPORT float calc_IAS ( float  differential_pressure)

Calculate indicated airspeed (IAS).

Note that the indicated airspeed is not the true airspeed because it lacks the air density compensation. Use the calc_true_airspeed functions to get the true airspeed.

Parameters
total_pressurepressure inside the pitot/prandtl tube
static_pressurepressure at the side of the tube/airplane
Returns
indicated airspeed in m/s

Note that the indicated airspeed is not the true airspeed because it lacks the air density and instrument error compensation.

Parameters
differential_pressuretotal_ pressure - static pressure
Returns
IAS in m/s

Definition at line 195 of file airspeed.cpp.

References CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C, and f().

Referenced by MavlinkReceiver::handle_message_hil_sensor().

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

◆ calc_IAS_corrected()

__EXPORT float calc_IAS_corrected ( enum AIRSPEED_COMPENSATION_MODEL  pmodel,
enum AIRSPEED_SENSOR_MODEL  smodel,
float  tube_len,
float  tube_dia_mm,
float  differential_pressure,
float  pressure_ambient,
float  temperature_celsius 
)

Calculate indicated airspeed (IAS).

Note that the indicated airspeed is not the true airspeed because it lacks the air density compensation. Use the calc_true_airspeed functions to get the true airspeed.

Parameters
total_pressurepressure inside the pitot/prandtl tube
static_pressurepressure at the side of the tube/airplane
Returns
indicated airspeed in m/s

Calculate indicated airspeed (IAS).

Note that the indicated airspeed is not the true airspeed because it lacks the air density compensation. Use the calc_true_airspeed functions to get the true airspeed.

Parameters
differential_pressuretotal_ pressure - static pressure
Returns
indicated airspeed in m/s

Definition at line 58 of file airspeed.cpp.

References AIRSPEED_COMPENSATION_MODEL_NO_PITOT, AIRSPEED_COMPENSATION_MODEL_PITOT, AIRSPEED_COMPENSATION_TUBE_PRESSURE_LOSS, AIRSPEED_SENSOR_MODEL_MEMBRANE, AIRSPEED_SENSOR_MODEL_SDP3X, CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C, f(), get_air_density(), and M_PI_F.

Referenced by Sensors::diff_pres_poll().

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

◆ calc_TAS()

__EXPORT float calc_TAS ( float  total_pressure,
float  static_pressure,
float  temperature_celsius 
)

Directly calculate true airspeed (TAS)

Here we assume to have no instrument or pitot position error (IAS = CAS), and neglect the CAS to EAS conversion (CAS = EAS). Note that the true airspeed is NOT the groundspeed, because of the effects of wind.

Parameters
total_pressurepressure inside the pitot/prandtl tube
static_pressurepressure at the side of the tube/airplane
temperature_celsiusair temperature in degrees celcius
Returns
true airspeed in m/s

Definition at line 249 of file airspeed.cpp.

References CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C, f(), and get_air_density().

Here is the call graph for this function:

◆ calc_TAS_from_EAS()

__EXPORT float calc_TAS_from_EAS ( float  speed_equivalent,
float  pressure_ambient,
float  temperature_celsius 
)

Calculate true airspeed (TAS) from equivalent airspeed (EAS).

Note that the true airspeed is NOT the groundspeed, because of the effects of wind

Parameters
speed_equivalentcurrent equivalent airspeed
pressure_ambientpressure at the side of the tube/airplane
temperature_celsiusair temperature in degrees celcius
Returns
TAS in m/s

Definition at line 218 of file airspeed.cpp.

References CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C, and get_air_density().

Referenced by Sensors::diff_pres_poll(), MavlinkReceiver::handle_message_hil_sensor(), and AirspeedValidator::update_EAS_TAS().

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

◆ get_air_density()

__EXPORT float get_air_density ( float  static_pressure,
float  temperature_celsius 
)

Calculates air density.

Parameters
static_pressureambient pressure in millibar
temperature_celciusair / ambient temperature in celcius

Definition at line 267 of file airspeed.cpp.

References CONSTANTS_ABSOLUTE_NULL_CELSIUS, and CONSTANTS_AIR_GAS_CONST.

Referenced by calc_EAS_from_TAS(), calc_IAS_corrected(), calc_TAS(), and calc_TAS_from_EAS().

Here is the caller graph for this function: