Browse Source

Copter: Now recognizes DO_FENCE_ENABLE mission command.

mission-4.1.18
Michael Day 8 years ago committed by Francisco Ferreira
parent
commit
49e3ce8e75
  1. 13
      ArduCopter/commands_logic.cpp

13
ArduCopter/commands_logic.cpp

@ -113,6 +113,18 @@ bool Copter::start_command(const AP_Mission::Mission_Command& cmd) @@ -113,6 +113,18 @@ bool Copter::start_command(const AP_Mission::Mission_Command& cmd)
do_mount_control(cmd);
break;
case MAV_CMD_DO_FENCE_ENABLE:
#if AC_FENCE == ENABLED
if (cmd.p1 == 0) { //disable
copter.fence.enable(false);
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Fence Disabled");
} else { //enable fence
copter.fence.enable(true);
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Fence Enabled");
}
#endif //AC_FENCE == ENABLED
break;
#if CAMERA == ENABLED
case MAV_CMD_DO_CONTROL_VIDEO: // Control on-board camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
break;
@ -256,6 +268,7 @@ bool Copter::verify_command(const AP_Mission::Mission_Command& cmd) @@ -256,6 +268,7 @@ bool Copter::verify_command(const AP_Mission::Mission_Command& cmd)
case MAV_CMD_DO_PARACHUTE: // assume parachute was released successfully
case MAV_CMD_DO_GRIPPER:
case MAV_CMD_DO_GUIDED_LIMITS:
case MAV_CMD_DO_FENCE_ENABLE:
return true;
default:

Loading…
Cancel
Save