diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index a4203dafa3045..08cf70f91abf6 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -997,14 +997,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg) break; } -#if AC_FENCE == ENABLED - // send or receive fence points with GCS - case MAVLINK_MSG_ID_FENCE_POINT: // MAV ID: 160 - case MAVLINK_MSG_ID_FENCE_FETCH_POINT: - sub.fence.handle_msg(*this, msg); - break; -#endif // AC_FENCE == ENABLED - case MAVLINK_MSG_ID_TERRAIN_DATA: case MAVLINK_MSG_ID_TERRAIN_CHECK: #if AP_TERRAIN_AVAILABLE && AC_TERRAIN