mirror of https://github.com/ArduPilot/ardupilot
Rover: accept DO_CHANGE_SPEED commands
This commit is contained in:
parent
8464e82812
commit
a08a955cbc
|
@ -510,6 +510,16 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||||
|
|
||||||
switch (packet.command) {
|
switch (packet.command) {
|
||||||
|
|
||||||
|
case MAV_CMD_DO_CHANGE_SPEED:
|
||||||
|
// param1 : unused
|
||||||
|
// param2 : new speed in m/s
|
||||||
|
if (rover.control_mode->set_desired_speed(packet.param2)) {
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
} else {
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_HOME: {
|
case MAV_CMD_DO_SET_HOME: {
|
||||||
// assume failure
|
// assume failure
|
||||||
result = MAV_RESULT_FAILED;
|
result = MAV_RESULT_FAILED;
|
||||||
|
@ -689,6 +699,16 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_DO_CHANGE_SPEED:
|
||||||
|
// param1 : unused
|
||||||
|
// param2 : new speed in m/s
|
||||||
|
if (rover.control_mode->set_desired_speed(packet.param2)) {
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
} else {
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_HOME:
|
case MAV_CMD_DO_SET_HOME:
|
||||||
{
|
{
|
||||||
// param1 : use current (1=use current location, 0=use specified location)
|
// param1 : use current (1=use current location, 0=use specified location)
|
||||||
|
|
Loading…
Reference in New Issue