diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp index 7498568be99fb..f4b1304d67e5e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp @@ -68,7 +68,6 @@ TrajectoryPoints downsampleTrajectory( void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_base) { - auto t = 0.0; auto prev_point = trajectory.front(); auto prev_heading = tf2::getYaw(prev_point.pose.orientation); for (auto i = 1ul; i < trajectory.size(); ++i) { @@ -76,7 +75,6 @@ void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_b auto & point = trajectory[i]; const auto dt = autoware::universe_utils::calcDistance2d(prev_point, point) / prev_point.longitudinal_velocity_mps; - t += dt; const auto heading = tf2::getYaw(point.pose.orientation); const auto d_heading = heading - prev_heading; prev_heading = heading;