From 3938fb7255002807d767ff35270a97525f227be0 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 18 Mar 2014 16:32:55 +0900 Subject: [PATCH] GCS_MAVLink: loiter direction removed This is now handled in Mission library --- libraries/GCS_MAVLink/GCS_Common.cpp | 19 ------------------- 1 file changed, 19 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index f3dfe2c3fc..08026acfa7 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -215,25 +215,6 @@ void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t // set auto continue to 1 ret_packet.autocontinue = 1; // 1 (true), 0 (false) - // plane specific overrides to packet values - switch (cmd.id) { - case MAV_CMD_NAV_LOITER_TIME: - case MAV_CMD_NAV_LOITER_TURNS: - if (cmd.content.location.flags.loiter_ccw) { - ret_packet.param3 = -1; - } else { - ret_packet.param3 = 1; - } - break; - case MAV_CMD_NAV_LOITER_UNLIM: - if (cmd.content.location.flags.loiter_ccw) { - ret_packet.param3 = -1; - } else { - ret_packet.param3 = 1; - } - break; - } - /* avoid the _send() function to save memory on APM2, as it avoids the stack usage of the _send() function by using the already