From c58d9577ae74a7f3ad743a932f7daf6f5c000157 Mon Sep 17 00:00:00 2001 From: deweibel Date: Wed, 18 Aug 2010 18:28:30 +0000 Subject: [PATCH] corrected altitude scaling git-svn-id: https://arducopter.googlecode.com/svn/trunk@229 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/GPS_UBLOX/GPS_UBLOX.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/GPS_UBLOX/GPS_UBLOX.cpp b/libraries/GPS_UBLOX/GPS_UBLOX.cpp index 12e5204a94..c255b13b05 100644 --- a/libraries/GPS_UBLOX/GPS_UBLOX.cpp +++ b/libraries/GPS_UBLOX/GPS_UBLOX.cpp @@ -192,7 +192,8 @@ void GPS_UBLOX_Class::parse_ubx_gps(void) j+=4; //Altitude = join_4_bytes(&UBX_buffer[j]); // elipsoid heigth mm j+=4; - Altitude = (float)join_4_bytes(&UBX_buffer[j]); // MSL heigth mm + Altitude = (float)join_4_bytes(&UBX_buffer[j]); // MSL heigth mm + Altitude /= 10.; // Rescale altitude to cm //j+=4; /* hacc = (float)join_4_bytes(&UBX_buffer[j])/(float)1000;