Browse Source

Rover: accept DO_CHANGE_SPEED commands

master
Randy Mackay 7 years ago
parent
commit
a08a955cbc
  1. 20
      APMrover2/GCS_Mavlink.cpp

20
APMrover2/GCS_Mavlink.cpp

@ -510,6 +510,16 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) @@ -510,6 +510,16 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
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: {
// assume failure
result = MAV_RESULT_FAILED;
@ -689,6 +699,16 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) @@ -689,6 +699,16 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
}
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:
{
// param1 : use current (1=use current location, 0=use specified location)

Loading…
Cancel
Save