mirror of https://github.com/ArduPilot/ardupilot
barometer: fixed HIL barometer build
This commit is contained in:
parent
65ed8cc2c3
commit
de5c1c5147
|
@ -14,7 +14,7 @@ AP_Baro_BMP085_HIL::AP_Baro_BMP085_HIL()
|
|||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
|
@ -22,7 +22,7 @@ void AP_Baro_BMP085_HIL::Init(int initialiseWireLib, bool apm2_hardware)
|
|||
|
||||
// Read the sensor. This is a state machine
|
||||
// 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;
|
||||
|
||||
|
@ -47,3 +47,23 @@ void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press)
|
|||
Temp = _Temp;
|
||||
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;
|
||||
}
|
||||
|
|
|
@ -8,18 +8,22 @@ class AP_Baro_BMP085_HIL
|
|||
{
|
||||
private:
|
||||
uint8_t BMP085_State;
|
||||
int16_t Temp;
|
||||
int32_t Press;
|
||||
|
||||
public:
|
||||
AP_Baro_BMP085_HIL(); // Constructor
|
||||
int32_t RawPress;
|
||||
int32_t RawTemp;
|
||||
int16_t Temp;
|
||||
int32_t Press;
|
||||
//int Altitude;
|
||||
uint8_t oss;
|
||||
void Init(int initialiseWireLib = 1, bool apm2_hardware=false);
|
||||
uint8_t Read();
|
||||
void setHIL(float Temp, float Press);
|
||||
int32_t _offset_press;
|
||||
void 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();
|
||||
void setHIL(float Temp, float Press);
|
||||
int32_t _offset_press;
|
||||
};
|
||||
|
||||
#endif // __AP_BARO_BMP085_HIL_H__
|
||||
|
|
Loading…
Reference in New Issue