mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-22 18:37:34 +08:00
airspeed: remove duplicated comments from cpp (they should only be in header)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
@@ -45,16 +45,6 @@
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
|
||||
/**
|
||||
* Calculate indicated airspeed.
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @param differential_pressure total_ pressure - static pressure
|
||||
* @return indicated airspeed in m/s
|
||||
*/
|
||||
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)
|
||||
{
|
||||
@@ -185,15 +175,6 @@ float calc_IAS_corrected(enum AIRSPEED_COMPENSATION_MODEL pmodel, enum AIRSPEED_
|
||||
return (differential_pressure > 0.0f) ? airspeed_corrected : -airspeed_corrected;
|
||||
}
|
||||
|
||||
/**
|
||||
* Calculate indicated airspeed (IAS).
|
||||
*
|
||||
* Note that the indicated airspeed is not the true airspeed because it
|
||||
* lacks the air density and instrument error compensation.
|
||||
*
|
||||
* @param differential_pressure total_ pressure - static pressure
|
||||
* @return IAS in m/s
|
||||
*/
|
||||
float calc_IAS(float differential_pressure)
|
||||
{
|
||||
if (differential_pressure > 0.0f) {
|
||||
@@ -205,16 +186,6 @@ float calc_IAS(float differential_pressure)
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Calculate true airspeed (TAS) from equivalent airspeed (EAS).
|
||||
*
|
||||
* Note that the true airspeed is NOT the groundspeed, because of the effects of wind
|
||||
*
|
||||
* @param speed_equivalent current equivalent airspeed
|
||||
* @param pressure_ambient pressure at the side of the tube/airplane
|
||||
* @param temperature_celsius air temperature in degrees celcius
|
||||
* @return TAS in m/s
|
||||
*/
|
||||
float calc_TAS_from_EAS(float speed_equivalent, float pressure_ambient, float temperature_celsius)
|
||||
{
|
||||
if (!PX4_ISFINITE(temperature_celsius)) {
|
||||
@@ -225,31 +196,11 @@ float calc_TAS_from_EAS(float speed_equivalent, float pressure_ambient, float te
|
||||
temperature_celsius));
|
||||
}
|
||||
|
||||
/**
|
||||
* Calculate equivalent airspeed (EAS) from indicated airspeed (IAS).
|
||||
* Note that we neglect the conversion from CAS (calibrated airspeed) to EAS.
|
||||
*
|
||||
* @param speed_indicated current indicated airspeed
|
||||
* @param scale scale from IAS to CAS (accounting for instrument and pitot position erros)
|
||||
* @return EAS in m/s
|
||||
*/
|
||||
float calc_EAS_from_IAS(float speed_indicated, float scale)
|
||||
{
|
||||
return speed_indicated * scale;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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.
|
||||
*
|
||||
* @param total_pressure pressure inside the pitot/prandtl tube
|
||||
* @param static_pressure pressure at the side of the tube/airplane
|
||||
* @param temperature_celsius air temperature in degrees celcius
|
||||
* @return true airspeed in m/s
|
||||
*/
|
||||
float calc_TAS(float total_pressure, float static_pressure, float temperature_celsius)
|
||||
{
|
||||
float density = get_air_density(static_pressure, temperature_celsius);
|
||||
@@ -277,16 +228,6 @@ float get_air_density(float static_pressure, float temperature_celsius)
|
||||
return static_pressure / (CONSTANTS_AIR_GAS_CONST * (temperature_celsius - CONSTANTS_ABSOLUTE_NULL_CELSIUS));
|
||||
}
|
||||
|
||||
/**
|
||||
* Calculate equivalent airspeed (EAS) from true airspeed (TAS).
|
||||
* It is the inverse function to calc_TAS_from_EAS()
|
||||
*
|
||||
*
|
||||
* @param speed_true current true airspeed
|
||||
* @param pressure_ambient pressure at the side of the tube/airplane
|
||||
* @param temperature_celsius air temperature in degrees celcius
|
||||
* @return EAS in m/s
|
||||
*/
|
||||
float calc_EAS_from_TAS(float speed_true, float pressure_ambient, float temperature_celsius)
|
||||
{
|
||||
return speed_true * sqrtf(get_air_density(pressure_ambient, temperature_celsius) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
|
||||
|
||||
Reference in New Issue
Block a user