mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Rover: support speed control of DO_REPOSITION
This commit is contained in:
parent
1d0735f206
commit
e347618210
@ -718,6 +718,12 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_com
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (is_positive(packet.param1)) {
|
||||||
|
if (!rover.control_mode->set_desired_speed(packet.param1)) {
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// set the destination
|
// set the destination
|
||||||
if (!rover.mode_guided.set_desired_location(request_location)) {
|
if (!rover.mode_guided.set_desired_location(request_location)) {
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
|
Loading…
Reference in New Issue
Block a user