Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GCS_MAVLink: handle MAV_CMD_START_RX_PAIR as both int and long #25375

Merged
merged 1 commit into from
Oct 31, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -587,7 +587,7 @@ class GCS_MAVLINK
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);

Expand Down
9 changes: 4 additions & 5 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3276,7 +3276,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
Expand Down Expand Up @@ -4703,10 +4703,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:
Expand Down Expand Up @@ -5139,6 +5135,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);
Expand Down