mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: collapse un-needed method
This commit is contained in:
parent
e0eacdc197
commit
485fa80f1c
|
@ -654,7 +654,6 @@ protected:
|
|||
|
||||
virtual bool mav_frame_for_command_long(MAV_FRAME &fame, MAV_CMD packet_command) const;
|
||||
MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
||||
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
||||
MAV_RESULT handle_command_camera(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet);
|
||||
virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc);
|
||||
|
|
|
@ -4751,20 +4751,6 @@ MAV_RESULT GCS_MAVLINK::try_command_long_as_command_int(const mavlink_command_lo
|
|||
return handle_command_int_packet(command_int, msg);
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
|
||||
{
|
||||
MAV_RESULT result = MAV_RESULT_FAILED;
|
||||
|
||||
switch (packet.command) {
|
||||
|
||||
default:
|
||||
result = try_command_long_as_command_int(packet, msg);
|
||||
break;
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::location_from_command_t(const mavlink_command_long_t &in, MAV_FRAME in_frame, Location &out)
|
||||
{
|
||||
mavlink_command_int_t command_int;
|
||||
|
@ -4865,7 +4851,7 @@ void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg)
|
|||
|
||||
hal.util->persistent_data.last_mavlink_cmd = packet.command;
|
||||
|
||||
const MAV_RESULT result = handle_command_long_packet(packet, msg);
|
||||
const MAV_RESULT result = try_command_long_as_command_int(packet, msg);
|
||||
|
||||
// send ACK or NAK
|
||||
mavlink_msg_command_ack_send(chan, packet.command, result,
|
||||
|
|
Loading…
Reference in New Issue