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_DEBUG_TRAP as both long and int #25235

Merged
merged 1 commit into from
Oct 16, 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 @@ -658,7 +658,7 @@ class GCS_MAVLINK
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_debug_trap(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_debug_trap(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_set_ekf_source_set(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_airframe_configuration(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 @@ -4535,7 +4535,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_l
return MAV_RESULT_ACCEPTED;
}

MAV_RESULT GCS_MAVLINK::handle_command_debug_trap(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK::handle_command_debug_trap(const mavlink_command_int_t &packet)
{
// magic number must be supplied to trap; you must *really* mean it.
if (uint32_t(packet.param1) != 32451) {
Expand Down Expand Up @@ -4828,10 +4828,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
result = handle_command_get_home_position(packet);
break;

case MAV_CMD_DEBUG_TRAP:
result = handle_command_debug_trap(packet);
break;

default:
result = try_command_long_as_command_int(packet, msg);
break;
Expand Down Expand Up @@ -5096,6 +5092,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_DEBUG_TRAP:
return handle_command_debug_trap(packet);

case MAV_CMD_DO_AUX_FUNCTION:
return handle_command_do_aux_function(packet);

Expand Down