|
APM:Libraries
|
#include <AP_Airspeed.h>
Classes | |
| struct | airspeed_state |
Public Types | |
| enum | pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE = 0, PITOT_TUBE_ORDER_NEGATIVE = 1, PITOT_TUBE_ORDER_AUTO = 2 } |
| enum | airspeed_type { TYPE_NONE =0, TYPE_I2C_MS4525 =1, TYPE_ANALOG =2, TYPE_I2C_MS5525 =3, TYPE_I2C_MS5525_ADDRESS_1 =4, TYPE_I2C_MS5525_ADDRESS_2 =5, TYPE_I2C_SDP3X =6 } |
Public Member Functions | |
| AP_Airspeed () | |
| void | init (void) |
| void | read (void) |
| void | calibrate (bool in_startup) |
| float | get_airspeed (uint8_t i) const |
| float | get_airspeed (void) const |
| float | get_raw_airspeed (uint8_t i) const |
| float | get_raw_airspeed (void) const |
| float | get_airspeed_ratio (uint8_t i) const |
| float | get_airspeed_ratio (void) const |
| bool | get_temperature (uint8_t i, float &temperature) |
| bool | get_temperature (float &temperature) |
| void | set_airspeed_ratio (uint8_t i, float ratio) |
| void | set_airspeed_ratio (float ratio) |
| bool | use (uint8_t i) const |
| bool | use (void) const |
| bool | enabled (uint8_t i) const |
| bool | enabled (void) const |
| void | set_HIL (float airspeed) |
| float | get_differential_pressure (uint8_t i) const |
| float | get_differential_pressure (void) const |
| float | get_offset (uint8_t i) const |
| float | get_offset (void) const |
| float | get_corrected_pressure (uint8_t i) const |
| float | get_corrected_pressure (void) const |
| void | set_EAS2TAS (uint8_t i, float v) |
| void | set_EAS2TAS (float v) |
| float | get_EAS2TAS (uint8_t i) const |
| float | get_EAS2TAS (void) const |
| void | update_calibration (const Vector3f &vground, int16_t max_airspeed_allowed_during_cal) |
| void | log_mavlink_send (mavlink_channel_t chan, const Vector3f &vground) |
| bool | healthy (uint8_t i) const |
| bool | healthy (void) const |
| bool | all_healthy (void) const |
| void | setHIL (float pressure) |
| uint32_t | last_update_ms (uint8_t i) const |
| uint32_t | last_update_ms (void) const |
| void | setHIL (float airspeed, float diff_pressure, float temperature) |
| uint8_t | get_primary (void) const |
Static Public Member Functions | |
| static AP_Airspeed * | get_singleton () |
Static Public Attributes | |
| static const struct AP_Param::GroupInfo | var_info [] |
Private Member Functions | |
| void | read (uint8_t i) |
| float | get_pressure (uint8_t i) |
| void | update_calibration (uint8_t i, float raw_pressure) |
| void | update_calibration (uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal) |
Private Attributes | |
| AP_Int8 | primary_sensor |
| struct { | |
| AP_Float offset | |
| AP_Float ratio | |
| AP_Float psi_range | |
| AP_Int8 use | |
| AP_Int8 type | |
| AP_Int8 pin | |
| AP_Int8 bus | |
| AP_Int8 autocal | |
| AP_Int8 tube_order | |
| AP_Int8 skip_cal | |
| } | param [AIRSPEED_MAX_SENSORS] |
| struct AP_Airspeed::airspeed_state | state [AIRSPEED_MAX_SENSORS] |
| uint8_t | primary |
| AP_Airspeed_Backend * | sensor [AIRSPEED_MAX_SENSORS] |
Static Private Attributes | |
| static AP_Airspeed * | _singleton |
Friends | |
| class | AP_Airspeed_Backend |
Definition at line 35 of file AP_Airspeed.h.
| Enumerator | |
|---|---|
| TYPE_NONE | |
| TYPE_I2C_MS4525 | |
| TYPE_ANALOG | |
| TYPE_I2C_MS5525 | |
| TYPE_I2C_MS5525_ADDRESS_1 | |
| TYPE_I2C_MS5525_ADDRESS_2 | |
| TYPE_I2C_SDP3X | |
Definition at line 157 of file AP_Airspeed.h.
| Enumerator | |
|---|---|
| PITOT_TUBE_ORDER_POSITIVE | |
| PITOT_TUBE_ORDER_NEGATIVE | |
| PITOT_TUBE_ORDER_AUTO | |
Definition at line 153 of file AP_Airspeed.h.
| AP_Airspeed::AP_Airspeed | ( | ) |
| bool AP_Airspeed::all_healthy | ( | void | ) | const |
| void AP_Airspeed::calibrate | ( | bool | in_startup | ) |
Definition at line 292 of file AP_Airspeed.cpp.
Referenced by GCS_MAVLINK::_handle_command_preflight_calibration_baro(), and setup().
|
inline |
Definition at line 85 of file AP_Airspeed.h.
Referenced by AP_Arming::airspeed_checks(), AP_Frsky_Telem::calc_velandyaw(), and DataFlash_Class::Log_Write_Airspeed().
|
inline |
Definition at line 91 of file AP_Airspeed.h.
Referenced by all_healthy(), calibrate(), enabled(), get_pressure(), get_temperature(), read(), setHIL(), and update_calibration().
|
inline |
Definition at line 53 of file AP_Airspeed.h.
Referenced by AP_AHRS_DCM::airspeed_estimate(), AP_AHRS::airspeed_estimate(), AP_Frsky_Telem::calc_velandyaw(), NavEKF2_core::detectFlight(), NavEKF3_core::detectFlight(), AP_AHRS_DCM::drift_correction(), AP_AHRS_DCM::estimate_wind(), loop(), NavEKF2_core::readAirSpdData(), and GCS_MAVLINK::vfr_hud_airspeed().
|
inline |
Definition at line 56 of file AP_Airspeed.h.
Referenced by get_airspeed(), and read().
|
inline |
Definition at line 65 of file AP_Airspeed.h.
Referenced by AP_Airspeed_Backend::get_airspeed_ratio().
|
inline |
Definition at line 68 of file AP_Airspeed.h.
Referenced by get_airspeed_ratio().
|
inline |
Definition at line 111 of file AP_Airspeed.h.
Referenced by DataFlash_Class::Log_Write_Airspeed().
|
inline |
Definition at line 114 of file AP_Airspeed.h.
Referenced by get_corrected_pressure().
|
inline |
Definition at line 99 of file AP_Airspeed.h.
Referenced by DataFlash_Class::Log_Write_Airspeed(), and GCS_MAVLINK::send_scaled_pressure().
|
inline |
Definition at line 102 of file AP_Airspeed.h.
Referenced by get_differential_pressure().
|
inline |
Definition at line 123 of file AP_Airspeed.h.
Referenced by NavEKF2_core::detectFlight(), NavEKF3_core::detectFlight(), AP_AHRS::get_EAS2TAS(), NavEKF2_core::readAirSpdData(), and NavEKF3_core::readAirSpdData().
|
inline |
Definition at line 126 of file AP_Airspeed.h.
Referenced by get_EAS2TAS().
|
inline |
Definition at line 105 of file AP_Airspeed.h.
Referenced by DataFlash_Class::Log_Write_Airspeed().
|
inline |
Definition at line 108 of file AP_Airspeed.h.
Referenced by get_offset().
|
private |
Definition at line 262 of file AP_Airspeed.cpp.
Referenced by read().
|
inline |
Definition at line 168 of file AP_Airspeed.h.
Referenced by DataFlash_Class::Log_Write_Airspeed().
|
inline |
Definition at line 59 of file AP_Airspeed.h.
Referenced by DataFlash_Class::Log_Write_Airspeed(), and NavEKF3_core::readAirSpdData().
|
inline |
Definition at line 62 of file AP_Airspeed.h.
Referenced by get_raw_airspeed().
|
inlinestatic |
Definition at line 170 of file AP_Airspeed.h.
Referenced by GCS_MAVLINK::_handle_command_preflight_calibration_baro(), GCS_MAVLINK::send_scaled_pressure(), and GCS_MAVLINK::vfr_hud_airspeed().
| bool AP_Airspeed::get_temperature | ( | uint8_t | i, |
| float & | temperature | ||
| ) |
Definition at line 279 of file AP_Airspeed.cpp.
Referenced by DataFlash_Class::Log_Write_Airspeed(), and loop().
|
inline |
Definition at line 72 of file AP_Airspeed.h.
Referenced by get_temperature().
|
inline |
Definition at line 135 of file AP_Airspeed.h.
Referenced by AP_Arming::airspeed_checks(), AP_AHRS::airspeed_sensor_enabled(), DataFlash_Class::Log_Write_Airspeed(), loop(), and GCS_MAVLINK::vfr_hud_airspeed().
|
inline |
Definition at line 138 of file AP_Airspeed.h.
Referenced by all_healthy(), healthy(), read(), and update_calibration().
| void AP_Airspeed::init | ( | void | ) |
Definition at line 219 of file AP_Airspeed.cpp.
Referenced by setup().
|
inline |
Definition at line 146 of file AP_Airspeed.h.
Referenced by NavEKF2_core::readAirSpdData(), and NavEKF3_core::readAirSpdData().
|
inline |
Definition at line 147 of file AP_Airspeed.h.
Referenced by last_update_ms().
| void AP_Airspeed::log_mavlink_send | ( | mavlink_channel_t | chan, |
| const Vector3f & | vground | ||
| ) |
Definition at line 163 of file Airspeed_Calibration.cpp.
| void AP_Airspeed::read | ( | void | ) |
Definition at line 395 of file AP_Airspeed.cpp.
Referenced by loop().
|
private |
|
inline |
Definition at line 75 of file AP_Airspeed.h.
|
inline |
Definition at line 78 of file AP_Airspeed.h.
Referenced by set_airspeed_ratio().
|
inline |
Definition at line 117 of file AP_Airspeed.h.
|
inline |
Definition at line 120 of file AP_Airspeed.h.
Referenced by set_EAS2TAS().
|
inline |
Definition at line 94 of file AP_Airspeed.h.
|
inline |
Definition at line 143 of file AP_Airspeed.h.
| void AP_Airspeed::setHIL | ( | float | airspeed, |
| float | diff_pressure, | ||
| float | temperature | ||
| ) |
| void AP_Airspeed::update_calibration | ( | const Vector3f & | vground, |
| int16_t | max_airspeed_allowed_during_cal | ||
| ) |
Definition at line 155 of file Airspeed_Calibration.cpp.
Referenced by read().
|
private |
|
private |
| bool AP_Airspeed::use | ( | uint8_t | i | ) | const |
|
inline |
Definition at line 82 of file AP_Airspeed.h.
Referenced by setHIL(), and use().
|
friend |
Definition at line 38 of file AP_Airspeed.h.
|
staticprivate |
Definition at line 173 of file AP_Airspeed.h.
Referenced by all_healthy(), and AP_Airspeed().
| AP_Int8 AP_Airspeed::autocal |
Definition at line 185 of file AP_Airspeed.h.
| AP_Int8 AP_Airspeed::bus |
Definition at line 184 of file AP_Airspeed.h.
Referenced by AP_Airspeed_Backend::get_bus().
| AP_Float AP_Airspeed::offset |
Definition at line 178 of file AP_Airspeed.h.
Referenced by AP_Airspeed_Backend::set_offset().
| struct { ... } AP_Airspeed::param[AIRSPEED_MAX_SENSORS] |
| AP_Int8 AP_Airspeed::pin |
Definition at line 183 of file AP_Airspeed.h.
Referenced by AP_Airspeed_Backend::get_pin(), and init().
|
private |
Definition at line 217 of file AP_Airspeed.h.
Referenced by read().
|
private |
Definition at line 175 of file AP_Airspeed.h.
Referenced by read().
| AP_Float AP_Airspeed::psi_range |
Definition at line 180 of file AP_Airspeed.h.
Referenced by AP_Airspeed_Backend::get_psi_range().
| AP_Float AP_Airspeed::ratio |
Definition at line 179 of file AP_Airspeed.h.
|
private |
Definition at line 226 of file AP_Airspeed.h.
Referenced by get_pressure(), get_temperature(), init(), and read().
| AP_Int8 AP_Airspeed::skip_cal |
Definition at line 187 of file AP_Airspeed.h.
Referenced by calibrate(), and AP_Airspeed_Backend::set_skip_cal().
|
private |
Referenced by AP_Airspeed(), calibrate(), get_pressure(), init(), read(), AP_Airspeed_Backend::set_use_zero_offset(), setHIL(), and update_calibration().
| AP_Int8 AP_Airspeed::tube_order |
Definition at line 186 of file AP_Airspeed.h.
Referenced by AP_Airspeed_Backend::get_tube_order(), and read().
| AP_Int8 AP_Airspeed::type |
Definition at line 182 of file AP_Airspeed.h.
Referenced by init().
| bool AP_Airspeed::use |
Definition at line 181 of file AP_Airspeed.h.
Referenced by AP_Arming::airspeed_checks(), AP_AHRS::airspeed_sensor_enabled(), DataFlash_Class::Log_Write_Airspeed(), NavEKF2_core::readAirSpdData(), and NavEKF3_core::readAirSpdData().
|
static |
Definition at line 151 of file AP_Airspeed.h.
Referenced by AP_Airspeed(), and setup().
1.8.13