mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: accept MAV_CMD_NAV_RETURN_TO_LAUNCH as both long and int
This commit is contained in:
parent
b93e1d471f
commit
380a1fe738
@ -657,6 +657,12 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
|
|||||||
rover.control_mode->set_reversed(is_equal(packet.param1,1.0f));
|
rover.control_mode->set_reversed(is_equal(packet.param1,1.0f));
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
|
||||||
|
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||||
|
if (rover.set_mode(rover.mode_rtl, ModeReason::GCS_COMMAND)) {
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
}
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
||||||
}
|
}
|
||||||
@ -666,12 +672,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l
|
|||||||
{
|
{
|
||||||
switch (packet.command) {
|
switch (packet.command) {
|
||||||
|
|
||||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
|
||||||
if (rover.set_mode(rover.mode_rtl, ModeReason::GCS_COMMAND)) {
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
}
|
|
||||||
return MAV_RESULT_FAILED;
|
|
||||||
|
|
||||||
case MAV_CMD_MISSION_START:
|
case MAV_CMD_MISSION_START:
|
||||||
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
|
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
Loading…
Reference in New Issue
Block a user