updated formatting, baud

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1643 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-02-14 00:43:35 +00:00
parent 6512531bf9
commit 1f56ef5f21

View File

@ -1,6 +1,6 @@
/*
Example of APM_BMP085 (absolute pressure sensor) library.
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
Example of APM_BMP085 (absolute pressure sensor) library.
Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
*/
#include <Wire.h>
@ -12,32 +12,31 @@ unsigned long timer;
void setup()
{
APM_BMP085.Init(); // APM ADC initialization
Serial.begin(57600);
Serial.println("ArduPilot Mega BMP085 library test");
delay(1000);
timer = millis();
APM_BMP085.Init(); // APM ADC initialization
Serial.begin(38400);
Serial.println("ArduPilot Mega BMP085 library test");
delay(1000);
timer = millis();
}
void loop()
{
int ch;
float tmp_float;
float Altitude;
int ch;
float tmp_float;
float Altitude;
if((millis()- timer) > 50)
{
timer=millis();
APM_BMP085.Read();
Serial.print("Pressure:");
Serial.print(APM_BMP085.Press);
Serial.print(" Temperature:");
Serial.print(APM_BMP085.Temp/10.0);
Serial.print(" Altitude:");
tmp_float = (APM_BMP085.Press/101325.0);
tmp_float = pow(tmp_float,0.190295);
Altitude = 44330*(1.0-tmp_float);
Serial.print(Altitude);
Serial.println();
}
if((millis()- timer) > 50){
timer = millis();
APM_BMP085.Read();
Serial.print("Pressure:");
Serial.print(APM_BMP085.Press);
Serial.print(" Temperature:");
Serial.print(APM_BMP085.Temp / 10.0);
Serial.print(" Altitude:");
tmp_float = (APM_BMP085.Press / 101325.0);
tmp_float = pow(tmp_float, 0.190295);
Altitude = 44330 * (1.0 - tmp_float);
Serial.print(Altitude);
Serial.println();
}
}