mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: fixing a bug the Rover simulation
Just a small change to ensure the max_wheel_turn parameter is used instead of a hard coded value.
This commit is contained in:
parent
0366bce9c1
commit
5861b754cc
@ -54,7 +54,7 @@ float SimRover::turn_circle(float steering)
|
||||
if (fabsf(steering) < 1.0e-6) {
|
||||
return 0;
|
||||
}
|
||||
return turning_circle * sinf(radians(35)) / sinf(radians(steering*35));
|
||||
return turning_circle * sinf(radians(max_wheel_turn)) / sinf(radians(steering*max_wheel_turn));
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user