From 372837b959db8a2a59a2a92dfbef73d3afd6aedd Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 20 Dec 2016 15:57:52 +0100 Subject: [PATCH] Update AP_ADSB.cpp AP_ADSB: fixed GPS.alt reporting cm to mm conversion bug Issue 5424 --- libraries/AP_ADSB/AP_ADSB.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 4bf9bf4cbc..c36c9ffc57 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -469,7 +469,7 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan) int32_t latitude = _my_loc.lat; int32_t longitude = _my_loc.lng; - int32_t altGNSS = _my_loc.alt*0.1f; // convert cm to mm + int32_t altGNSS = _my_loc.alt * 10; // convert cm to mm int16_t velVert = gps_velocity.z * 1E2; // convert m/s to cm/s int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s