AP_Airspeed: Periph: remove useage of hidden params and remove tuber order

This commit is contained in:
Iampete1 2022-12-15 11:41:30 +00:00 committed by Andrew Tridgell
parent aedac8a6d0
commit e142747d1f
5 changed files with 64 additions and 15 deletions

View File

@ -147,6 +147,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
AP_GROUPINFO("_AUTOCAL", 5, AP_Airspeed, param[0].autocal, 0),
#endif
#ifndef HAL_BUILD_AP_PERIPH
// @Param: _TUBE_ORDER
// @DisplayName: Control pitot tube order
// @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed.
@ -154,7 +155,6 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Values: 0:Normal,1:Swapped,2:Auto Detect
AP_GROUPINFO("_TUBE_ORDER", 6, AP_Airspeed, param[0].tube_order, 2),
#ifndef HAL_BUILD_AP_PERIPH
// @Param: _SKIP_CAL
// @DisplayName: Skip airspeed offset calibration on startup
// @Description: This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
@ -239,6 +239,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @User: Standard
AP_GROUPINFO_FLAGS("2_TYPE", 11, AP_Airspeed, param[1].type, 0, AP_PARAM_FLAG_ENABLE),
#ifndef HAL_BUILD_AP_PERIPH
// @Param: 2_USE
// @DisplayName: Enable use of 2nd airspeed sensor
// @Description: use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won't be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller
@ -266,14 +267,18 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Description: Pin number indicating location of analog airspeed sensors. Pixhawk/Cube if set to 15.
// @User: Advanced
AP_GROUPINFO("2_PIN", 15, AP_Airspeed, param[1].pin, 0),
#endif
#if AP_AIRSPEED_AUTOCAL_ENABLE
// @Param: 2_AUTOCAL
// @DisplayName: Automatic airspeed ratio calibration for 2nd airspeed sensor
// @Description: If this is enabled then the autopilot will automatically adjust the ARSPD_RATIO during flight, based upon an estimation filter using ground speed and true airspeed. The automatic calibration will save the new ratio to EEPROM every 2 minutes if it changes by more than 5%. This option should be enabled for a calibration flight then disabled again when calibration is complete. Leaving it enabled all the time is not recommended.
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
// @User: Advanced
AP_GROUPINFO("2_AUTOCAL", 16, AP_Airspeed, param[1].autocal, 0),
#endif
#ifndef HAL_BUILD_AP_PERIPH
// @Param: 2_TUBE_ORDR
// @DisplayName: Control pitot tube order of 2nd airspeed sensor
// @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed.
@ -287,6 +292,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Values: 0:Disable,1:Enable
// @User: Advanced
AP_GROUPINFO("2_SKIP_CAL", 18, AP_Airspeed, param[1].skip_cal, 0),
#endif
// @Param: 2_PSI_RANGE
// @DisplayName: The PSI range of the device for 2nd sensor
@ -294,6 +300,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @User: Advanced
AP_GROUPINFO("2_PSI_RANGE", 19, AP_Airspeed, param[1].psi_range, PSI_RANGE_DEFAULT),
#ifndef HAL_BUILD_AP_PERIPH
// @Param: 2_BUS
// @DisplayName: Airspeed I2C bus for 2nd sensor
// @Description: Bus number of the I2C bus where the airspeed sensor is connected. May not correspond to board's I2C bus number labels. Retry another bus and reboot if airspeed sensor fails to initialize.
@ -301,6 +308,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("2_BUS", 20, AP_Airspeed, param[1].bus, 1),
#endif
#if AIRSPEED_MAX_SENSORS > 1
// @Param: 2_DEVID
@ -377,12 +385,13 @@ void AP_Airspeed::init()
// already initialised
return;
}
#ifndef HAL_BUILD_AP_PERIPH
// cope with upgrade from old system
if (param[0].pin.load() && param[0].pin.get() != 65) {
param[0].type.set_default(TYPE_ANALOG);
}
#ifndef HAL_BUILD_AP_PERIPH
// Switch to dedicated WIND_MAX param
// PARAMETER_CONVERSION - Added: Oct-2020
const float ahrs_max_wind = AP::ahrs().get_max_wind();
@ -561,6 +570,7 @@ bool AP_Airspeed::get_temperature(uint8_t i, float &temperature)
// least once before the get_airspeed() interface can be used
void AP_Airspeed::calibrate(bool in_startup)
{
#ifndef HAL_BUILD_AP_PERIPH
if (hal.util->was_watchdog_reset()) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed: skipping cal");
return;
@ -586,6 +596,7 @@ void AP_Airspeed::calibrate(bool in_startup)
state[i].cal.read_count = 0;
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed %u calibration started", i+1);
}
#endif // HAL_BUILD_AP_PERIPH
}
/*
@ -593,6 +604,7 @@ void AP_Airspeed::calibrate(bool in_startup)
*/
void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
{
#ifndef HAL_BUILD_AP_PERIPH
if (!enabled(i) || state[i].cal.start_ms == 0) {
return;
}
@ -626,6 +638,7 @@ void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
state[i].cal.count++;
}
state[i].cal.read_count++;
#endif // HAL_BUILD_AP_PERIPH
}
// read one airspeed sensor
@ -643,17 +656,18 @@ void AP_Airspeed::read(uint8_t 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);
}
float airspeed_pressure = raw_pressure - param[i].offset;
float airspeed_pressure = raw_pressure - get_offset(i);
// remember raw pressure for logging
state[i].corrected_pressure = airspeed_pressure;
#ifndef HAL_BUILD_AP_PERIPH
bool prev_healthy = state[i].healthy;
if (state[i].cal.start_ms != 0) {
update_calibration(i, raw_pressure);
}
// filter before clamping positive
if (!prev_healthy) {
// if the previous state was not healthy then we should not
@ -686,6 +700,7 @@ void AP_Airspeed::read(uint8_t i)
state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio);
break;
}
#endif // HAL_BUILD_AP_PERIPH
}
// read all airspeed sensors
@ -809,21 +824,23 @@ void AP_Airspeed::Log_Airspeed()
bool AP_Airspeed::use(uint8_t i) const
{
#ifndef HAL_BUILD_AP_PERIPH
if (_force_disable_use) {
return false;
}
if (!enabled(i) || !param[i].use) {
return false;
}
#ifndef HAL_BUILD_AP_PERIPH
if (param[i].use == 2 && !is_zero(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))) {
// special case for gliders with airspeed sensors behind the
// propeller. Allow airspeed to be disabled when throttle is
// running
return false;
}
#endif
return true;
#else
return false;
#endif // HAL_BUILD_AP_PERIPH
}
/*

View File

@ -67,7 +67,11 @@ public:
// return the current airspeed ratio (dimensionless)
float get_airspeed_ratio(uint8_t i) const {
#ifndef HAL_BUILD_AP_PERIPH
return param[i].ratio;
#else
return 0.0;
#endif
}
float get_airspeed_ratio(void) const { return get_airspeed_ratio(primary); }
@ -76,10 +80,12 @@ public:
bool get_temperature(float &temperature) { return get_temperature(primary, temperature); }
// set the airspeed ratio (dimensionless)
#ifndef HAL_BUILD_AP_PERIPH
void set_airspeed_ratio(uint8_t i, float ratio) {
param[i].ratio.set(ratio);
}
void set_airspeed_ratio(float ratio) { set_airspeed_ratio(primary, ratio); }
#endif
// return true if airspeed is enabled, and airspeed use is set
bool use(uint8_t i) const;
@ -178,17 +184,23 @@ private:
AP_Float _wind_gate;
struct {
AP_Int32 bus_id;
#ifndef HAL_BUILD_AP_PERIPH
AP_Float offset;
AP_Float ratio;
#endif
AP_Float psi_range;
#ifndef HAL_BUILD_AP_PERIPH
AP_Int8 use;
AP_Int8 type;
AP_Int8 pin;
AP_Int8 bus;
AP_Int8 autocal;
AP_Int8 tube_order;
AP_Int8 skip_cal;
AP_Int32 bus_id;
#endif
AP_Int8 type;
AP_Int8 bus;
#if AP_AIRSPEED_AUTOCAL_ENABLE
AP_Int8 autocal;
#endif
AP_Int8 tube_order;
} param[AIRSPEED_MAX_SENSORS];
struct airspeed_state {
@ -265,7 +277,11 @@ private:
void send_airspeed_calibration(const Vector3f &vg);
// return the current calibration offset
float get_offset(uint8_t i) const {
#ifndef HAL_BUILD_AP_PERIPH
return param[i].offset;
#else
return 0.0;
#endif
}
float get_offset(void) const { return get_offset(primary); }

View File

@ -37,7 +37,11 @@ AP_Airspeed_Backend::~AP_Airspeed_Backend(void)
int8_t AP_Airspeed_Backend::get_pin(void) const
{
#ifndef HAL_BUILD_AP_PERIPH
return frontend.param[instance].pin;
#else
return 0;
#endif
}
float AP_Airspeed_Backend::get_psi_range(void) const

View File

@ -65,7 +65,11 @@ protected:
}
AP_Airspeed::pitot_tube_order get_tube_order(void) const {
#ifndef HAL_BUILD_AP_PERIPH
return AP_Airspeed::pitot_tube_order(frontend.param[instance].tube_order.get());
#else
return AP_Airspeed::pitot_tube_order::PITOT_TUBE_ORDER_AUTO;
#endif
}
// semaphore for access to shared frontend data
@ -82,17 +86,23 @@ protected:
// set to no zero cal, which makes sense for some sensors
void set_skip_cal(void) {
#ifndef HAL_BUILD_AP_PERIPH
frontend.param[instance].skip_cal.set(1);
#endif
}
// set zero offset
void set_offset(float ofs) {
#ifndef HAL_BUILD_AP_PERIPH
frontend.param[instance].offset.set(ofs);
#endif
}
// set use
void set_use(int8_t use) {
#ifndef HAL_BUILD_AP_PERIPH
frontend.param[instance].use.set(use);
#endif
}
// set bus ID of this instance, for ARSPD_DEVID parameters

View File

@ -18,6 +18,7 @@ void AP_Airspeed::check_sensor_failures()
void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
{
#ifndef HAL_BUILD_AP_PERIPH
const uint32_t now_ms = AP_HAL::millis();
if ((now_ms - state[i].failures.last_check_ms) <= 200) {
// slow the checking rate
@ -116,4 +117,5 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
param[i].use.set_and_notify(state[i].failures.param_use_backup); // resume
state[i].failures.param_use_backup = -1; // set to invalid so we don't use it
}
#endif // HAL_BUILD_AP_PERIPH
}