Copter: acccept DO_LAND_START as both int and long

This commit is contained in:
Peter Barker 2023-09-29 09:55:49 +10:00 committed by Peter Barker
parent 3a465829b3
commit ef1952e1c0

View File

@ -814,6 +814,14 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
}
return MAV_RESULT_ACCEPTED;
#if MODE_AUTO_ENABLED == ENABLED
case MAV_CMD_DO_LAND_START:
if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
#endif
default:
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
}
@ -857,14 +865,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
return MAV_RESULT_ACCEPTED;
}
#if MODE_AUTO_ENABLED == ENABLED
case MAV_CMD_DO_LAND_START:
if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
#endif
default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}