uncrustify libraries/AP_Baro/AP_Baro_BMP085_hil.cpp
This commit is contained in:
parent
6f02a645c3
commit
b39411e8d4
@ -12,15 +12,15 @@ AP_Baro_BMP085_HIL::AP_Baro_BMP085_HIL()
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
bool AP_Baro_BMP085_HIL::init(AP_PeriodicProcess * scheduler)
|
||||
{
|
||||
BMP085_State=1;
|
||||
return true;
|
||||
BMP085_State=1;
|
||||
return true;
|
||||
}
|
||||
|
||||
// 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 result = 0;
|
||||
uint8_t result = 0;
|
||||
|
||||
if (_count != 0) {
|
||||
result = 1;
|
||||
@ -30,9 +30,9 @@ uint8_t AP_Baro_BMP085_HIL::read()
|
||||
_count = 0;
|
||||
_pressure_sum = 0;
|
||||
_temperature_sum = 0;
|
||||
}
|
||||
}
|
||||
|
||||
return result;
|
||||
return result;
|
||||
}
|
||||
|
||||
void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press)
|
||||
@ -49,7 +49,7 @@ void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press)
|
||||
_temperature_sum /= 2;
|
||||
}
|
||||
|
||||
healthy = true;
|
||||
healthy = true;
|
||||
_last_update = millis();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user