From 7815e3d8101fc60567ab6f485b511820bc30250e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 8 Aug 2012 11:14:01 +1000 Subject: [PATCH] APM: fixed rounding of altitude the cast was rounding to the nearest meter --- ArduPlane/sensors.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde index 1b128d2d2c..5554d30c7e 100644 --- a/ArduPlane/sensors.pde +++ b/ArduPlane/sensors.pde @@ -21,7 +21,7 @@ static LowPassFilterInt32 altitude_filter(0.3); static int32_t read_barometer(void) { barometer.read(); - return altitude_filter.apply(((int32_t)barometer.get_altitude() * 100.0)); + return altitude_filter.apply(barometer.get_altitude() * 100.0); } // in M/S * 100