ardupilot/libraries/AP_Baro/AP_Baro_BMP085.h

53 lines
1.1 KiB
C
Raw Normal View History

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_BARO_BMP085_H__
#define __AP_BARO_BMP085_H__
2011-11-27 00:42:52 -04:00
#define PRESS_FILTER_SIZE 2
2011-11-27 00:42:52 -04:00
#include "AP_Baro.h"
#include <AverageFilter.h>
2011-11-27 00:42:52 -04:00
class AP_Baro_BMP085 : public AP_Baro
2011-11-27 00:42:52 -04:00
{
public:
AP_Baro_BMP085(bool apm2_hardware):
_apm2_hardware(apm2_hardware) {}; // Constructor
/* AP_Baro public interface: */
bool init(AP_PeriodicProcess * scheduler);
uint8_t read();
int32_t get_pressure();
int16_t get_temperature();
float get_altitude();
int32_t get_raw_pressure();
int32_t get_raw_temp();
private:
2011-11-27 00:42:52 -04:00
int32_t RawPress;
int32_t RawTemp;
int16_t Temp;
uint32_t Press;
2011-11-25 19:11:14 -04:00
bool _apm2_hardware;
2011-11-27 00:42:52 -04:00
// State machine
uint8_t BMP085_State;
// Internal calibration registers
int16_t ac1, ac2, ac3, b1, b2, mb, mc, md;
uint16_t ac4, ac5, ac6;
AverageFilterInt32_Size4 _temp_filter;
2011-11-27 00:42:52 -04:00
uint32_t _retry_time;
2011-11-27 00:42:52 -04:00
void Command_ReadPress();
void Command_ReadTemp();
void ReadPress();
void ReadTemp();
void Calculate();
};
#endif // __AP_BARO_BMP085_H__