mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: remove old DO_SET_MODE support
We no longer support setting modes except via custom-modes
This commit is contained in:
parent
1304b86d09
commit
add5eb6907
@ -799,31 +799,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_MODE:
|
||||
switch (static_cast<uint16_t>(packet.param1)) {
|
||||
case MAV_MODE_MANUAL_ARMED:
|
||||
case MAV_MODE_MANUAL_DISARMED:
|
||||
rover.set_mode(rover.mode_manual, MODE_REASON_GCS_COMMAND);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
case MAV_MODE_AUTO_ARMED:
|
||||
case MAV_MODE_AUTO_DISARMED:
|
||||
rover.set_mode(rover.mode_auto, MODE_REASON_GCS_COMMAND);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
case MAV_MODE_STABILIZE_DISARMED:
|
||||
case MAV_MODE_STABILIZE_ARMED:
|
||||
rover.set_mode(rover.mode_steering, MODE_REASON_GCS_COMMAND);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
default:
|
||||
result = MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
if (is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f)) {
|
||||
// when packet.param1 == 3 we reboot to hold in bootloader
|
||||
|
Loading…
Reference in New Issue
Block a user