ardupilot/libraries/AP_Baro/AP_Baro_BMP085_hil.h
Andrew Tridgell 44755bf3ce AP_Baro: improved barometer averaging
this changes the barometer calculations to floating point. On a MS5611
this is actually about twice as fast as the previous 64 bit
calculations, but gains us more accuracy as we are able to take
advantage of sub-bit precision when we average over 8 samples.
2012-07-06 15:11:30 +10:00

31 lines
649 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;
float Temp;
float Press;
int32_t _pressure_sum;
int32_t _temperature_sum;
uint8_t _count;
public:
AP_Baro_BMP085_HIL(); // Constructor
bool init(AP_PeriodicProcess * scheduler);
uint8_t read();
float get_pressure();
float get_temperature();
int32_t get_raw_pressure();
int32_t get_raw_temp();
void setHIL(float Temp, float Press);
};
#endif // __AP_BARO_BMP085_HIL_H__