Skip to content

Commit

Permalink
fix ci
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed Dec 15, 2024
1 parent f0f215c commit 83e3f8f
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -498,7 +498,6 @@ void FreespaceParkingPlanner::onTimer()
const auto & current_status = local_request.get_current_status();
const auto & pull_over_path_opt = local_request.get_pull_over_path();
const auto & last_path_update_time = local_request.get_last_path_update_time();
const auto & occupancy_grid_map = local_request.get_occupancy_grid_map();

if (current_status == ModuleStatus::IDLE) {
return;
Expand Down Expand Up @@ -1690,11 +1689,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath(
// 4. feasible stop
const auto stop_pose_opt = std::invoke([&]() -> std::optional<Pose> {
if (context_data.pull_over_path_opt)
return context_data.pull_over_path_opt.value().start_pose();
return std::make_optional<Pose>(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;

Check notice on line 1695 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

GoalPlannerModule::generateStopPath decreases in cyclomatic complexity from 14 to 13, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 1695 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1694-L1695

Added lines #L1694 - L1695 were not covered by tests
});
if (!stop_pose_opt.has_value()) {
const auto feasible_stop_path =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,9 +78,6 @@ std::optional<PullOverPath> 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
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ std::optional<PullOverPath> 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 {};
Expand Down

0 comments on commit 83e3f8f

Please sign in to comment.