mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: guided heading-and-speed control fix
This removes the lane-based-speed-control from guided mode's heading-and-speed controller which does not use the navigation controller
This commit is contained in:
parent
fd385c0f91
commit
2ba6aa7e8a
@ -53,7 +53,7 @@ void ModeGuided::update()
|
||||
if (have_attitude_target) {
|
||||
// run steering and throttle controllers
|
||||
calc_steering_to_heading(_desired_yaw_cd);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true, true);
|
||||
calc_throttle(_desired_speed, true, true);
|
||||
} else {
|
||||
// we have reached the destination so stay here
|
||||
if (rover.is_boat()) {
|
||||
|
Loading…
Reference in New Issue
Block a user