mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: handle MAV_CMD_DO_SEND_BANNER as both long and int
This commit is contained in:
parent
0e458f3342
commit
37b02725b3
|
@ -652,7 +652,6 @@ protected:
|
|||
MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
||||
virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
||||
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet);
|
||||
virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc);
|
||||
MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet);
|
||||
|
|
|
@ -4508,13 +4508,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavl
|
|||
}
|
||||
#endif
|
||||
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_send_banner(const mavlink_command_long_t &packet)
|
||||
{
|
||||
send_banner();
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_set_mode(const mavlink_command_int_t &packet)
|
||||
{
|
||||
const MAV_MODE _base_mode = (MAV_MODE)packet.param1;
|
||||
|
@ -4734,10 +4727,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|||
|
||||
switch (packet.command) {
|
||||
|
||||
case MAV_CMD_DO_SEND_BANNER:
|
||||
result = handle_command_do_send_banner(packet);
|
||||
break;
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
case MAV_CMD_DO_FENCE_ENABLE:
|
||||
result = handle_command_do_fence_enable(packet);
|
||||
|
@ -5114,6 +5103,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
|||
case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE:
|
||||
return handle_command_mount(packet, msg);
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
|
||||
case MAV_CMD_DO_SEND_BANNER:
|
||||
send_banner();
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
case MAV_CMD_DO_SET_HOME:
|
||||
return handle_command_do_set_home(packet);
|
||||
#if AP_AHRS_POSITION_RESET_ENABLED
|
||||
|
|
Loading…
Reference in New Issue