Rover: move handling of MAV_CMD_DO_SET_FENCE_ENABLED up
This commit is contained in:
parent
8d45a8ff53
commit
ded3ab99bb
@ -666,19 +666,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l
|
|||||||
}
|
}
|
||||||
return MAV_RESULT_UNSUPPORTED;
|
return MAV_RESULT_UNSUPPORTED;
|
||||||
|
|
||||||
case MAV_CMD_DO_FENCE_ENABLE:
|
|
||||||
switch ((uint16_t)packet.param1) {
|
|
||||||
case 0:
|
|
||||||
rover.g2.fence.enable(false);
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
case 1:
|
|
||||||
rover.g2.fence.enable(true);
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
return MAV_RESULT_FAILED;
|
|
||||||
|
|
||||||
case MAV_CMD_DO_CHANGE_SPEED:
|
case MAV_CMD_DO_CHANGE_SPEED:
|
||||||
// param1 : unused
|
// param1 : unused
|
||||||
// param2 : new speed in m/s
|
// param2 : new speed in m/s
|
||||||
|
Loading…
Reference in New Issue
Block a user