mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: stop_vehicle controls turn rate until stopped
This commit is contained in:
parent
30ddc4e06c
commit
a0ef7a1476
@ -331,7 +331,7 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled)
|
|||||||
g2.motors.set_throttle(throttle_out);
|
g2.motors.set_throttle(throttle_out);
|
||||||
}
|
}
|
||||||
|
|
||||||
// performs a controlled stop with steering centered
|
// performs a controlled stop without turning
|
||||||
bool Mode::stop_vehicle()
|
bool Mode::stop_vehicle()
|
||||||
{
|
{
|
||||||
// call throttle controller and convert output to -100 to +100 range
|
// call throttle controller and convert output to -100 to +100 range
|
||||||
@ -353,8 +353,12 @@ bool Mode::stop_vehicle()
|
|||||||
// send to motor
|
// send to motor
|
||||||
g2.motors.set_throttle(throttle_out);
|
g2.motors.set_throttle(throttle_out);
|
||||||
|
|
||||||
// do not attempt to steer
|
// do not turn while slowing down
|
||||||
g2.motors.set_steering(0.0f);
|
float steering_out = 0.0;
|
||||||
|
if (!stopped) {
|
||||||
|
steering_out = attitude_control.get_steering_out_rate(0.0, g2.motors.limit.steer_left, g2.motors.limit.steer_right, rover.G_Dt);
|
||||||
|
}
|
||||||
|
g2.motors.set_steering(steering_out * 4500.0);
|
||||||
|
|
||||||
// return true once stopped
|
// return true once stopped
|
||||||
return stopped;
|
return stopped;
|
||||||
|
Loading…
Reference in New Issue
Block a user