mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
GCS_MAVLink: handle MAV_CMD_DEBUG_TRAP as both long and int
This commit is contained in:
parent
105801c5b0
commit
1ece48b2b3
@ -658,7 +658,7 @@ protected:
|
|||||||
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
|
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_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_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_set_ekf_source_set(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_command_airframe_configuration(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_airframe_configuration(const mavlink_command_int_t &packet);
|
||||||
|
|
||||||
|
@ -4535,7 +4535,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_l
|
|||||||
return MAV_RESULT_ACCEPTED;
|
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.
|
// magic number must be supplied to trap; you must *really* mean it.
|
||||||
if (uint32_t(packet.param1) != 32451) {
|
if (uint32_t(packet.param1) != 32451) {
|
||||||
@ -4822,10 +4822,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|||||||
result = handle_command_get_home_position(packet);
|
result = handle_command_get_home_position(packet);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DEBUG_TRAP:
|
|
||||||
result = handle_command_debug_trap(packet);
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
result = try_command_long_as_command_int(packet, msg);
|
result = try_command_long_as_command_int(packet, msg);
|
||||||
break;
|
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);
|
return handle_can_forward(packet, msg);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
case MAV_CMD_DEBUG_TRAP:
|
||||||
|
return handle_command_debug_trap(packet);
|
||||||
|
|
||||||
case MAV_CMD_DO_AUX_FUNCTION:
|
case MAV_CMD_DO_AUX_FUNCTION:
|
||||||
return handle_command_do_aux_function(packet);
|
return handle_command_do_aux_function(packet);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user