mirror of https://github.com/ArduPilot/ardupilot
Adjusted the state machine to read the temperature less often (from twice a second to every 4 seconds). Added a small smoothing filter.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2552 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
c1ddd58d4c
commit
2651cadb84
|
@ -55,12 +55,13 @@ APM_BMP085_Class::APM_BMP085_Class()
|
|||
void APM_BMP085_Class::Init(int initialiseWireLib)
|
||||
{
|
||||
byte buff[22];
|
||||
int i=0;
|
||||
int i = 0;
|
||||
|
||||
pinMode(BMP085_EOC,INPUT); // End Of Conversion (PC7) input
|
||||
pinMode(BMP085_EOC, INPUT); // End Of Conversion (PC7) input
|
||||
|
||||
if( initialiseWireLib != 0 )
|
||||
Wire.begin();
|
||||
|
||||
oss = 3; // Over Sampling setting 3 = High resolution
|
||||
BMP085_State = 0; // Initial state
|
||||
|
||||
|
@ -70,12 +71,13 @@ void APM_BMP085_Class::Init(int initialiseWireLib)
|
|||
Wire.endTransmission();
|
||||
|
||||
Wire.requestFrom(BMP085_ADDRESS, 22);
|
||||
|
||||
//Wire.endTransmission();
|
||||
while(Wire.available())
|
||||
{
|
||||
while(Wire.available()){
|
||||
buff[i] = Wire.receive(); // receive one byte
|
||||
i++;
|
||||
}
|
||||
|
||||
ac1 = ((int)buff[0] << 8) | buff[1];
|
||||
ac2 = ((int)buff[2] << 8) | buff[3];
|
||||
ac3 = ((int)buff[4] << 8) | buff[5];
|
||||
|
@ -90,7 +92,7 @@ void APM_BMP085_Class::Init(int initialiseWireLib)
|
|||
|
||||
//Send a command to read Temp
|
||||
Command_ReadTemp();
|
||||
BMP085_State=1;
|
||||
BMP085_State = 1;
|
||||
}
|
||||
|
||||
|
||||
|
@ -98,39 +100,31 @@ void APM_BMP085_Class::Init(int initialiseWireLib)
|
|||
// 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;
|
||||
uint8_t result = 0;
|
||||
|
||||
if (BMP085_State==1)
|
||||
{
|
||||
if (digitalRead(BMP085_EOC))
|
||||
{
|
||||
if (BMP085_State == 1){
|
||||
if (digitalRead(BMP085_EOC)){
|
||||
ReadTemp(); // On state 1 we read temp
|
||||
BMP085_State++;
|
||||
Command_ReadPress();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (BMP085_State==5)
|
||||
{
|
||||
if (digitalRead(BMP085_EOC))
|
||||
{
|
||||
}else{
|
||||
if (BMP085_State == 40){
|
||||
if (digitalRead(BMP085_EOC)){
|
||||
ReadPress();
|
||||
Calculate();
|
||||
BMP085_State = 1; // Start again from state=1
|
||||
|
||||
BMP085_State = 1; // Start again from state = 1
|
||||
Command_ReadTemp(); // Read Temp
|
||||
result=1; // New pressure reading
|
||||
result = 1; // New pressure reading
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (digitalRead(BMP085_EOC))
|
||||
{
|
||||
}else{
|
||||
if (digitalRead(BMP085_EOC)){
|
||||
ReadPress();
|
||||
Calculate();
|
||||
BMP085_State++;
|
||||
Command_ReadPress();
|
||||
result=1; // New pressure reading
|
||||
result = 1; // New pressure reading
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -143,7 +137,7 @@ void APM_BMP085_Class::Command_ReadPress()
|
|||
{
|
||||
Wire.beginTransmission(BMP085_ADDRESS);
|
||||
Wire.send(0xF4);
|
||||
Wire.send(0x34+(oss<<6)); //write_register(0xF4,0x34+(oversampling_setting<<6));
|
||||
Wire.send(0x34+(oss << 6)); // write_register(0xF4, 0x34+(oversampling_setting << 6));
|
||||
Wire.endTransmission();
|
||||
}
|
||||
|
||||
|
@ -159,19 +153,25 @@ void APM_BMP085_Class::ReadPress()
|
|||
Wire.endTransmission();
|
||||
|
||||
Wire.requestFrom(BMP085_ADDRESS, 3); // read a byte
|
||||
|
||||
while(!Wire.available()) {
|
||||
// waiting
|
||||
}
|
||||
|
||||
msb = Wire.receive();
|
||||
|
||||
while(!Wire.available()) {
|
||||
// waiting
|
||||
}
|
||||
|
||||
lsb = Wire.receive();
|
||||
|
||||
while(!Wire.available()) {
|
||||
// waiting
|
||||
}
|
||||
|
||||
xlsb = Wire.receive();
|
||||
RawPress = (((long)msb<<16) | ((long)lsb<<8) | ((long)xlsb)) >> (8-oss);
|
||||
RawPress = (((long)msb << 16) | ((long)lsb << 8) | ((long)xlsb)) >> (8 - oss);
|
||||
}
|
||||
|
||||
// Send Command to Read Temperature
|
||||
|
@ -187,18 +187,20 @@ void APM_BMP085_Class::Command_ReadTemp()
|
|||
void APM_BMP085_Class::ReadTemp()
|
||||
{
|
||||
byte tmp;
|
||||
int16_t tmp2;
|
||||
|
||||
Wire.beginTransmission(BMP085_ADDRESS);
|
||||
Wire.send(0xF6);
|
||||
Wire.endTransmission();
|
||||
|
||||
Wire.beginTransmission(BMP085_ADDRESS);
|
||||
Wire.requestFrom(BMP085_ADDRESS,2);
|
||||
Wire.requestFrom(BMP085_ADDRESS, 2);
|
||||
while(!Wire.available()); // wait
|
||||
RawTemp = Wire.receive();
|
||||
tmp2 = Wire.receive();
|
||||
while(!Wire.available()); // wait
|
||||
tmp = Wire.receive();
|
||||
RawTemp = RawTemp<<8 | tmp;
|
||||
RawTemp += tmp2 << 8 | tmp;
|
||||
RawTemp = RawTemp >> 1;
|
||||
}
|
||||
|
||||
// Calculate Temperature and Pressure in real units.
|
||||
|
@ -252,26 +254,21 @@ void APM_BMP085_HIL_Class::Init(int initialiseWireLib)
|
|||
|
||||
|
||||
// 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_HIL_Class::Read()
|
||||
{
|
||||
uint8_t result=0;
|
||||
uint8_t result = 0;
|
||||
|
||||
if (BMP085_State==1)
|
||||
{
|
||||
if (BMP085_State == 1){
|
||||
BMP085_State++;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (BMP085_State==5)
|
||||
{
|
||||
BMP085_State = 1; // Start again from state=1
|
||||
result=1; // New pressure reading
|
||||
}
|
||||
else
|
||||
{
|
||||
}else{
|
||||
|
||||
if (BMP085_State == 5){
|
||||
BMP085_State = 1; // Start again from state = 1
|
||||
result = 1; // New pressure reading
|
||||
}else{
|
||||
BMP085_State++;
|
||||
result=1; // New pressure reading
|
||||
result = 1; // New pressure reading
|
||||
}
|
||||
}
|
||||
return(result);
|
||||
|
|
|
@ -15,6 +15,7 @@ class APM_BMP085_Class
|
|||
void ReadPress();
|
||||
void ReadTemp();
|
||||
void Calculate();
|
||||
|
||||
public:
|
||||
int32_t RawPress;
|
||||
int32_t RawTemp;
|
||||
|
|
Loading…
Reference in New Issue