mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: much simpler SPEED_TURN_GAIN implementation
as soon as we hit the SPEED_TURN_DIST we lower target speed to the specified gain
This commit is contained in:
parent
69b5f352f6
commit
fc0d703b9b
@ -109,7 +109,7 @@ static void calc_throttle(float target_speed)
|
||||
|
||||
if (control_mode >= AUTO && wp_distance <= g.speed_turn_dist) {
|
||||
// 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) {
|
||||
reduction = reduction2;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user