mirror of https://github.com/ArduPilot/ardupilot
Plane: accept MAV_CMD_DO_LAND_START as both command_long and COMMAND_INT
This commit is contained in:
parent
1f8df2204f
commit
e965b987f6
|
@ -1000,6 +1000,14 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||
case MAV_CMD_DO_GO_AROUND:
|
||||
return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
|
||||
|
||||
case MAV_CMD_DO_LAND_START:
|
||||
// attempt to switch to next DO_LAND_START command in the mission
|
||||
if (plane.mission.jump_to_landing_sequence()) {
|
||||
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
||||
}
|
||||
|
@ -1051,14 +1059,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
|||
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
case MAV_CMD_DO_LAND_START:
|
||||
// attempt to switch to next DO_LAND_START command in the mission
|
||||
if (plane.mission.jump_to_landing_sequence()) {
|
||||
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue