Copter: move handling of MAV_CMD_DO_SET_FENCE_ENABLED up

This has the effect of losing the statustext messages.  We should not be
sending statustext messages for things that complete successfully, and
this data is available in the fence_status mavlink message (and in
SYS_STATUS too)
This commit is contained in:
Peter Barker 2019-02-04 11:07:56 +11:00 committed by Randy Mackay
parent ded3ab99bb
commit 727d42be1c
1 changed files with 0 additions and 14 deletions

View File

@ -780,20 +780,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
}
return MAV_RESULT_FAILED;
#if AC_FENCE == ENABLED
case MAV_CMD_DO_FENCE_ENABLE:
switch ((uint16_t)packet.param1) {
case 0:
copter.fence.enable(false);
return MAV_RESULT_ACCEPTED;
case 1:
copter.fence.enable(true);
return MAV_RESULT_ACCEPTED;
default:
return MAV_RESULT_FAILED;
}
#endif
#if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE:
// configure or release parachute