From 0d9b9433dab9aa39525862b1abda9af6dc58d772 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Fri, 15 Apr 2016 16:32:25 -0300 Subject: [PATCH] GCS_MAVLink: fix home position unit As per documentation the home position is in mm. Since location stores it in cm, convert to mm before sending. --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index c1ea8174a5..c387547fbb 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1419,7 +1419,7 @@ void GCS_MAVLINK::send_home(const Location &home) const chan, home.lat, home.lng, - home.alt / 100, + home.alt * 10, 0.0f, 0.0f, 0.0f, q, 0.0f, 0.0f, 0.0f); @@ -1437,7 +1437,7 @@ void GCS_MAVLINK::send_home_all(const Location &home) chan, home.lat, home.lng, - home.alt / 100, + home.alt * 10, 0.0f, 0.0f, 0.0f, q, 0.0f, 0.0f, 0.0f);