mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
updated formatting, baud
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1643 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
6512531bf9
commit
1f56ef5f21
@ -1,43 +1,42 @@
|
|||||||
/*
|
/*
|
||||||
Example of APM_BMP085 (absolute pressure sensor) library.
|
Example of APM_BMP085 (absolute pressure sensor) library.
|
||||||
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
|
Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <APM_BMP085.h> // ArduPilot Mega BMP085 Library
|
#include <APM_BMP085.h> // ArduPilot Mega BMP085 Library
|
||||||
|
|
||||||
APM_BMP085_Class APM_BMP085;
|
APM_BMP085_Class APM_BMP085;
|
||||||
|
|
||||||
unsigned long timer;
|
unsigned long timer;
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
APM_BMP085.Init(); // APM ADC initialization
|
APM_BMP085.Init(); // APM ADC initialization
|
||||||
Serial.begin(57600);
|
Serial.begin(38400);
|
||||||
Serial.println("ArduPilot Mega BMP085 library test");
|
Serial.println("ArduPilot Mega BMP085 library test");
|
||||||
delay(1000);
|
delay(1000);
|
||||||
timer = millis();
|
timer = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
int ch;
|
int ch;
|
||||||
float tmp_float;
|
float tmp_float;
|
||||||
float Altitude;
|
float Altitude;
|
||||||
|
|
||||||
if((millis()- timer) > 50)
|
if((millis()- timer) > 50){
|
||||||
{
|
timer = millis();
|
||||||
timer=millis();
|
APM_BMP085.Read();
|
||||||
APM_BMP085.Read();
|
Serial.print("Pressure:");
|
||||||
Serial.print("Pressure:");
|
Serial.print(APM_BMP085.Press);
|
||||||
Serial.print(APM_BMP085.Press);
|
Serial.print(" Temperature:");
|
||||||
Serial.print(" Temperature:");
|
Serial.print(APM_BMP085.Temp / 10.0);
|
||||||
Serial.print(APM_BMP085.Temp/10.0);
|
Serial.print(" Altitude:");
|
||||||
Serial.print(" Altitude:");
|
tmp_float = (APM_BMP085.Press / 101325.0);
|
||||||
tmp_float = (APM_BMP085.Press/101325.0);
|
tmp_float = pow(tmp_float, 0.190295);
|
||||||
tmp_float = pow(tmp_float,0.190295);
|
Altitude = 44330 * (1.0 - tmp_float);
|
||||||
Altitude = 44330*(1.0-tmp_float);
|
Serial.print(Altitude);
|
||||||
Serial.print(Altitude);
|
Serial.println();
|
||||||
Serial.println();
|
}
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
Loading…
Reference in New Issue
Block a user