AP_Airspeed: added ARSP_PSI_RANGE parameter

for using pressure sensors with a different range
This commit is contained in:
Andrew Tridgell 2016-06-09 10:10:54 +10:00
parent 28d5103435
commit 003c94830b
8 changed files with 42 additions and 11 deletions

View File

@ -64,10 +64,17 @@ extern const AP_HAL::HAL &hal;
#else #else
#define ARSPD_DEFAULT_PIN AP_AIRSPEED_I2C_PIN #define ARSPD_DEFAULT_PIN AP_AIRSPEED_I2C_PIN
#endif #endif
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
#define PSI_RANGE_DEFAULT 0.05
#endif
#else #else
#define ARSPD_DEFAULT_PIN 0 #define ARSPD_DEFAULT_PIN 0
#endif #endif
#ifndef PSI_RANGE_DEFAULT
#define PSI_RANGE_DEFAULT 1.0f
#endif
// table of user settable parameters // table of user settable parameters
const AP_Param::GroupInfo AP_Airspeed::var_info[] = { const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
@ -120,6 +127,12 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("SKIP_CAL", 7, AP_Airspeed, _skip_cal, 0), AP_GROUPINFO("SKIP_CAL", 7, AP_Airspeed, _skip_cal, 0),
// @Param: PSI_RANGE
// @DisplayName: The PSI range of the device
// @Description: This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
// @User: Advanced
AP_GROUPINFO("PSI_RANGE", 8, AP_Airspeed, _psi_range, PSI_RANGE_DEFAULT),
AP_GROUPEND AP_GROUPEND
}; };
@ -127,7 +140,6 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
AP_Airspeed::AP_Airspeed(const AP_Vehicle::FixedWing &parms) AP_Airspeed::AP_Airspeed(const AP_Vehicle::FixedWing &parms)
: _EAS2TAS(1.0f) : _EAS2TAS(1.0f)
, _calibration(parms) , _calibration(parms)
, analog(_pin)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
} }

View File

@ -149,6 +149,7 @@ public:
private: private:
AP_Float _offset; AP_Float _offset;
AP_Float _ratio; AP_Float _ratio;
AP_Float _psi_range;
AP_Int8 _use; AP_Int8 _use;
AP_Int8 _enable; AP_Int8 _enable;
AP_Int8 _pin; AP_Int8 _pin;
@ -180,10 +181,10 @@ private:
float get_pressure(void); float get_pressure(void);
void update_calibration(float raw_pressure); void update_calibration(float raw_pressure);
AP_Airspeed_Analog analog; AP_Airspeed_Analog analog{_pin, _psi_range};
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
AP_Airspeed_PX4 digital; AP_Airspeed_PX4 digital{_psi_range};
#else #else
AP_Airspeed_I2C digital; AP_Airspeed_I2C digital{_psi_range};
#endif #endif
}; };

View File

@ -37,6 +37,11 @@ extern const AP_HAL::HAL &hal;
#define MS4525D0_I2C_BUS 1 #define MS4525D0_I2C_BUS 1
#endif #endif
AP_Airspeed_I2C::AP_Airspeed_I2C(const AP_Float &psi_range) :
_psi_range(psi_range)
{
}
// probe and initialise the sensor // probe and initialise the sensor
bool AP_Airspeed_I2C::init() bool AP_Airspeed_I2C::init()
{ {
@ -91,8 +96,8 @@ void AP_Airspeed_I2C::_collect()
dT_raw = (data[2] << 8) + data[3]; dT_raw = (data[2] << 8) + data[3];
dT_raw = (0xFFE0 & dT_raw) >> 5; dT_raw = (0xFFE0 & dT_raw) >> 5;
const float P_min = -1.0f; const float P_max = _psi_range.get();
const float P_max = 1.0f; const float P_min = - P_max;
const float PSI_to_Pa = 6894.757f; const float PSI_to_Pa = 6894.757f;
/* /*
this equation is an inversion of the equation in the this equation is an inversion of the equation in the

View File

@ -21,6 +21,10 @@
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <AP_HAL/utility/OwnPtr.h>
#include <AP_HAL/I2CDevice.h>
#include <utility>
#include "AP_Airspeed_Backend.h" #include "AP_Airspeed_Backend.h"
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
@ -28,6 +32,9 @@
class AP_Airspeed_I2C : public AP_Airspeed_Backend class AP_Airspeed_I2C : public AP_Airspeed_Backend
{ {
public: public:
AP_Airspeed_I2C(const AP_Float &psi_range);
~AP_Airspeed_I2C(void) {}
// probe and initialise the sensor // probe and initialise the sensor
bool init(); bool init();
@ -46,4 +53,5 @@ private:
uint32_t _last_sample_time_ms; uint32_t _last_sample_time_ms;
uint32_t _measurement_started_ms; uint32_t _measurement_started_ms;
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev; AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
const AP_Float &_psi_range;
}; };

View File

@ -61,7 +61,7 @@ bool AP_Airspeed_PX4::get_differential_pressure(float &pressure)
while (::read(_fd, &report, sizeof(report)) == sizeof(report) && while (::read(_fd, &report, sizeof(report)) == sizeof(report) &&
report.timestamp != _last_timestamp) { report.timestamp != _last_timestamp) {
psum += report.differential_pressure_raw_pa; psum += report.differential_pressure_raw_pa / _psi_range.get();
tsum += report.temperature; tsum += report.temperature;
count++; count++;
_last_timestamp = report.timestamp; _last_timestamp = report.timestamp;

View File

@ -21,12 +21,14 @@
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include "AP_Airspeed_Backend.h" #include "AP_Airspeed_Backend.h"
class AP_Airspeed_PX4 : public AP_Airspeed_Backend { class AP_Airspeed_PX4 : public AP_Airspeed_Backend {
public: public:
// constructor // constructor
AP_Airspeed_PX4() : _fd(-1) {} AP_Airspeed_PX4(const AP_Float &psi_range) :
_psi_range(psi_range) {}
// probe and initialise the sensor // probe and initialise the sensor
bool init(void); bool init(void);
@ -38,7 +40,8 @@ public:
bool get_temperature(float &temperature); bool get_temperature(float &temperature);
private: private:
int _fd; int _fd = -1;
uint64_t _last_timestamp; uint64_t _last_timestamp;
float _temperature; float _temperature;
const AP_Float &_psi_range;
}; };

View File

@ -42,6 +42,6 @@ bool AP_Airspeed_Analog::get_differential_pressure(float &pressure)
return false; return false;
} }
_source->set_pin(_pin); _source->set_pin(_pin);
pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL; pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL / _psi_range.get();
return true; return true;
} }

View File

@ -9,9 +9,10 @@
class AP_Airspeed_Analog : public AP_Airspeed_Backend class AP_Airspeed_Analog : public AP_Airspeed_Backend
{ {
public: public:
AP_Airspeed_Analog(const AP_Int8 &pin) AP_Airspeed_Analog(const AP_Int8 &pin, const AP_Float &psi_range)
: _source(NULL) : _source(NULL)
, _pin(pin) , _pin(pin)
, _psi_range(psi_range)
{ } { }
// probe and initialise the sensor // probe and initialise the sensor
@ -26,4 +27,5 @@ public:
private: private:
AP_HAL::AnalogSource *_source; AP_HAL::AnalogSource *_source;
const AP_Int8 &_pin; const AP_Int8 &_pin;
const AP_Float &_psi_range;
}; };