@ -735,7 +735,7 @@ bool GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &missio
msg->compid,
MAV_MISSION_ACCEPTED);
send_text(MAV_SEVERITY_WARNING,"flight plan received");
send_text(MAV_SEVERITY_INFO,"flight plan received");
waypoint_receiving = false;
mission_is_complete = true;
// XXX ignores waypoint radius for individual waypoints, can