diff --git a/ArduCopterMega/GCS_Mavlink.pde b/ArduCopterMega/GCS_Mavlink.pde index 24e62074de..eb3b6773f8 100644 --- a/ArduCopterMega/GCS_Mavlink.pde +++ b/ArduCopterMega/GCS_Mavlink.pde @@ -400,11 +400,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // command needs scaling x = tell_command.lat/1.0e7; // local (x), global (latitude) y = tell_command.lng/1.0e7; // local (y), global (longitude) - if (tell_command.options & WP_OPTION_ALT_RELATIVE) { - z = (tell_command.alt - home.alt) / 1.0e2; // because tell_command.alt already includes a += home.alt - } else { - z = tell_command.alt/1.0e2; // local (z), global/relative (altitude) - } + // ACM is processing alt inside each command. so we save and load raw values. - this is diffrent to APM + z = tell_command.alt/1.0e2; // local (z), global/relative (altitude) }