Skip to content

Commit

Permalink
fix(motion_velocity_smoother): calc first point front_wheel_angle_rad
Browse files Browse the repository at this point in the history
Signed-off-by: Vincent Richard <richard-v@macnica.co.jp>
  • Loading branch information
VRichardJP committed Jan 22, 2024
1 parent f5cef6c commit b1d9442
Showing 1 changed file with 1 addition and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -215,7 +215,7 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit(

// Step2. Calculate steer rate for each trajectory point.
std::vector<double> steer_rate_arr(output.size(), 0.0);
for (size_t i = 1; i < output.size() - 1; i++) {
for (size_t i = 0; i < output.size() - 1; i++) {
// velocity
const auto & v_front = output.at(i + 1).longitudinal_velocity_mps;
const auto & v_back = output.at(i).longitudinal_velocity_mps;
Expand All @@ -234,7 +234,6 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit(
steer_rate_arr.at(i) = steering_diff / dt;
}

steer_rate_arr.at(0) = steer_rate_arr.at(1);
steer_rate_arr.back() = steer_rate_arr.at((output.size() - 2));

// Step3. Remove noise by mean filter.
Expand Down

0 comments on commit b1d9442

Please sign in to comment.