diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 5160cbc2e2..46d0758cff 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -121,7 +121,7 @@ void Rover::send_location(mavlink_channel_t chan) current_loc.lat, // in 1E7 degrees current_loc.lng, // in 1E7 degrees current_loc.alt * 10UL, // millimeters above sea level - (current_loc.alt - home.alt) * 10, // millimeters above ground + (current_loc.alt - home.alt) * 10, // millimeters above home vel.x * 100, // X speed cm/s (+ve North) vel.y * 100, // Y speed cm/s (+ve East) vel.z * -100, // Z speed cm/s (+ve up)