diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index e08c6fd5b3..575721fbc5 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1976,7 +1976,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) Location new_home_loc; new_home_loc.lat = packet.latitude; new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude * 100; + new_home_loc.alt = packet.altitude / 10; if (copter.far_from_EKF_origin(new_home_loc)) { break; }