diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index d1bd9138ff..4efa7821cc 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -780,20 +780,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ } return MAV_RESULT_FAILED; -#if AC_FENCE == ENABLED - case MAV_CMD_DO_FENCE_ENABLE: - switch ((uint16_t)packet.param1) { - case 0: - copter.fence.enable(false); - return MAV_RESULT_ACCEPTED; - case 1: - copter.fence.enable(true); - return MAV_RESULT_ACCEPTED; - default: - return MAV_RESULT_FAILED; - } -#endif - #if PARACHUTE == ENABLED case MAV_CMD_DO_PARACHUTE: // configure or release parachute