From 823ffb6c9e153d29be8e93d7ef34270e53fd3276 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 31 May 2024 15:19:36 +0100 Subject: [PATCH] Copter: use generic fence handling in missions --- ArduCopter/mode_auto.cpp | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index b672ba4d54..4c4ab35ac2 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -782,18 +782,6 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) // point the camera to a specified angle do_mount_control(cmd); break; - - case MAV_CMD_DO_FENCE_ENABLE: -#if AP_FENCE_ENABLED - if (cmd.p1 == 0) { //disable - copter.fence.enable_configured(false); - gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled"); - } else { //enable fence - copter.fence.enable_configured(true); - gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled"); - } -#endif //AP_FENCE_ENABLED - break; #if AC_NAV_GUIDED == ENABLED case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits