Skip to content

Commit f0041d3

Browse files
author
Shigekazu Fukuta
committed
return code moved to end
1 parent 153a115 commit f0041d3

File tree

1 file changed

+2
-2
lines changed
  • planning/obstacle_avoidance_planner/src

1 file changed

+2
-2
lines changed

planning/obstacle_avoidance_planner/src/utils.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -343,6 +343,7 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolate2DTraj
343343
const auto monotonic_base_yaw = convertEulerAngleToMonotonic(base_yaw);
344344

345345
// spline interpolation
346+
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolated_points;
346347
try {
347348
const auto interpolated_x = interpolation::slerp(base_s, base_x, new_s);
348349
const auto interpolated_y = interpolation::slerp(base_s, base_y, new_s);
@@ -354,7 +355,6 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolate2DTraj
354355
}
355356
}
356357

357-
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolated_points;
358358
for (size_t i = 0; i < interpolated_x.size(); i++) {
359359
autoware_auto_planning_msgs::msg::TrajectoryPoint point;
360360
point.pose.position.x = interpolated_x[i];
@@ -364,10 +364,10 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolate2DTraj
364364
interpolated_points.push_back(point);
365365
}
366366

367-
return interpolated_points;
368367
} catch (const std::invalid_argument & e) {
369368
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
370369
}
370+
return interpolated_points;
371371
}
372372

373373
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> getInterpolatedTrajectoryPoints(

0 commit comments

Comments
 (0)