mirror of https://github.com/ArduPilot/ardupilot
Rover: remove redundant set_steering calls from Guided
steering is centered within the stop_vehicle method
This commit is contained in:
parent
3b7e84ce7a
commit
77598f72d1
|
@ -48,7 +48,6 @@ void ModeGuided::update()
|
|||
calc_throttle(_desired_speed, true, true);
|
||||
} else {
|
||||
stop_vehicle();
|
||||
g2.motors.set_steering(0.0f);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -70,7 +69,6 @@ void ModeGuided::update()
|
|||
calc_throttle(_desired_speed, true, true);
|
||||
} else {
|
||||
stop_vehicle();
|
||||
g2.motors.set_steering(0.0f);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue