Skip to content

Commit 4088726

Browse files
sfukutapre-commit-ci[bot]
authored and
kimurariku
committed
fix(obstacle_avoidance_planner): add empty check (#1285)
* fix(obstacle_avoidance_planner): add empty check * ci(pre-commit): autofix * add invalid_argument * delete empty check * return code moved to end * add warning log * update rclcpp_debug * delete debug log * Delete unnecessary blank lines --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent a5b62af commit 4088726

File tree

1 file changed

+20
-17
lines changed
  • planning/obstacle_avoidance_planner/src

1 file changed

+20
-17
lines changed

planning/obstacle_avoidance_planner/src/utils.cpp

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

345345
// spline interpolation
346-
const auto interpolated_x = interpolation::slerp(base_s, base_x, new_s);
347-
const auto interpolated_y = interpolation::slerp(base_s, base_y, new_s);
348-
const auto interpolated_yaw = interpolation::slerp(base_s, monotonic_base_yaw, new_s);
349-
350-
for (size_t i = 0; i < interpolated_x.size(); i++) {
351-
if (std::isnan(interpolated_x[i]) || std::isnan(interpolated_y[i])) {
352-
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
346+
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolated_points;
347+
try {
348+
const auto interpolated_x = interpolation::slerp(base_s, base_x, new_s);
349+
const auto interpolated_y = interpolation::slerp(base_s, base_y, new_s);
350+
const auto interpolated_yaw = interpolation::slerp(base_s, monotonic_base_yaw, new_s);
351+
352+
for (size_t i = 0; i < interpolated_x.size(); i++) {
353+
if (std::isnan(interpolated_x[i]) || std::isnan(interpolated_y[i])) {
354+
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
355+
}
353356
}
354-
}
355357

356-
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolated_points;
357-
for (size_t i = 0; i < interpolated_x.size(); i++) {
358-
autoware_auto_planning_msgs::msg::TrajectoryPoint point;
359-
point.pose.position.x = interpolated_x[i];
360-
point.pose.position.y = interpolated_y[i];
361-
point.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(
362-
tier4_autoware_utils::normalizeRadian(interpolated_yaw[i]));
363-
interpolated_points.push_back(point);
358+
for (size_t i = 0; i < interpolated_x.size(); i++) {
359+
autoware_auto_planning_msgs::msg::TrajectoryPoint point;
360+
point.pose.position.x = interpolated_x[i];
361+
point.pose.position.y = interpolated_y[i];
362+
point.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(
363+
tier4_autoware_utils::normalizeRadian(interpolated_yaw[i]));
364+
interpolated_points.push_back(point);
365+
}
366+
} catch (const std::invalid_argument & e) {
367+
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
364368
}
365-
366369
return interpolated_points;
367370
}
368371

0 commit comments

Comments
 (0)