mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: handle MAV_CMD_START_RX_PAIR as both int and long
This commit is contained in:
parent
7e4b5b0c97
commit
afd85c8613
@ -590,7 +590,7 @@ protected:
|
||||
bool get_ap_message_interval(ap_message id, uint16_t &interval_ms) const;
|
||||
MAV_RESULT handle_command_request_message(const mavlink_command_int_t &packet);
|
||||
|
||||
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_START_RX_PAIR(const mavlink_command_int_t &packet);
|
||||
|
||||
virtual MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet);
|
||||
|
||||
|
@ -3287,7 +3287,7 @@ MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_int_t &p
|
||||
/*
|
||||
handle a R/C bind request (for spektrum)
|
||||
*/
|
||||
MAV_RESULT GCS_MAVLINK::handle_rc_bind(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK::handle_START_RX_PAIR(const mavlink_command_int_t &packet)
|
||||
{
|
||||
// initiate bind procedure. We accept the DSM type from either
|
||||
// param1 or param2 due to a past mixup with what parameter is the
|
||||
@ -4724,10 +4724,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
||||
|
||||
switch (packet.command) {
|
||||
|
||||
case MAV_CMD_START_RX_PAIR:
|
||||
result = handle_rc_bind(packet);
|
||||
break;
|
||||
|
||||
#if AP_CAMERA_ENABLED
|
||||
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||
@ -5167,6 +5163,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
||||
case MAV_CMD_SET_EKF_SOURCE_SET:
|
||||
return handle_command_set_ekf_source_set(packet);
|
||||
|
||||
case MAV_CMD_START_RX_PAIR:
|
||||
return handle_START_RX_PAIR(packet);
|
||||
|
||||
#if AP_FILESYSTEM_FORMAT_ENABLED
|
||||
case MAV_CMD_STORAGE_FORMAT:
|
||||
return handle_command_storage_format(packet, msg);
|
||||
|
Loading…
Reference in New Issue
Block a user