mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: allow setting modes via COMMAND_INT and DO_SET_MODE
This commit is contained in:
parent
aaca600a94
commit
7713b531a0
|
@ -657,7 +657,7 @@ protected:
|
|||
virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc);
|
||||
MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_sprayer(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_set_mode(const mavlink_command_int_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_int_t &packet);
|
||||
|
|
|
@ -4515,7 +4515,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_send_banner(const mavlink_command_long
|
|||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_set_mode(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_set_mode(const mavlink_command_int_t &packet)
|
||||
{
|
||||
const MAV_MODE _base_mode = (MAV_MODE)packet.param1;
|
||||
const uint32_t _custom_mode = (uint32_t)packet.param2;
|
||||
|
@ -4732,10 +4732,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|||
|
||||
switch (packet.command) {
|
||||
|
||||
case MAV_CMD_DO_SET_MODE:
|
||||
result = handle_command_do_set_mode(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SEND_BANNER:
|
||||
result = handle_command_do_send_banner(packet);
|
||||
break;
|
||||
|
@ -5105,6 +5101,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
|||
case MAV_CMD_DO_FLIGHTTERMINATION:
|
||||
return handle_flight_termination(packet);
|
||||
|
||||
case MAV_CMD_DO_SET_MODE:
|
||||
return handle_command_do_set_mode(packet);
|
||||
|
||||
case MAV_CMD_DO_SET_ROI:
|
||||
case MAV_CMD_DO_SET_ROI_LOCATION:
|
||||
return handle_command_do_set_roi(packet);
|
||||
|
|
Loading…
Reference in New Issue