From 5861b754cc536d4f5cd1b5e4f6e6caa014002bf2 Mon Sep 17 00:00:00 2001 From: Grant Morphett Date: Thu, 7 Apr 2016 17:15:54 +1000 Subject: [PATCH] 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. --- libraries/SITL/SIM_Rover.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_Rover.cpp b/libraries/SITL/SIM_Rover.cpp index aa28a20bab..173645604a 100644 --- a/libraries/SITL/SIM_Rover.cpp +++ b/libraries/SITL/SIM_Rover.cpp @@ -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)); } /*