mirror of https://github.com/ArduPilot/ardupilot
Copter: use generic fence handling in missions
This commit is contained in:
parent
a11cc6ea66
commit
823ffb6c9e
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue