2012-07-15 22:21:20 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#ifndef __AP_AIRSPEED_H__
|
|
|
|
#define __AP_AIRSPEED_H__
|
|
|
|
|
|
|
|
#include <AP_Common.h>
|
2012-10-09 21:01:22 -03:00
|
|
|
#include <AP_HAL.h>
|
2012-07-15 22:21:20 -03:00
|
|
|
#include <AP_Param.h>
|
2013-08-28 09:35:50 -03:00
|
|
|
#include <GCS_MAVLink.h>
|
2013-09-12 22:45:57 -03:00
|
|
|
#include <AP_Vehicle.h>
|
2013-09-28 05:40:29 -03:00
|
|
|
#include <AP_Airspeed_Backend.h>
|
|
|
|
#include <AP_Airspeed_analog.h>
|
|
|
|
#include <AP_Airspeed_PX4.h>
|
|
|
|
#include <AP_Airspeed_I2C.h>
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
class Airspeed_Calibration {
|
|
|
|
public:
|
2013-08-28 09:35:50 -03:00
|
|
|
friend class AP_Airspeed;
|
2013-07-19 19:14:58 -03:00
|
|
|
// constructor
|
2013-09-12 22:45:57 -03:00
|
|
|
Airspeed_Calibration(const AP_Vehicle::FixedWing &parms);
|
2013-07-19 19:14:58 -03:00
|
|
|
|
|
|
|
// initialise the calibration
|
|
|
|
void init(float initial_ratio);
|
|
|
|
|
|
|
|
// take current airspeed in m/s and ground speed vector and return
|
|
|
|
// new scaling factor
|
|
|
|
float update(float airspeed, const Vector3f &vg);
|
|
|
|
|
|
|
|
private:
|
|
|
|
// state of kalman filter for airspeed ratio estimation
|
|
|
|
Matrix3f P; // covarience matrix
|
|
|
|
const float Q0; // process noise matrix top left and middle element
|
|
|
|
const float Q1; // process noise matrix bottom right element
|
|
|
|
Vector3f state; // state vector
|
|
|
|
const float DT; // time delta
|
2013-09-12 22:45:57 -03:00
|
|
|
const AP_Vehicle::FixedWing &aparm;
|
2013-07-19 19:14:58 -03:00
|
|
|
};
|
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
class AP_Airspeed
|
|
|
|
{
|
|
|
|
public:
|
2012-08-17 03:08:43 -03:00
|
|
|
// constructor
|
2013-09-12 22:45:57 -03:00
|
|
|
AP_Airspeed(const AP_Vehicle::FixedWing &parms) :
|
2013-08-28 09:35:50 -03:00
|
|
|
_EAS2TAS(1.0f),
|
2013-09-28 05:40:29 -03:00
|
|
|
_calibration(parms),
|
|
|
|
analog(_pin),
|
|
|
|
_healthy(false)
|
2013-07-19 19:14:58 -03:00
|
|
|
{
|
2012-12-12 17:42:43 -04:00
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
};
|
2012-10-09 21:01:22 -03:00
|
|
|
|
2013-06-02 22:40:06 -03:00
|
|
|
void init(void);
|
|
|
|
|
2012-08-17 03:08:43 -03:00
|
|
|
// read the analog source and update _airspeed
|
|
|
|
void read(void);
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2012-08-17 03:08:43 -03:00
|
|
|
// calibrate the airspeed. This must be called on startup if the
|
|
|
|
// altitude/climb_rate/acceleration interfaces are ever used
|
2012-10-09 21:01:22 -03:00
|
|
|
void calibrate();
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2012-08-17 03:08:43 -03:00
|
|
|
// return the current airspeed in m/s
|
2013-07-13 08:53:38 -03:00
|
|
|
float get_airspeed(void) const {
|
2012-08-17 03:08:43 -03:00
|
|
|
return _airspeed;
|
|
|
|
}
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-06-02 22:40:06 -03:00
|
|
|
// return the unfiltered airspeed in m/s
|
2013-07-13 08:53:38 -03:00
|
|
|
float get_raw_airspeed(void) const {
|
2013-06-02 22:40:06 -03:00
|
|
|
return _raw_airspeed;
|
|
|
|
}
|
|
|
|
|
2012-08-17 03:08:43 -03:00
|
|
|
// return the current airspeed in cm/s
|
2013-07-13 08:53:38 -03:00
|
|
|
float get_airspeed_cm(void) const {
|
2012-08-17 03:08:43 -03:00
|
|
|
return _airspeed*100;
|
|
|
|
}
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-07-13 08:53:38 -03:00
|
|
|
// return the current airspeed ratio (dimensionless)
|
|
|
|
float get_airspeed_ratio(void) const {
|
|
|
|
return _ratio;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set the airspeed ratio (dimensionless)
|
|
|
|
void set_airspeed_ratio(float ratio) {
|
|
|
|
_ratio.set(ratio);
|
|
|
|
}
|
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
// return true if airspeed is enabled, and airspeed use is set
|
2013-07-13 08:53:38 -03:00
|
|
|
bool use(void) const {
|
2013-09-28 05:40:29 -03:00
|
|
|
return _enable && _use && _offset != 0 && _healthy;
|
2012-08-17 03:08:43 -03:00
|
|
|
}
|
2012-07-15 22:21:20 -03:00
|
|
|
|
|
|
|
// return true if airspeed is enabled
|
2013-07-13 08:53:38 -03:00
|
|
|
bool enabled(void) const {
|
2012-08-17 03:08:43 -03:00
|
|
|
return _enable;
|
|
|
|
}
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-06-02 22:40:06 -03:00
|
|
|
// force disable the airspeed sensor
|
|
|
|
void disable(void) {
|
|
|
|
_enable.set(0);
|
|
|
|
}
|
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
// used by HIL to set the airspeed
|
2012-08-17 03:08:43 -03:00
|
|
|
void set_HIL(float airspeed) {
|
|
|
|
_airspeed = airspeed;
|
|
|
|
}
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// return the differential pressure in Pascal for the last
|
|
|
|
// airspeed reading. Used by the calibration code
|
|
|
|
float get_differential_pressure(void) const {
|
|
|
|
return max(_last_pressure - _offset, 0);
|
|
|
|
}
|
|
|
|
|
2013-07-19 22:11:04 -03:00
|
|
|
// set the apparent to true airspeed ratio
|
|
|
|
void set_EAS2TAS(float v) {
|
|
|
|
_EAS2TAS = v;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get the apparent to true airspeed ratio
|
|
|
|
float get_EAS2TAS(void) const {
|
|
|
|
return _EAS2TAS;
|
|
|
|
}
|
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// update airspeed ratio calibration
|
2013-08-28 09:35:50 -03:00
|
|
|
void update_calibration(const Vector3f &vground);
|
|
|
|
|
|
|
|
// log data to MAVLink
|
|
|
|
void log_mavlink_send(mavlink_channel_t chan, const Vector3f &vground);
|
2013-07-19 19:14:58 -03:00
|
|
|
|
2012-10-09 21:01:22 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-08-28 09:35:50 -03:00
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
private:
|
2012-08-17 03:08:43 -03:00
|
|
|
AP_Float _offset;
|
|
|
|
AP_Float _ratio;
|
|
|
|
AP_Int8 _use;
|
|
|
|
AP_Int8 _enable;
|
2013-06-02 22:40:06 -03:00
|
|
|
AP_Int8 _pin;
|
2013-07-19 19:14:58 -03:00
|
|
|
AP_Int8 _autocal;
|
2013-06-02 22:40:06 -03:00
|
|
|
float _raw_airspeed;
|
2012-08-17 03:08:43 -03:00
|
|
|
float _airspeed;
|
2013-06-02 22:40:06 -03:00
|
|
|
float _last_pressure;
|
2013-07-19 22:11:04 -03:00
|
|
|
float _EAS2TAS;
|
2013-09-28 05:40:29 -03:00
|
|
|
bool _healthy;
|
2013-06-02 22:40:06 -03:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
Airspeed_Calibration _calibration;
|
|
|
|
float _last_saved_ratio;
|
|
|
|
uint8_t _counter;
|
|
|
|
|
2013-06-02 22:40:06 -03:00
|
|
|
float get_pressure(void);
|
2013-09-28 05:40:29 -03:00
|
|
|
|
|
|
|
AP_Airspeed_Analog analog;
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
AP_Airspeed_PX4 digital;
|
|
|
|
#else
|
|
|
|
AP_Airspeed_I2C digital;
|
|
|
|
#endif
|
2012-07-15 22:21:20 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_AIRSPEED_H__
|
2013-07-19 19:14:58 -03:00
|
|
|
|