Skip to content

Commit 3048db2

Browse files
VRichardJPkarishma1911
authored andcommitted
fix(motion_velocity_smoother): front wheel steer rate calculation (autowarefoundation#5965)
autowarefoundation#5964 Signed-off-by: Vincent Richard <richard-v@macnica.co.jp>
1 parent 779e0f8 commit 3048db2

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

planning/motion_velocity_smoother/src/smoother/smoother_base.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -224,8 +224,8 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit(
224224
auto & steer_back = output.at(i).front_wheel_angle_rad;
225225

226226
// calculate the just 2 steering angle
227-
steer_front = std::atan(base_param_.wheel_base * curvature_v.at(i));
228-
steer_back = std::atan(base_param_.wheel_base * curvature_v.at(i + 1));
227+
steer_front = std::atan(base_param_.wheel_base * curvature_v.at(i + 1));
228+
steer_back = std::atan(base_param_.wheel_base * curvature_v.at(i));
229229

230230
const auto mean_vel = 0.5 * (v_front + v_back);
231231
const auto dt = std::max(points_interval / mean_vel, std::numeric_limits<double>::epsilon());

0 commit comments

Comments
 (0)