Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(blind_spot_module): boost::optional to std::optional #5831

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion planning/behavior_velocity_blind_spot_module/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
<depend>behavior_velocity_planner_common</depend>
<depend>geometry_msgs</depend>
<depend>lanelet2_extension</depend>
<depend>libboost-dev</depend>
<depend>motion_utils</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
Expand Down
38 changes: 25 additions & 13 deletions planning/behavior_velocity_blind_spot_module/src/scene.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.69 to 5.75, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -27,12 +27,14 @@
#include <boost/geometry/algorithms/length.hpp>
#include <boost/geometry/algorithms/union.hpp>

#include <lanelet2_core/Forward.h>
#include <lanelet2_core/geometry/Polygon.h>
#include <lanelet2_core/primitives/BasicRegulatoryElements.h>

#include <algorithm>
#include <limits>
#include <memory>
#include <optional>
#include <string>
#include <type_traits>
#include <utility>
Expand Down Expand Up @@ -203,7 +205,7 @@
return true;
}

boost::optional<int> BlindSpotModule::getFirstPointConflictingLanelets(
std::optional<int> BlindSpotModule::getFirstPointConflictingLanelets(

Check warning on line 208 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L208

Added line #L208 was not covered by tests
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const lanelet::ConstLanelets & lanelets) const
{
Expand All @@ -229,7 +231,7 @@
if (is_conflict) {
return first_idx_conflicting_lanelets;
} else {
return boost::none;
return std::nullopt;

Check warning on line 234 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L234

Added line #L234 was not covered by tests
}
}

Expand All @@ -252,7 +254,7 @@
/* generate stop point */
int stop_idx_ip = 0; // stop point index for interpolated path.
if (straight_lanelets.size() > 0) {
boost::optional<int> first_idx_conflicting_lane_opt =
std::optional<int> first_idx_conflicting_lane_opt =
getFirstPointConflictingLanelets(path_ip, straight_lanelets);
if (!first_idx_conflicting_lane_opt) {
RCLCPP_DEBUG(logger_, "No conflicting line found.");
Expand All @@ -261,7 +263,7 @@
stop_idx_ip = std::max(
first_idx_conflicting_lane_opt.value() - 1 - margin_idx_dist - base2front_idx_dist, 0);
} else {
boost::optional<geometry_msgs::msg::Pose> intersection_enter_point_opt =
std::optional<geometry_msgs::msg::Pose> intersection_enter_point_opt =
getStartPointFromLaneLet(lane_id_);
if (!intersection_enter_point_opt) {
RCLCPP_DEBUG(logger_, "No intersection enter point found.");
Expand Down Expand Up @@ -502,7 +504,7 @@
return new_lanelet;
}

boost::optional<BlindSpotPolygons> BlindSpotModule::generateBlindSpotPolygons(
std::optional<BlindSpotPolygons> BlindSpotModule::generateBlindSpotPolygons(

Check warning on line 507 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L507

Added line #L507 was not covered by tests
lanelet::LaneletMapConstPtr lanelet_map_ptr,
[[maybe_unused]] lanelet::routing::RoutingGraphPtr routing_graph_ptr,
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int closest_idx,
Expand Down Expand Up @@ -537,11 +539,21 @@
lanelet::ConstLanelets adjacent_lanelets;
for (const auto i : lane_ids) {
const auto lane = lanelet_map_ptr->laneletLayer.get(i);
const auto adj =
turn_direction_ == TurnDirection::LEFT
? (routing_graph_ptr->adjacentLeft(lane))
: (turn_direction_ == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight(lane))
: boost::none);
const auto adj = std::invoke([&]() -> std::optional<lanelet::ConstLanelet> {

Check warning on line 542 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L542

Added line #L542 was not covered by tests
if (turn_direction_ == TurnDirection::INVALID) {
return std::nullopt;

Check warning on line 544 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L544

Added line #L544 was not covered by tests
}
const auto adj_lane = (turn_direction_ == TurnDirection::LEFT)
? routing_graph_ptr->adjacentLeft(lane)

Check warning on line 547 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L547

Added line #L547 was not covered by tests
: routing_graph_ptr->adjacentRight(lane);

if (adj_lane) {
return *adj_lane;
}

return std::nullopt;

Check warning on line 554 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L554

Added line #L554 was not covered by tests
});

if (adj) {
const auto half_lanelet = generateExtendedAdjacentLanelet(adj.value(), turn_direction_);
adjacent_lanelets.push_back(half_lanelet);
Expand Down Expand Up @@ -577,7 +589,7 @@
}
return blind_spot_polygons;
} else {
return boost::none;
return std::nullopt;

Check warning on line 592 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

BlindSpotModule::generateBlindSpotPolygons increases in cyclomatic complexity from 14 to 15, 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 592 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L592

Added line #L592 was not covered by tests
}
}

Expand Down Expand Up @@ -628,13 +640,13 @@
return false;
}

boost::optional<geometry_msgs::msg::Pose> BlindSpotModule::getStartPointFromLaneLet(
std::optional<geometry_msgs::msg::Pose> BlindSpotModule::getStartPointFromLaneLet(

Check warning on line 643 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L643

Added line #L643 was not covered by tests
const lanelet::Id lane_id) const
{
lanelet::ConstLanelet lanelet =
planner_data_->route_handler_->getLaneletMapPtr()->laneletLayer.get(lane_id);
if (lanelet.centerline().empty()) {
return boost::none;
return std::nullopt;

Check warning on line 649 in planning/behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_blind_spot_module/src/scene.cpp#L649

Added line #L649 was not covered by tests
}
const auto p = lanelet.centerline().front();
geometry_msgs::msg::Point start_point;
Expand Down
9 changes: 3 additions & 6 deletions planning/behavior_velocity_blind_spot_module/src/scene.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,6 @@
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <geometry_msgs/msg/point.hpp>

#include <boost/optional.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_routing/RoutingGraph.h>

Expand Down Expand Up @@ -128,7 +126,7 @@ class BlindSpotModule : public SceneModuleInterface
* @param closest_idx closest path point index from ego car in path points
* @return Blind spot polygons
*/
boost::optional<BlindSpotPolygons> generateBlindSpotPolygons(
std::optional<BlindSpotPolygons> generateBlindSpotPolygons(
lanelet::LaneletMapConstPtr lanelet_map_ptr,
lanelet::routing::RoutingGraphPtr routing_graph_ptr,
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int closest_idx,
Expand Down Expand Up @@ -192,7 +190,7 @@ class BlindSpotModule : public SceneModuleInterface
* @param lanelets target lanelets
* @return path point index
*/
boost::optional<int> getFirstPointConflictingLanelets(
std::optional<int> getFirstPointConflictingLanelets(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const lanelet::ConstLanelets & lanelets) const;

Expand All @@ -201,8 +199,7 @@ class BlindSpotModule : public SceneModuleInterface
* @param lane_id lane id of objective lanelet
* @return end point of lanelet
*/
boost::optional<geometry_msgs::msg::Pose> getStartPointFromLaneLet(
const lanelet::Id lane_id) const;
std::optional<geometry_msgs::msg::Pose> getStartPointFromLaneLet(const lanelet::Id lane_id) const;

/**
* @brief get straight lanelets in intersection
Expand Down
Loading