2011-12-28 05:32:21 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-11-05 22:11:25 -03:00
|
|
|
|
|
|
|
#ifndef __AP_BARO_H__
|
|
|
|
#define __AP_BARO_H__
|
|
|
|
|
2012-06-19 23:25:19 -03:00
|
|
|
#include <AP_Param.h>
|
|
|
|
#include <Filter.h>
|
2012-07-04 19:08:16 -03:00
|
|
|
#include <DerivativeFilter.h>
|
2011-12-09 02:33:00 -04:00
|
|
|
|
2011-11-05 22:11:25 -03:00
|
|
|
class AP_Baro
|
|
|
|
{
|
2012-08-17 03:09:24 -03:00
|
|
|
public:
|
|
|
|
bool healthy;
|
|
|
|
AP_Baro() {
|
|
|
|
}
|
2012-10-11 14:53:21 -03:00
|
|
|
virtual bool init()=0;
|
2012-08-17 03:09:24 -03:00
|
|
|
virtual uint8_t read() = 0;
|
|
|
|
virtual float get_pressure() = 0;
|
|
|
|
virtual float get_temperature() = 0;
|
|
|
|
|
|
|
|
virtual int32_t get_raw_pressure() = 0;
|
|
|
|
virtual int32_t get_raw_temp() = 0;
|
2012-06-19 23:25:19 -03:00
|
|
|
|
|
|
|
// calibrate the barometer. This must be called on startup if the
|
|
|
|
// altitude/climb_rate/acceleration interfaces are ever used
|
|
|
|
// the callback is a delay() like routine
|
2012-10-11 14:53:21 -03:00
|
|
|
void calibrate();
|
2012-06-19 23:25:19 -03:00
|
|
|
|
|
|
|
// get current altitude in meters relative to altitude at the time
|
|
|
|
// of the last calibrate() call
|
2012-08-17 03:09:24 -03:00
|
|
|
float get_altitude(void);
|
2012-06-19 23:25:19 -03:00
|
|
|
|
2012-07-05 03:26:56 -03:00
|
|
|
// return how many pressure samples were used to obtain
|
|
|
|
// the last pressure reading
|
2012-08-17 03:09:24 -03:00
|
|
|
uint8_t get_pressure_samples(void) {
|
|
|
|
return _pressure_samples;
|
|
|
|
}
|
2012-07-05 03:26:56 -03:00
|
|
|
|
2012-06-19 23:25:19 -03:00
|
|
|
// get current climb rate in meters/s. A positive number means
|
|
|
|
// going up
|
2012-08-17 03:09:24 -03:00
|
|
|
float get_climb_rate(void);
|
2012-06-19 23:25:19 -03:00
|
|
|
|
|
|
|
// the ground values are only valid after calibration
|
2012-08-17 03:09:24 -03:00
|
|
|
float get_ground_temperature(void) {
|
|
|
|
return _ground_temperature.get();
|
|
|
|
}
|
|
|
|
float get_ground_pressure(void) {
|
|
|
|
return _ground_pressure.get();
|
|
|
|
}
|
2012-06-19 23:25:19 -03:00
|
|
|
|
2012-11-07 05:58:36 -04:00
|
|
|
// get last time sample was taken
|
|
|
|
uint32_t get_last_update() { return _last_update; };
|
|
|
|
|
2012-08-17 03:09:24 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-06-27 02:59:52 -03:00
|
|
|
|
2012-06-19 23:25:19 -03:00
|
|
|
protected:
|
2012-08-17 03:09:24 -03:00
|
|
|
uint32_t _last_update;
|
|
|
|
uint8_t _pressure_samples;
|
2012-06-19 23:25:19 -03:00
|
|
|
|
|
|
|
private:
|
2012-08-17 03:09:24 -03:00
|
|
|
AP_Float _ground_temperature;
|
|
|
|
AP_Float _ground_pressure;
|
|
|
|
float _altitude;
|
|
|
|
uint32_t _last_altitude_t;
|
|
|
|
DerivativeFilterFloat_Size7 _climb_rate_filter;
|
2011-11-05 22:11:25 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#include "AP_Baro_MS5611.h"
|
2011-11-27 01:34:51 -04:00
|
|
|
#include "AP_Baro_BMP085.h"
|
|
|
|
#include "AP_Baro_BMP085_hil.h"
|
2011-11-05 22:11:25 -03:00
|
|
|
|
|
|
|
#endif // __AP_BARO_H__
|