diff --git a/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/interpolate.cpp b/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/interpolate.cpp index 0501df10e75e0..3a79b1f01a804 100644 --- a/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/interpolate.cpp +++ b/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/interpolate.cpp @@ -229,8 +229,8 @@ bool SplineInterpolate::interpolate( generateSpline(base_value); // interpolate by spline with normalized index - for (int j = 0; j < static_cast(normalized_idx.size()); ++j) { - return_value.push_back(getValue(normalized_idx[j])); + for (const auto & index : normalized_idx) { + return_value.push_back(getValue(index)); } return true; }