mirror of https://github.com/ArduPilot/ardupilot
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:
parent
b69012803d
commit
9c4517cfd2
|
@ -187,23 +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
|
||||
tmp2 = Wire.receive();
|
||||
RawTemp = Wire.receive();
|
||||
|
||||
while(!Wire.available()); // wait
|
||||
tmp = Wire.receive();
|
||||
tmp2 = tmp2 << 8 | tmp;
|
||||
if(RawTemp = 0)
|
||||
RawTemp = tmp2;
|
||||
RawTemp += tmp2;
|
||||
RawTemp = RawTemp >> 1;
|
||||
|
||||
RawTemp = RawTemp << 8 | tmp;
|
||||
}
|
||||
|
||||
// Calculate Temperature and Pressure in real units.
|
||||
|
|
Loading…
Reference in New Issue