Rover: stop_vehicle controls turn rate until stopped

This commit is contained in:
Randy Mackay 2021-12-02 20:22:29 +09:00
parent 30ddc4e06c
commit a0ef7a1476
1 changed files with 7 additions and 3 deletions

View File

@ -331,7 +331,7 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled)
g2.motors.set_throttle(throttle_out);
}
// performs a controlled stop with steering centered
// performs a controlled stop without turning
bool Mode::stop_vehicle()
{
// call throttle controller and convert output to -100 to +100 range
@ -353,8 +353,12 @@ bool Mode::stop_vehicle()
// send to motor
g2.motors.set_throttle(throttle_out);
// do not attempt to steer
g2.motors.set_steering(0.0f);
// do not turn while slowing down
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 stopped;