Rover: allow MAV_CMD_MISSION_START as both command_long and command_int

This commit is contained in:
Peter Barker 2023-08-24 22:31:48 +10:00 committed by Peter Barker
parent 1228f4c458
commit d44b51fa4d
1 changed files with 6 additions and 6 deletions

View File

@ -674,6 +674,12 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
static_cast<int16_t>(packet.param3),
packet.param4);
case MAV_CMD_MISSION_START:
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
default:
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
}
@ -683,12 +689,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l
{
switch (packet.command) {
case MAV_CMD_MISSION_START:
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
case MAV_CMD_NAV_SET_YAW_SPEED:
{
// param1 : yaw angle to adjust direction by in centidegress