mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: handle DO_AUX_FUNCTION as both long and int
This commit is contained in:
parent
5af5e1969b
commit
57c2f7b2de
|
@ -522,7 +522,7 @@ protected:
|
|||
virtual bool set_home(const Location& loc, bool lock) = 0;
|
||||
|
||||
virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_do_aux_function(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_aux_function(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_storage_format(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
||||
void handle_mission_request_list(const mavlink_message_t &msg);
|
||||
void handle_mission_request(const mavlink_message_t &msg);
|
||||
|
|
|
@ -2834,7 +2834,7 @@ void GCS_MAVLINK::send_heartbeat() const
|
|||
system_status());
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (packet.param2 > 2) {
|
||||
return MAV_RESULT_DENIED;
|
||||
|
@ -4838,10 +4838,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_AUX_FUNCTION:
|
||||
result = handle_command_do_aux_function(packet);
|
||||
break;
|
||||
|
||||
default:
|
||||
result = try_command_long_as_command_int(packet, msg);
|
||||
break;
|
||||
|
@ -5095,6 +5091,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
|||
return handle_can_forward(packet, msg);
|
||||
#endif
|
||||
|
||||
case MAV_CMD_DO_AUX_FUNCTION:
|
||||
return handle_command_do_aux_function(packet);
|
||||
|
||||
case MAV_CMD_DO_FLIGHTTERMINATION:
|
||||
return handle_flight_termination(packet);
|
||||
|
||||
|
|
Loading…
Reference in New Issue