mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Baro: BMP085: rename private member
This commit is contained in:
parent
e40b88aa70
commit
c5c52076ca
@ -78,7 +78,7 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
|||||||
// Send a command to read temperature
|
// Send a command to read temperature
|
||||||
_cmd_read_temp();
|
_cmd_read_temp();
|
||||||
|
|
||||||
BMP085_State = 0;
|
_state = 0;
|
||||||
|
|
||||||
sem->give();
|
sem->give();
|
||||||
}
|
}
|
||||||
@ -99,15 +99,15 @@ void AP_Baro_BMP085::accumulate(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (BMP085_State == 0) {
|
if (_state == 0) {
|
||||||
_read_temp();
|
_read_temp();
|
||||||
} else if (_read_pressure()) {
|
} else if (_read_pressure()) {
|
||||||
_calculate();
|
_calculate();
|
||||||
}
|
}
|
||||||
|
|
||||||
BMP085_State++;
|
_state++;
|
||||||
if (BMP085_State == 5) {
|
if (_state == 5) {
|
||||||
BMP085_State = 0;
|
_state = 0;
|
||||||
_cmd_read_temp();
|
_cmd_read_temp();
|
||||||
} else {
|
} else {
|
||||||
_cmd_read_pressure();
|
_cmd_read_pressure();
|
||||||
@ -237,7 +237,7 @@ bool AP_Baro_BMP085::_data_ready()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// No EOC pin: use time from last read instead.
|
// No EOC pin: use time from last read instead.
|
||||||
if (BMP085_State == 0) {
|
if (_state == 0) {
|
||||||
return AP_HAL::millis() > _last_temp_read_command_time + 5;
|
return AP_HAL::millis() > _last_temp_read_command_time + 5;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -37,7 +37,7 @@ private:
|
|||||||
uint32_t _last_temp_read_command_time;
|
uint32_t _last_temp_read_command_time;
|
||||||
|
|
||||||
// State machine
|
// State machine
|
||||||
uint8_t BMP085_State;
|
uint8_t _state;
|
||||||
|
|
||||||
// Internal calibration registers
|
// Internal calibration registers
|
||||||
int16_t ac1, ac2, ac3, b1, b2, mb, mc, md;
|
int16_t ac1, ac2, ac3, b1, b2, mb, mc, md;
|
||||||
|
Loading…
Reference in New Issue
Block a user