corrected altitude scaling

git-svn-id: https://arducopter.googlecode.com/svn/trunk@229 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
deweibel 2010-08-18 18:28:30 +00:00
parent f0776a962d
commit c58d9577ae
1 changed files with 2 additions and 1 deletions

View File

@ -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;