update to Baro lib to remove temp filtering.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2569 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-06-18 05:08:48 +00:00
parent b69012803d
commit 9c4517cfd2
1 changed files with 41 additions and 44 deletions

View File

@ -177,71 +177,68 @@ void APM_BMP085_Class::ReadPress()
// Send Command to Read Temperature // Send Command to Read Temperature
void APM_BMP085_Class::Command_ReadTemp() void APM_BMP085_Class::Command_ReadTemp()
{ {
Wire.beginTransmission(BMP085_ADDRESS); Wire.beginTransmission(BMP085_ADDRESS);
Wire.send(0xF4); Wire.send(0xF4);
Wire.send(0x2E); Wire.send(0x2E);
Wire.endTransmission(); Wire.endTransmission();
} }
// Read Raw Temperature values // Read Raw Temperature values
void APM_BMP085_Class::ReadTemp() void APM_BMP085_Class::ReadTemp()
{ {
byte tmp; byte tmp;
int16_t tmp2;
Wire.beginTransmission(BMP085_ADDRESS); Wire.beginTransmission(BMP085_ADDRESS);
Wire.send(0xF6); Wire.send(0xF6);
Wire.endTransmission(); Wire.endTransmission();
Wire.beginTransmission(BMP085_ADDRESS); Wire.beginTransmission(BMP085_ADDRESS);
Wire.requestFrom(BMP085_ADDRESS, 2); Wire.requestFrom(BMP085_ADDRESS,2);
while(!Wire.available()); // wait while(!Wire.available()); // wait
tmp2 = Wire.receive(); RawTemp = Wire.receive();
while(!Wire.available()); // wait while(!Wire.available()); // wait
tmp = Wire.receive(); tmp = Wire.receive();
tmp2 = tmp2 << 8 | tmp;
if(RawTemp = 0) RawTemp = RawTemp << 8 | tmp;
RawTemp = tmp2;
RawTemp += tmp2;
RawTemp = RawTemp >> 1;
} }
// Calculate Temperature and Pressure in real units. // Calculate Temperature and Pressure in real units.
void APM_BMP085_Class::Calculate() void APM_BMP085_Class::Calculate()
{ {
long x1, x2, x3, b3, b5, b6, p; long x1, x2, x3, b3, b5, b6, p;
unsigned long b4, b7; unsigned long b4, b7;
int32_t tmp; int32_t tmp;
// See Datasheet page 13 for this formulas // See Datasheet page 13 for this formulas
// Based also on Jee Labs BMP085 example code. Thanks for share. // Based also on Jee Labs BMP085 example code. Thanks for share.
// Temperature calculations // Temperature calculations
x1 = ((long)RawTemp - ac6) * ac5 >> 15; x1 = ((long)RawTemp - ac6) * ac5 >> 15;
x2 = ((long) mc << 11) / (x1 + md); x2 = ((long) mc << 11) / (x1 + md);
b5 = x1 + x2; b5 = x1 + x2;
Temp = (b5 + 8) >> 4; Temp = (b5 + 8) >> 4;
// Pressure calculations // Pressure calculations
b6 = b5 - 4000; b6 = b5 - 4000;
x1 = (b2 * (b6 * b6 >> 12)) >> 11; x1 = (b2 * (b6 * b6 >> 12)) >> 11;
x2 = ac2 * b6 >> 11; x2 = ac2 * b6 >> 11;
x3 = x1 + x2; x3 = x1 + x2;
//b3 = (((int32_t) ac1 * 4 + x3)<<oss + 2) >> 2; // BAD //b3 = (((int32_t) ac1 * 4 + x3)<<oss + 2) >> 2; // BAD
//b3 = ((int32_t) ac1 * 4 + x3 + 2) >> 2; //OK for oss=0 //b3 = ((int32_t) ac1 * 4 + x3 + 2) >> 2; //OK for oss=0
tmp = ac1; tmp = ac1;
tmp = (tmp*4 + x3)<<oss; tmp = (tmp*4 + x3)<<oss;
b3 = (tmp+2)/4; b3 = (tmp+2)/4;
x1 = ac3 * b6 >> 13; x1 = ac3 * b6 >> 13;
x2 = (b1 * (b6 * b6 >> 12)) >> 16; x2 = (b1 * (b6 * b6 >> 12)) >> 16;
x3 = ((x1 + x2) + 2) >> 2; x3 = ((x1 + x2) + 2) >> 2;
b4 = (ac4 * (uint32_t) (x3 + 32768)) >> 15; b4 = (ac4 * (uint32_t) (x3 + 32768)) >> 15;
b7 = ((uint32_t) RawPress - b3) * (50000 >> oss); b7 = ((uint32_t) RawPress - b3) * (50000 >> oss);
p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2; p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2;
x1 = (p >> 8) * (p >> 8); x1 = (p >> 8) * (p >> 8);
x1 = (x1 * 3038) >> 16; x1 = (x1 * 3038) >> 16;
x2 = (-7357 * p) >> 16; x2 = (-7357 * p) >> 16;
Press = p + ((x1 + x2 + 3791) >> 4); Press = p + ((x1 + x2 + 3791) >> 4);
} }
// Constructors //////////////////////////////////////////////////////////////// // Constructors ////////////////////////////////////////////////////////////////