Rover: support speed control of DO_REPOSITION

This commit is contained in:
Tatsuya Yamaguchi 2020-10-06 08:54:38 +09:00 committed by Randy Mackay
parent 1d0735f206
commit e347618210
1 changed files with 6 additions and 0 deletions

View File

@ -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
if (!rover.mode_guided.set_desired_location(request_location)) {
return MAV_RESULT_FAILED;