diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index a0e6dc3748..388b5bed0f 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1359,6 +1359,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) plane.auto_state.takeoff_altitude_rel_cm = packet.param1 * 100; } if (plane.landing.request_go_around()) { + plane.auto_state.next_wp_no_crosstrack = true; result = MAV_RESULT_ACCEPTED; } }