From 3c7e521f70aff528531f15a5a1d245b92c708937 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 6 Jul 2012 13:11:33 +1000 Subject: [PATCH] AP_Baro: update MS5611 test to use baro library altitude --- .../AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde index 43314adc4f..3f74bbe4bc 100644 --- a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde +++ b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde @@ -40,9 +40,6 @@ void setup() void loop() { - float tmp_float; - float Altitude; - if((micros() - timer) > 100000UL){ timer = micros(); baro.read(); @@ -56,13 +53,11 @@ void loop() Serial.print(" Temperature:"); Serial.print(baro.get_temperature()); Serial.print(" Altitude:"); - tmp_float = (baro.get_pressure() / 101325.0); - tmp_float = pow(tmp_float, 0.190295); - Altitude = 44330.0 * (1.0 - tmp_float); - Serial.print(Altitude); - Serial.printf(" climb=%.2f t=%u", + Serial.print(baro.get_altitude()); + Serial.printf(" climb=%.2f t=%u samples=%u", baro.get_climb_rate(), - (unsigned)read_time); + (unsigned)read_time, + (unsigned)baro.get_pressure_samples()); Serial.println(); } }