Rover: smooth steeing at low speed in STEERING mode

use the G limit from the turn radius as the steering limit
This commit is contained in:
Andrew Tridgell 2013-09-30 09:04:34 +10:00
parent 0784c01f19
commit c7ac864af9
1 changed files with 11 additions and 2 deletions

View File

@ -869,9 +869,18 @@ static void update_current_mode(void)
case STEERING: {
/*
in steering mode we control lateral acceleration directly
in steering mode we control lateral acceleration
directly. We first calculate the maximum lateral
acceleration at full steering lock for this speed. That is
V^2/R where R is the radius of turn. We get the radius of
turn from half the STEER2SRV_P.
*/
lateral_acceleration = g.turn_max_g * GRAVITY_MSS * (channel_steer->pwm_to_angle()/4500.0f);
float max_g_force = ground_speed * ground_speed / steerController.get_turn_radius();
// constrain to user set TURN_MAX_G
max_g_force = constrain_float(max_g_force, 0.1f, g.turn_max_g * GRAVITY_MSS);
lateral_acceleration = max_g_force * (channel_steer->pwm_to_angle()/4500.0f);
calc_nav_steer();
// and throttle gives speed in proportion to cruise speed