AP_Baro_BMP085: increase ratio of pressure reads again to be 5:1 (was 4:1)

This commit is contained in:
Randy Mackay 2013-01-11 14:46:34 +09:00
parent 49a5b664cc
commit dbb4a9fce6
1 changed files with 1 additions and 1 deletions

View File

@ -118,7 +118,7 @@ uint8_t AP_Baro_BMP085::read()
ReadPress();
Calculate();
result = 1;
if( BMP085_State >= 5 ) {
if( BMP085_State >= 6 ) {
BMP085_State = 1; // Start again from state = 1
Command_ReadTemp(); // next iteration we will read temperature
}else{