AP_Airspeed: added ARSPD_TYPE and use standard driver backend methods

this will allow for new sensor types
This commit is contained in:
Andrew Tridgell 2016-11-30 15:49:19 +11:00 committed by Tom Pittenger
parent b614b41d6d
commit 14a1f559c7
8 changed files with 125 additions and 58 deletions

View File

@ -15,7 +15,6 @@
/*
* APM_Airspeed.cpp - airspeed (pitot) driver
*/
#include "AP_Airspeed.h"
#include <AP_ADC/AP_ADC.h>
#include <AP_Common/AP_Common.h>
@ -24,16 +23,18 @@
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS.h>
#include <utility>
#include "AP_Airspeed.h"
#include "AP_Airspeed_I2C.h"
#include "AP_Airspeed_analog.h"
extern const AP_HAL::HAL &hal;
// the virtual pin for digital airspeed sensors
#define AP_AIRSPEED_I2C_PIN 65
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define ARSPD_DEFAULT_TYPE TYPE_ANALOG
#define ARSPD_DEFAULT_PIN 1
#else
#define ARSPD_DEFAULT_PIN AP_AIRSPEED_I2C_PIN
#define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
#define ARSPD_DEFAULT_PIN 15
#endif
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
@ -47,12 +48,12 @@ extern const AP_HAL::HAL &hal;
// table of user settable parameters
const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Param: ENABLE
// @DisplayName: Airspeed enable
// @Description: enable airspeed sensor
// @Values: 0:Disable,1:Enable
// @Param: TYPE
// @DisplayName: Airspeed type
// @Description: Type of airspeed sensor
// @Values: 0:None,1:I2C-MS4525D0,2:Analog
// @User: Standard
AP_GROUPINFO_FLAGS("ENABLE", 0, AP_Airspeed, _enable, 1, AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("TYPE", 0, AP_Airspeed, _type, ARSPD_DEFAULT_TYPE, AP_PARAM_FLAG_ENABLE),
// @Param: USE
// @DisplayName: Airspeed use
@ -77,7 +78,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Param: PIN
// @DisplayName: Airspeed pin
// @Description: The analog pin number that the airspeed sensor is connected to. Set this to 0..9 for the APM2 analog pins. Set to 64 on an APM1 for the dedicated airspeed port on the end of the board. Set to 11 on PX4 for the analog airspeed port. Set to 15 on the Pixhawk for the analog airspeed port. Set to 65 on the PX4 or Pixhawk for an EagleTree or MEAS I2C airspeed sensor.
// @Description: The pin number that the airspeed sensor is connected to for analog sensors. Set to 15 on the Pixhawk for the analog airspeed port.
// @User: Advanced
AP_GROUPINFO("PIN", 4, AP_Airspeed, _pin, ARSPD_DEFAULT_PIN),
@ -127,19 +128,36 @@ AP_Airspeed::AP_Airspeed()
void AP_Airspeed::init()
{
// cope with upgrade from old system
if (_pin.load() && _pin.get() != 65) {
_type.set_default(TYPE_ANALOG);
}
_last_pressure = 0;
_calibration.init(_ratio);
_last_saved_ratio = _ratio;
_counter = 0;
analog.init();
digital.init();
switch ((enum airspeed_type)_type.get()) {
case TYPE_NONE:
// nothing to do
break;
case TYPE_I2C_MS4525:
sensor = new AP_Airspeed_I2C(*this);
break;
case TYPE_ANALOG:
sensor = new AP_Airspeed_Analog(*this);
break;
}
if (sensor && !sensor->init()) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Airspeed init failed");
}
}
// read the airspeed sensor
float AP_Airspeed::get_pressure(void)
{
if (!_enable) {
if (!enabled()) {
return 0;
}
if (_hil_set) {
@ -147,10 +165,8 @@ float AP_Airspeed::get_pressure(void)
return _hil_pressure;
}
float pressure = 0;
if (_pin == AP_AIRSPEED_I2C_PIN) {
_healthy = digital.get_differential_pressure(pressure);
} else {
_healthy = analog.get_differential_pressure(pressure);
if (sensor) {
_healthy = sensor->get_differential_pressure(pressure);
}
return pressure;
}
@ -158,11 +174,11 @@ float AP_Airspeed::get_pressure(void)
// get a temperature reading if possible
bool AP_Airspeed::get_temperature(float &temperature)
{
if (!_enable) {
if (!enabled()) {
return false;
}
if (_pin == AP_AIRSPEED_I2C_PIN) {
return digital.get_temperature(temperature);
if (sensor) {
return sensor->get_temperature(temperature);
}
return false;
}
@ -171,7 +187,7 @@ bool AP_Airspeed::get_temperature(float &temperature)
// the get_airspeed() interface can be used
void AP_Airspeed::calibrate(bool in_startup)
{
if (!_enable) {
if (!enabled()) {
return;
}
if (in_startup && _skip_cal) {
@ -214,7 +230,7 @@ void AP_Airspeed::update_calibration(float raw_pressure)
void AP_Airspeed::read(void)
{
float airspeed_pressure;
if (!_enable) {
if (!enabled()) {
return;
}
float raw_pressure = get_pressure();

View File

@ -3,12 +3,9 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include "AP_Airspeed_Backend.h"
#include "AP_Airspeed_I2C.h"
#include "AP_Airspeed_analog.h"
class Airspeed_Calibration {
public:
@ -35,6 +32,8 @@ private:
class AP_Airspeed
{
public:
friend class AP_Airspeed_Backend;
// constructor
AP_Airspeed();
@ -77,17 +76,17 @@ public:
// return true if airspeed is enabled, and airspeed use is set
bool use(void) const {
return _enable && _use;
return enabled() && _use;
}
// return true if airspeed is enabled
bool enabled(void) const {
return _enable;
return _type.get() != TYPE_NONE;
}
// force disable the airspeed sensor
void disable(void) {
_enable.set(0);
_type.set(TYPE_NONE);
}
// used by HIL to set the airspeed
@ -128,7 +127,7 @@ public:
void log_mavlink_send(mavlink_channel_t chan, const Vector3f &vground);
// return health status of sensor
bool healthy(void) const { return _healthy && fabsf(_offset) > 0 && _enable; }
bool healthy(void) const { return _healthy && fabsf(_offset) > 0 && enabled(); }
void setHIL(float pressure) { _healthy=_hil_set=true; _hil_pressure=pressure; }
@ -143,12 +142,18 @@ public:
PITOT_TUBE_ORDER_NEGATIVE = 1,
PITOT_TUBE_ORDER_AUTO = 2 };
enum airspeed_type {
TYPE_NONE=0,
TYPE_I2C_MS4525=1,
TYPE_ANALOG=2,
};
private:
AP_Float _offset;
AP_Float _ratio;
AP_Float _psi_range;
AP_Int8 _use;
AP_Int8 _enable;
AP_Int8 _type;
AP_Int8 _pin;
AP_Int8 _autocal;
AP_Int8 _tube_order;
@ -178,6 +183,5 @@ private:
float get_pressure(void);
void update_calibration(float raw_pressure);
AP_Airspeed_Analog analog{_pin, _psi_range};
AP_Airspeed_I2C digital{_psi_range};
AP_Airspeed_Backend *sensor;
};

View File

@ -0,0 +1,38 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
backend driver class for airspeed
*/
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_Airspeed.h"
AP_Airspeed_Backend::AP_Airspeed_Backend(AP_Airspeed &_frontend) :
frontend(_frontend)
{}
int8_t AP_Airspeed_Backend::get_pin(void) const
{
return frontend._pin;
}
float AP_Airspeed_Backend::get_psi_range(void) const
{
return frontend._psi_range;
}

View File

@ -21,8 +21,12 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
class AP_Airspeed;
class AP_Airspeed_Backend {
public:
AP_Airspeed_Backend(AP_Airspeed &frontend);
// probe and initialise the sensor
virtual bool init(void) = 0;
@ -31,4 +35,11 @@ public:
// return the current temperature in degrees C, if available
virtual bool get_temperature(float &temperature) = 0;
protected:
int8_t get_pin(void) const;
float get_psi_range(void) const;
private:
AP_Airspeed &frontend;
};

View File

@ -35,8 +35,8 @@ extern const AP_HAL::HAL &hal;
#define MS4525D0_I2C_BUS 1
#endif
AP_Airspeed_I2C::AP_Airspeed_I2C(const AP_Float &psi_range) :
_psi_range(psi_range)
AP_Airspeed_I2C::AP_Airspeed_I2C(AP_Airspeed &_frontend) :
AP_Airspeed_Backend(_frontend)
{
}
@ -101,7 +101,7 @@ void AP_Airspeed_I2C::_collect()
dT_raw = (data[2] << 8) + data[3];
dT_raw = (0xFFE0 & dT_raw) >> 5;
const float P_max = _psi_range.get();
const float P_max = get_psi_range();
const float P_min = - P_max;
const float PSI_to_Pa = 6894.757f;
/*

View File

@ -30,17 +30,17 @@
class AP_Airspeed_I2C : public AP_Airspeed_Backend
{
public:
AP_Airspeed_I2C(const AP_Float &psi_range);
AP_Airspeed_I2C(AP_Airspeed &frontend);
~AP_Airspeed_I2C(void) {}
// probe and initialise the sensor
bool init();
bool init() override;
// return the current differential_pressure in Pascal
bool get_differential_pressure(float &pressure);
bool get_differential_pressure(float &pressure) override;
// return the current temperature in degrees C, if available
bool get_temperature(float &temperature);
bool get_temperature(float &temperature) override;
private:
void _measure();
@ -53,5 +53,4 @@ private:
uint32_t _last_sample_time_ms;
uint32_t _measurement_started_ms;
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
const AP_Float &_psi_range;
};

View File

@ -15,23 +15,27 @@
/*
* analog airspeed driver
*/
#include "AP_Airspeed_analog.h"
#include <AP_ADC/AP_ADC.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "AP_Airspeed.h"
#include "AP_Airspeed_analog.h"
extern const AP_HAL::HAL &hal;
// scaling for 3DR analog airspeed sensor
#define VOLTS_TO_PASCAL 819
AP_Airspeed_Analog::AP_Airspeed_Analog(AP_Airspeed &_frontend) :
AP_Airspeed_Backend(_frontend)
{
_source = hal.analogin->channel(get_pin());
}
bool AP_Airspeed_Analog::init()
{
_source = hal.analogin->channel(_pin);
return true;
return _source != nullptr;
}
// read the airspeed sensor
@ -40,7 +44,8 @@ bool AP_Airspeed_Analog::get_differential_pressure(float &pressure)
if (_source == nullptr) {
return false;
}
_source->set_pin(_pin);
pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL / _psi_range.get();
// allow pin to change
_source->set_pin(get_pin());
pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL / get_psi_range();
return true;
}

View File

@ -8,23 +8,17 @@
class AP_Airspeed_Analog : public AP_Airspeed_Backend
{
public:
AP_Airspeed_Analog(const AP_Int8 &pin, const AP_Float &psi_range)
: _source(nullptr)
, _pin(pin)
, _psi_range(psi_range)
{ }
AP_Airspeed_Analog(AP_Airspeed &frontend);
// probe and initialise the sensor
bool init(void);
bool init(void) override;
// return the current differential_pressure in Pascal
bool get_differential_pressure(float &pressure);
bool get_differential_pressure(float &pressure) override;
// temperature not available via analog backend
bool get_temperature(float &temperature) { return false; }
bool get_temperature(float &temperature) override { return false; }
private:
AP_HAL::AnalogSource *_source;
const AP_Int8 &_pin;
const AP_Float &_psi_range;
};