mirror of https://github.com/ArduPilot/ardupilot
Rover: use generic fence handling in missions
This commit is contained in:
parent
823ffb6c9e
commit
685fb7e34f
|
@ -593,18 +593,6 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
||||||
do_set_reverse(cmd);
|
do_set_reverse(cmd);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_FENCE_ENABLE:
|
|
||||||
#if AP_FENCE_ENABLED
|
|
||||||
if (cmd.p1 == 0) { //disable
|
|
||||||
rover.fence.enable_configured(false);
|
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled");
|
|
||||||
} else { //enable fence
|
|
||||||
rover.fence.enable_configured(true);
|
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled");
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAV_CMD_DO_GUIDED_LIMITS:
|
case MAV_CMD_DO_GUIDED_LIMITS:
|
||||||
do_guided_limits(cmd);
|
do_guided_limits(cmd);
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue