From 55cd8a689b33a96d5a334929737a8426d373e4d8 Mon Sep 17 00:00:00 2001 From: Saurabh Kamat Date: Thu, 28 Mar 2024 01:26:14 +0800 Subject: [PATCH] Fixed turning error in ackermann steering (#2342) This is a fix to the error seen in Ackermann Steering's mode. The steps to reproduce this error are described in issue #2314. Signed-off-by: Saurabh Kamat Signed-off-by: Gaurav Kumar --- src/systems/ackermann_steering/AckermannSteering.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/systems/ackermann_steering/AckermannSteering.cc b/src/systems/ackermann_steering/AckermannSteering.cc index 3fe8a5f60d..0d468916e5 100644 --- a/src/systems/ackermann_steering/AckermannSteering.cc +++ b/src/systems/ackermann_steering/AckermannSteering.cc @@ -968,11 +968,11 @@ void AckermannSteeringPrivate::UpdateAngle( double leftSteeringJointAngle = atan((2.0 * this->wheelBase * sin(ang)) / \ - ((2.0 * this->wheelBase * cos(ang)) + \ + ((2.0 * this->wheelBase * cos(ang)) - \ (1.0 * this->wheelSeparation * sin(ang)))); double rightSteeringJointAngle = atan((2.0 * this->wheelBase * sin(ang)) / \ - ((2.0 * this->wheelBase * cos(ang)) - \ + ((2.0 * this->wheelBase * cos(ang)) + \ (1.0 * this->wheelSeparation * sin(ang)))); auto leftSteeringPos = _ecm.Component(