mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
GCS_MAVLink: handle DO_SET_MISSION_CURRENT as both long and int
This commit is contained in:
parent
b572fe80ec
commit
d7160aea2d
@ -638,8 +638,8 @@ protected:
|
||||
virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
||||
virtual MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg);
|
||||
|
||||
virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_jump_tag(const mavlink_command_long_t &packet);
|
||||
virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_do_jump_tag(const mavlink_command_int_t &packet);
|
||||
|
||||
MAV_RESULT handle_command_battery_reset(const mavlink_command_int_t &packet);
|
||||
void handle_command_long(const mavlink_message_t &msg);
|
||||
|
@ -4452,7 +4452,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_i
|
||||
// the current waypoint, rather than this DO command. It is hoped we
|
||||
// can move to this command in the future to avoid acknowledgement
|
||||
// issues with MISSION_SET_CURRENT
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)
|
||||
{
|
||||
AP_Mission *mission = AP::mission();
|
||||
if (mission == nullptr) {
|
||||
@ -4485,7 +4485,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_comm
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_jump_tag(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_jump_tag(const mavlink_command_int_t &packet)
|
||||
{
|
||||
AP_Mission *mission = AP::mission();
|
||||
if (mission == nullptr) {
|
||||
@ -4757,14 +4757,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
||||
|
||||
switch (packet.command) {
|
||||
|
||||
case MAV_CMD_DO_JUMP_TAG:
|
||||
result = handle_command_do_jump_tag(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_MISSION_CURRENT:
|
||||
result = handle_command_do_set_mission_current(packet);
|
||||
break;
|
||||
|
||||
default:
|
||||
result = try_command_long_as_command_int(packet, msg);
|
||||
break;
|
||||
@ -5074,6 +5066,13 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
||||
return handle_command_do_gripper(packet);
|
||||
#endif
|
||||
|
||||
case MAV_CMD_DO_JUMP_TAG:
|
||||
result = handle_command_do_jump_tag(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_MISSION_CURRENT:
|
||||
return handle_command_do_set_mission_current(packet);
|
||||
|
||||
case MAV_CMD_DO_SET_MODE:
|
||||
return handle_command_do_set_mode(packet);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user