From 58c879a7089fe0795e1995d1d85a97e4d2571c13 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Sun, 15 Dec 2024 15:05:00 +0900 Subject: [PATCH] fix ci Signed-off-by: Mamoru Sobue --- .../src/goal_planner_module.cpp | 7 +++---- .../src/pull_over_planner/geometric_pull_over.cpp | 5 +---- .../src/pull_over_planner/shift_pull_over.cpp | 2 +- 3 files changed, 5 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 28a2f8cee48b0..24bacf6fa6540 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1690,11 +1690,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath( // 4. feasible stop const auto stop_pose_opt = std::invoke([&]() -> std::optional { if (context_data.pull_over_path_opt) - return context_data.pull_over_path_opt.value().start_pose(); + return std::make_optional(context_data.pull_over_path_opt.value().start_pose()); if (context_data.lane_parking_response.closest_start_pose) - return context_data.lane_parking_response.closest_start_pose.value(); - if (!decel_pose) return std::nullopt; - return decel_pose.value(); + return context_data.lane_parking_response.closest_start_pose; + return decel_pose; }); if (!stop_pose_opt.has_value()) { const auto feasible_stop_path = diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index f75358601d877..c0bac5c5ce2a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -78,9 +78,6 @@ std::optional GeometricPullOver::plan( auto pull_over_path_opt = PullOverPath::create( getPlannerType(), id, planner_.getPaths(), planner_.getStartPose(), modified_goal_pose, planner_.getPairsTerminalVelocityAndAccel()); - if (!pull_over_path_opt) { - return {}; - } - return pull_over_path_opt.value(); + return pull_over_path_opt; } } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index 501502125d7ee..edecfd733d3be 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -67,7 +67,7 @@ std::optional ShiftPullOver::plan( modified_goal_pose, id, planner_data, previous_module_output, road_lanes, pull_over_lanes, lateral_jerk); if (!pull_over_path) continue; - return *pull_over_path; + return pull_over_path; } return {};