Skip to content
Snippets Groups Projects
Commit fc0d703b authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

Rover: much simpler SPEED_TURN_GAIN implementation

as soon as we hit the SPEED_TURN_DIST we lower target speed to the
specified gain
parent 69b5f352
No related branches found
No related tags found
No related merge requests found
...@@ -109,7 +109,7 @@ static void calc_throttle(float target_speed) ...@@ -109,7 +109,7 @@ static void calc_throttle(float target_speed)
if (control_mode >= AUTO && wp_distance <= g.speed_turn_dist) { if (control_mode >= AUTO && wp_distance <= g.speed_turn_dist) {
// in auto-modes we reduce speed when approaching waypoints // in auto-modes we reduce speed when approaching waypoints
float reduction2 = 1.0 - speed_turn_reduction*((g.speed_turn_dist - wp_distance)/g.speed_turn_dist); float reduction2 = 1.0 - speed_turn_reduction;
if (reduction2 < reduction) { if (reduction2 < reduction) {
reduction = reduction2; reduction = reduction2;
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment