mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: handle DO_SET_MISSION_CURRENT as both long and int
This commit is contained in:
parent
d7160aea2d
commit
e0eacdc197
|
@ -1383,7 +1383,7 @@ void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg)
|
|||
} // end switch
|
||||
} // end handle mavlink
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)
|
||||
{
|
||||
const MAV_RESULT result = GCS_MAVLINK::handle_command_do_set_mission_current(packet);
|
||||
if (result != MAV_RESULT_ACCEPTED) {
|
||||
|
|
|
@ -26,7 +26,7 @@ protected:
|
|||
|
||||
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
|
||||
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
|
||||
MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet) override;
|
||||
MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_int_t &packet) override;
|
||||
|
||||
void send_position_target_global_int() override;
|
||||
|
||||
|
|
|
@ -5067,8 +5067,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
|||
#endif
|
||||
|
||||
case MAV_CMD_DO_JUMP_TAG:
|
||||
result = handle_command_do_jump_tag(packet);
|
||||
break;
|
||||
return handle_command_do_jump_tag(packet);
|
||||
|
||||
case MAV_CMD_DO_SET_MISSION_CURRENT:
|
||||
return handle_command_do_set_mission_current(packet);
|
||||
|
|
Loading…
Reference in New Issue