Copter: use generic fence handling in missions

This commit is contained in:
Andy Piper 2024-05-31 15:19:36 +01:00 committed by Peter Barker
parent a11cc6ea66
commit 823ffb6c9e
1 changed files with 0 additions and 12 deletions

View File

@ -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