Minimized the baro filtering to use a new approach to rate control. Redid the state machine so the temp is sampled more often.
This commit is contained in:
Jason Short 2011-11-01 09:22:21 -07:00
parent 67e98ae867
commit 9c4ad5f7ff
2 changed files with 28 additions and 4 deletions

View File

@ -95,7 +95,7 @@ void APM_BMP085_Class::Init(int initialiseWireLib)
BMP085_State = 1; BMP085_State = 1;
} }
/*
// Read the sensor. This is a state machine // Read the sensor. This is a state machine
// We read one time Temperature (state=1) and then 4 times Pressure (states 2-5) // We read one time Temperature (state=1) and then 4 times Pressure (states 2-5)
uint8_t APM_BMP085_Class::Read() uint8_t APM_BMP085_Class::Read()
@ -130,6 +130,30 @@ uint8_t APM_BMP085_Class::Read()
} }
return(result); return(result);
} }
*/
// 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 APM_BMP085_Class::Read()
{
uint8_t result = 0;
if (BMP085_State == 1){
if (digitalRead(BMP085_EOC)){
BMP085_State = 2;
ReadTemp(); // On state 1 we read temp
Command_ReadPress();
}
}else{
if (digitalRead(BMP085_EOC)){
BMP085_State = 1; // Start again from state = 1
ReadPress();
Calculate();
Command_ReadTemp(); // Read Temp
result = 1; // New pressure reading
}
}
return(result);
}
// Send command to Read Pressure // Send command to Read Pressure

View File

@ -1,8 +1,8 @@
#ifndef APM_BMP085_h #ifndef APM_BMP085_h
#define APM_BMP085_h #define APM_BMP085_h
#define TEMP_FILTER_SIZE 16 #define TEMP_FILTER_SIZE 2
#define PRESS_FILTER_SIZE 10 #define PRESS_FILTER_SIZE 2
#include "APM_BMP085_hil.h" #include "APM_BMP085_hil.h"
@ -13,6 +13,7 @@ class APM_BMP085_Class
_temp_index(0), _temp_index(0),
_press_index(0){}; // Constructor _press_index(0){}; // Constructor
int32_t RawPress; int32_t RawPress;
int32_t _offset_press;
int32_t RawTemp; int32_t RawTemp;
int16_t Temp; int16_t Temp;
int32_t Press; int32_t Press;
@ -32,7 +33,6 @@ class APM_BMP085_Class
int _temp_filter[TEMP_FILTER_SIZE]; int _temp_filter[TEMP_FILTER_SIZE];
int _press_filter[PRESS_FILTER_SIZE]; int _press_filter[PRESS_FILTER_SIZE];
long _offset_press;
long _offset_temp; long _offset_temp;
uint8_t _temp_index; uint8_t _temp_index;