123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550 |
- #include <AP_Common/AP_Common.h>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_HAL/I2CDevice.h>
- #include <AP_Math/AP_Math.h>
- #include <GCS_MAVLink/GCS.h>
- #include <SRV_Channel/SRV_Channel.h>
- #include <AP_Logger/AP_Logger.h>
- #include <utility>
- #include "AP_Airspeed.h"
- #include "AP_Airspeed_MS4525.h"
- #include "AP_Airspeed_MS5525.h"
- #include "AP_Airspeed_SDP3X.h"
- #include "AP_Airspeed_DLVR.h"
- #include "AP_Airspeed_analog.h"
- #include "AP_Airspeed_Backend.h"
- #if HAL_WITH_UAVCAN
- #include "AP_Airspeed_UAVCAN.h"
- #endif
- extern const AP_HAL::HAL &hal;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- #define ARSPD_DEFAULT_TYPE TYPE_ANALOG
- #define ARSPD_DEFAULT_PIN 1
- #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
- #define ARSPD_DEFAULT_TYPE TYPE_NONE
- #define ARSPD_DEFAULT_PIN 15
- #else
- #define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
- #ifdef HAL_DEFAULT_AIRSPEED_PIN
- #define ARSPD_DEFAULT_PIN HAL_DEFAULT_AIRSPEED_PIN
- #else
- #define ARSPD_DEFAULT_PIN 15
- #endif
- #endif
- #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
- #define PSI_RANGE_DEFAULT 0.05
- #endif
- #ifndef PSI_RANGE_DEFAULT
- #define PSI_RANGE_DEFAULT 1.0f
- #endif
- const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO_FLAGS("_TYPE", 0, AP_Airspeed, param[0].type, ARSPD_DEFAULT_TYPE, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
- AP_GROUPINFO("_USE", 1, AP_Airspeed, param[0].use, 0),
-
-
-
-
-
- AP_GROUPINFO("_OFFSET", 2, AP_Airspeed, param[0].offset, 0),
-
-
-
-
-
- AP_GROUPINFO("_RATIO", 3, AP_Airspeed, param[0].ratio, 1.9936f),
-
-
-
-
- AP_GROUPINFO("_PIN", 4, AP_Airspeed, param[0].pin, ARSPD_DEFAULT_PIN),
-
-
-
-
- AP_GROUPINFO("_AUTOCAL", 5, AP_Airspeed, param[0].autocal, 0),
-
-
-
-
- AP_GROUPINFO("_TUBE_ORDER", 6, AP_Airspeed, param[0].tube_order, 2),
-
-
-
-
-
- AP_GROUPINFO("_SKIP_CAL", 7, AP_Airspeed, param[0].skip_cal, 0),
-
-
-
-
- AP_GROUPINFO("_PSI_RANGE", 8, AP_Airspeed, param[0].psi_range, PSI_RANGE_DEFAULT),
-
-
-
-
-
- AP_GROUPINFO("_BUS", 9, AP_Airspeed, param[0].bus, 1),
-
-
-
-
-
- AP_GROUPINFO("_PRIMARY", 10, AP_Airspeed, primary_sensor, 0),
-
-
-
-
-
- AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, 0),
-
-
-
-
-
- AP_GROUPINFO_FLAGS("2_TYPE", 11, AP_Airspeed, param[1].type, 0, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
- AP_GROUPINFO("2_USE", 12, AP_Airspeed, param[1].use, 0),
-
-
-
-
-
- AP_GROUPINFO("2_OFFSET", 13, AP_Airspeed, param[1].offset, 0),
-
-
-
-
-
- AP_GROUPINFO("2_RATIO", 14, AP_Airspeed, param[1].ratio, 2),
-
-
-
-
- AP_GROUPINFO("2_PIN", 15, AP_Airspeed, param[1].pin, 0),
-
-
-
-
- AP_GROUPINFO("2_AUTOCAL", 16, AP_Airspeed, param[1].autocal, 0),
-
-
-
-
- AP_GROUPINFO("2_TUBE_ORDR", 17, AP_Airspeed, param[1].tube_order, 2),
-
-
-
-
-
- AP_GROUPINFO("2_SKIP_CAL", 18, AP_Airspeed, param[1].skip_cal, 0),
-
-
-
-
- AP_GROUPINFO("2_PSI_RANGE", 19, AP_Airspeed, param[1].psi_range, PSI_RANGE_DEFAULT),
-
-
-
-
-
- AP_GROUPINFO("2_BUS", 20, AP_Airspeed, param[1].bus, 1),
-
- AP_GROUPEND
- };
- #define SCALING_OLD_CALIBRATION 819
- AP_Airspeed::AP_Airspeed()
- {
- AP_Param::setup_object_defaults(this, var_info);
- if (_singleton != nullptr) {
- AP_HAL::panic("AP_Airspeed must be singleton");
- }
- _singleton = this;
- }
- void AP_Airspeed::init()
- {
-
- if (param[0].pin.load() && param[0].pin.get() != 65) {
- param[0].type.set_default(TYPE_ANALOG);
- }
- for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
- state[i].calibration.init(param[i].ratio);
- state[i].last_saved_ratio = param[i].ratio;
-
- state[i].failures.health_probability = 1.0f;
- switch ((enum airspeed_type)param[i].type.get()) {
- case TYPE_NONE:
-
- break;
- case TYPE_I2C_MS4525:
- sensor[i] = new AP_Airspeed_MS4525(*this, i);
- break;
- case TYPE_ANALOG:
- sensor[i] = new AP_Airspeed_Analog(*this, i);
- break;
- case TYPE_I2C_MS5525:
- sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO);
- break;
- case TYPE_I2C_MS5525_ADDRESS_1:
- sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1);
- break;
- case TYPE_I2C_MS5525_ADDRESS_2:
- sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2);
- break;
- case TYPE_I2C_SDP3X:
- sensor[i] = new AP_Airspeed_SDP3X(*this, i);
- break;
- case TYPE_I2C_DLVR_5IN:
- #if !HAL_MINIMIZE_FEATURES
- sensor[i] = new AP_Airspeed_DLVR(*this, i, 5);
- #endif
- break;
- case TYPE_I2C_DLVR_10IN:
- #if !HAL_MINIMIZE_FEATURES
- sensor[i] = new AP_Airspeed_DLVR(*this, i, 10);
- #endif
- break;
- case TYPE_UAVCAN:
- #if HAL_WITH_UAVCAN
- sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i);
- #endif
- break;
- }
- if (sensor[i] && !sensor[i]->init()) {
- gcs().send_text(MAV_SEVERITY_INFO, "Airspeed %u init failed", i + 1);
- delete sensor[i];
- sensor[i] = nullptr;
- }
- }
- }
- float AP_Airspeed::get_pressure(uint8_t i)
- {
- if (!enabled(i)) {
- return 0;
- }
- if (state[i].hil_set) {
- state[i].healthy = true;
- return state[i].hil_pressure;
- }
- float pressure = 0;
- if (sensor[i]) {
- state[i].healthy = sensor[i]->get_differential_pressure(pressure);
- }
- return pressure;
- }
- bool AP_Airspeed::get_temperature(uint8_t i, float &temperature)
- {
- if (!enabled(i)) {
- return false;
- }
- if (sensor[i]) {
- return sensor[i]->get_temperature(temperature);
- }
- return false;
- }
- void AP_Airspeed::calibrate(bool in_startup)
- {
- if (hal.util->was_watchdog_reset()) {
- gcs().send_text(MAV_SEVERITY_INFO,"Airspeed: skipping cal");
- return;
- }
- for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
- if (!enabled(i)) {
- continue;
- }
- if (state[i].use_zero_offset) {
- param[i].offset.set(0);
- continue;
- }
- if (in_startup && param[i].skip_cal) {
- continue;
- }
- state[i].cal.start_ms = AP_HAL::millis();
- state[i].cal.count = 0;
- state[i].cal.sum = 0;
- state[i].cal.read_count = 0;
- }
- gcs().send_text(MAV_SEVERITY_INFO,"Airspeed calibration started");
- }
- void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
- {
- if (!enabled(i) || state[i].cal.start_ms == 0) {
- return;
- }
-
-
-
- if (AP_HAL::millis() - state[i].cal.start_ms >= 1000 &&
- state[i].cal.read_count > 15) {
- if (state[i].cal.count == 0) {
- gcs().send_text(MAV_SEVERITY_INFO, "Airspeed %u unhealthy", i + 1);
- } else {
- gcs().send_text(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1);
- param[i].offset.set_and_save(state[i].cal.sum / state[i].cal.count);
- }
- state[i].cal.start_ms = 0;
- return;
- }
-
- if (state[i].healthy && state[i].cal.read_count > 5) {
- state[i].cal.sum += raw_pressure;
- state[i].cal.count++;
- }
- state[i].cal.read_count++;
- }
- void AP_Airspeed::read(uint8_t i)
- {
- float airspeed_pressure;
- if (!enabled(i) || !sensor[i]) {
- return;
- }
- bool prev_healthy = state[i].healthy;
- float raw_pressure = get_pressure(i);
- if (state[i].cal.start_ms != 0) {
- update_calibration(i, raw_pressure);
- }
-
- airspeed_pressure = raw_pressure - param[i].offset;
-
- state[i].corrected_pressure = airspeed_pressure;
-
- if (!prev_healthy) {
-
-
-
- state[i].filtered_pressure = airspeed_pressure;
- } else {
- state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure;
- }
-
- switch ((enum pitot_tube_order)param[i].tube_order.get()) {
- case PITOT_TUBE_ORDER_NEGATIVE:
- state[i].last_pressure = -airspeed_pressure;
- state[i].raw_airspeed = sqrtf(MAX(-airspeed_pressure, 0) * param[i].ratio);
- state[i].airspeed = sqrtf(MAX(-state[i].filtered_pressure, 0) * param[i].ratio);
- break;
- case PITOT_TUBE_ORDER_POSITIVE:
- state[i].last_pressure = airspeed_pressure;
- state[i].raw_airspeed = sqrtf(MAX(airspeed_pressure, 0) * param[i].ratio);
- state[i].airspeed = sqrtf(MAX(state[i].filtered_pressure, 0) * param[i].ratio);
- break;
- case PITOT_TUBE_ORDER_AUTO:
- default:
- state[i].last_pressure = fabsf(airspeed_pressure);
- state[i].raw_airspeed = sqrtf(fabsf(airspeed_pressure) * param[i].ratio);
- state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio);
- break;
- }
- if (state[i].last_pressure < -32) {
-
-
- state[i].healthy = false;
- }
- state[i].last_update_ms = AP_HAL::millis();
- }
- void AP_Airspeed::update(bool log)
- {
- for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
- read(i);
- }
- #if 1
-
- if (enabled(1)) {
- gcs().send_named_float("AS2", get_airspeed(1));
- }
- #endif
-
- if (healthy(primary_sensor.get())) {
- primary = primary_sensor.get();
- } else {
- for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
- if (healthy(i)) {
- primary = i;
- break;
- }
- }
- }
- check_sensor_failures();
- if (log) {
- Log_Airspeed();
- }
- }
- void AP_Airspeed::Log_Airspeed()
- {
- const uint64_t now = AP_HAL::micros64();
- for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
- if (!enabled(i)) {
- continue;
- }
- float temperature;
- if (!get_temperature(i, temperature)) {
- temperature = 0;
- }
- struct log_AIRSPEED pkt = {
- LOG_PACKET_HEADER_INIT(i==0?LOG_ARSP_MSG:LOG_ASP2_MSG),
- time_us : now,
- airspeed : get_raw_airspeed(i),
- diffpressure : get_differential_pressure(i),
- temperature : (int16_t)(temperature * 100.0f),
- rawpressure : get_corrected_pressure(i),
- offset : get_offset(i),
- use : use(i),
- healthy : healthy(i),
- health_prob : get_health_failure_probability(i),
- primary : get_primary()
- };
- AP::logger().WriteBlock(&pkt, sizeof(pkt));
- }
- }
- void AP_Airspeed::setHIL(float airspeed, float diff_pressure, float temperature)
- {
- state[0].raw_airspeed = airspeed;
- state[0].airspeed = airspeed;
- state[0].last_pressure = diff_pressure;
- state[0].last_update_ms = AP_HAL::millis();
- state[0].hil_pressure = diff_pressure;
- state[0].hil_set = true;
- state[0].healthy = true;
- }
- bool AP_Airspeed::use(uint8_t i) const
- {
- if (!enabled(i) || !param[i].use) {
- return false;
- }
- if (param[i].use == 2 && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) != 0) {
-
-
-
- return false;
- }
- return true;
- }
- bool AP_Airspeed::all_healthy(void) const
- {
- for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
- if (enabled(i) && !healthy(i)) {
- return false;
- }
- }
- return true;
- }
- AP_Airspeed *AP_Airspeed::_singleton;
- namespace AP {
- AP_Airspeed *airspeed()
- {
- return AP_Airspeed::get_singleton();
- }
- };
|