Browse Source

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.
mission-4.1.18
Grant Morphett 9 years ago committed by Randy Mackay
parent
commit
5861b754cc
  1. 2
      libraries/SITL/SIM_Rover.cpp

2
libraries/SITL/SIM_Rover.cpp

@ -54,7 +54,7 @@ float SimRover::turn_circle(float steering) @@ -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…
Cancel
Save