We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 6efa91b commit e4e129eCopy full SHA for e4e129e
planning/motion_velocity_smoother/src/smoother/smoother_base.cpp
@@ -224,8 +224,8 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit(
224
auto & steer_back = output.at(i).front_wheel_angle_rad;
225
226
// 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));
+ steer_front = std::atan(base_param_.wheel_base * curvature_v.at(i + 1));
+ steer_back = std::atan(base_param_.wheel_base * curvature_v.at(i));
229
230
const auto mean_vel = 0.5 * (v_front + v_back);
231
const auto dt = std::max(points_interval / mean_vel, std::numeric_limits<double>::epsilon());
0 commit comments