Browse Source

barometer: fixed HIL barometer build

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
3648c81dd9
  1. 24
      libraries/AP_Baro/AP_Baro_BMP085_hil.cpp
  2. 20
      libraries/AP_Baro/AP_Baro_BMP085_hil.h

24
libraries/AP_Baro/AP_Baro_BMP085_hil.cpp

@ -14,7 +14,7 @@ AP_Baro_BMP085_HIL::AP_Baro_BMP085_HIL()
} }
// Public Methods ////////////////////////////////////////////////////////////// // Public Methods //////////////////////////////////////////////////////////////
void AP_Baro_BMP085_HIL::Init(int initialiseWireLib, bool apm2_hardware) void AP_Baro_BMP085_HIL::init(AP_PeriodicProcess * scheduler)
{ {
BMP085_State=1; BMP085_State=1;
} }
@ -22,7 +22,7 @@ void AP_Baro_BMP085_HIL::Init(int initialiseWireLib, bool apm2_hardware)
// Read the sensor. This is a state machine // Read the sensor. This is a state machine
// We read one time Temperature (state = 1) and then 4 times Pressure (states 2-5) // We read one time Temperature (state = 1) and then 4 times Pressure (states 2-5)
uint8_t AP_Baro_BMP085_HIL::Read() uint8_t AP_Baro_BMP085_HIL::read()
{ {
uint8_t result = 0; uint8_t result = 0;
@ -47,3 +47,23 @@ void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press)
Temp = _Temp; Temp = _Temp;
Press = _Press; Press = _Press;
} }
int32_t AP_Baro_BMP085_HIL::get_pressure() {
return Press;
}
int16_t AP_Baro_BMP085_HIL::get_temperature() {
return Temp;
}
float AP_Baro_BMP085_HIL::get_altitude() {
return 0.0; // TODO
}
int32_t AP_Baro_BMP085_HIL::get_raw_pressure() {
return Press;
}
int32_t AP_Baro_BMP085_HIL::get_raw_temp() {
return Temp;
}

20
libraries/AP_Baro/AP_Baro_BMP085_hil.h

@ -8,18 +8,22 @@ class AP_Baro_BMP085_HIL
{ {
private: private:
uint8_t BMP085_State; uint8_t BMP085_State;
int16_t Temp;
int32_t Press;
public: public:
AP_Baro_BMP085_HIL(); // Constructor AP_Baro_BMP085_HIL(); // Constructor
int32_t RawPress;
int32_t RawTemp;
int16_t Temp;
int32_t Press;
//int Altitude; //int Altitude;
uint8_t oss; uint8_t oss;
void Init(int initialiseWireLib = 1, bool apm2_hardware=false); void init(AP_PeriodicProcess * scheduler);
uint8_t Read(); uint8_t read();
void setHIL(float Temp, float Press); int32_t get_pressure();
int32_t _offset_press; int16_t get_temperature();
float get_altitude();
int32_t get_raw_pressure();
int32_t get_raw_temp();
void setHIL(float Temp, float Press);
int32_t _offset_press;
}; };
#endif // __AP_BARO_BMP085_HIL_H__ #endif // __AP_BARO_BMP085_HIL_H__

Loading…
Cancel
Save