ardupilot/libraries/AP_Baro/AP_Baro_BMP085_hil.h
Andrew Tridgell 53e950531e Baro: added get_altitude() and get_climb_rate() interfaces
this allows the barometer driver to calibrate and return altitude and
climb rate values. This will be used by the AHRS drift correction code
for vertical velocity

The climb rate uses a 5 point average filter
2012-06-27 16:01:50 +10:00

29 lines
601 B
C++

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_BARO_BMP085_HIL_H__
#define __AP_BARO_BMP085_HIL_H__
#include "AP_Baro.h"
class AP_Baro_BMP085_HIL : public AP_Baro
{
private:
uint8_t BMP085_State;
int16_t Temp;
int32_t Press;
public:
AP_Baro_BMP085_HIL(); // Constructor
//int Altitude;
bool init(AP_PeriodicProcess * scheduler);
uint8_t read();
int32_t get_pressure();
int16_t get_temperature();
int32_t get_raw_pressure();
int32_t get_raw_temp();
void setHIL(float Temp, float Press);
};
#endif // __AP_BARO_BMP085_HIL_H__