mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Baro_BMP085: increase ratio of pressure reads to temperature reads to be 5:1 which is same as APM2's baro
previously the ratio was 1:1
This commit is contained in:
parent
b58a89e71e
commit
4a5908c2ad
@ -115,11 +115,16 @@ uint8_t AP_Baro_BMP085::read()
|
||||
}
|
||||
}else{
|
||||
if (BMP_DATA_READY()) {
|
||||
BMP085_State = 1; // Start again from state = 1
|
||||
ReadPress();
|
||||
Calculate();
|
||||
Command_ReadTemp(); // Read Temp
|
||||
result = 1; // New pressure reading
|
||||
result = 1;
|
||||
if( BMP085_State >= 5 ) {
|
||||
BMP085_State = 1; // Start again from state = 1
|
||||
Command_ReadTemp(); // next iteration we will read temperature
|
||||
}else{
|
||||
BMP085_State++;
|
||||
Command_ReadPress(); // next iteration we will read pressure
|
||||
}
|
||||
}
|
||||
}
|
||||
if (result) {
|
||||
|
Loading…
Reference in New Issue
Block a user