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

feat(autoware_behavior_path_dynamic_obstacle_avoidance): expand drivable area #8295

Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@
max_object_vel: 0.5 # [m/s] The object will be determined as stopped if the velocity is smaller than this value.

drivable_area_generation:
expand_drivable_area: false
polygon_generation_method: "ego_path_base" # choose "ego_path_base" and "object_path_base"
object_path_base:
min_longitudinal_polygon_margin: 3.0 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,8 @@ struct DynamicAvoidanceParameters
bool enable_debug_info{true};
bool use_hatched_road_markings{true};

std::string use_lane_type{"opposite_direction_lane"};

// obstacle types to avoid
bool avoid_car{true};
bool avoid_truck{true};
Expand Down Expand Up @@ -130,6 +132,7 @@ struct DynamicAvoidanceParameters

// drivable area generation
PolygonGenerationMethod polygon_generation_method{};
bool expand_drivable_area;
double min_obj_path_based_lon_polygon_margin{0.0};
double lat_offset_from_obstacle{0.0};
double margin_distance_around_pedestrian{0.0};
Expand Down Expand Up @@ -169,6 +172,10 @@ struct LatFeasiblePaths
class DynamicObstacleAvoidanceModule : public SceneModuleInterface
{
public:
static constexpr const char * logger_namespace =
"planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.dynamic_"
"obstacle_avoidance";

struct DynamicAvoidanceObject
{
DynamicAvoidanceObject(
Expand Down Expand Up @@ -439,6 +446,11 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
std::optional<autoware::universe_utils::Polygon2d> calcPredictedPathBasedDynamicObstaclePolygon(
const DynamicAvoidanceObject & object, const EgoPathReservePoly & ego_path_poly) const;
EgoPathReservePoly calcEgoPathReservePoly(const PathWithLaneId & ego_path) const;
lanelet::ConstLanelets getCurrentLanesFromPath(
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data);
DrivableLanes generateExpandedDrivableLanes(
const lanelet::ConstLanelet & lanelet, const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<DynamicAvoidanceParameters> & parameters);

void printIgnoreReason(const std::string & obj_uuid, const std::string & reason)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,11 @@
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>signal_processing</depend>
<depend>tf2</depend>
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@

{ // drivable_area_generation
const std::string ns = "dynamic_avoidance.drivable_area_generation.";
p.expand_drivable_area = node->declare_parameter<bool>(ns + "expand_drivable_area");

Check warning on line 111 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

DynamicObstacleAvoidanceModuleManager::init increases from 96 to 97 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 111 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp#L111

Added line #L111 was not covered by tests
p.polygon_generation_method = convertToPolygonGenerationMethod(
node->declare_parameter<std::string>(ns + "polygon_generation_method"));
p.min_obj_path_based_lon_polygon_margin =
Expand Down Expand Up @@ -238,6 +239,7 @@
p->polygon_generation_method =
convertToPolygonGenerationMethod(polygon_generation_method_str);
}
updateParam<bool>(parameters, ns + "expand_drivable_area", p->expand_drivable_area);

Check warning on line 242 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

DynamicObstacleAvoidanceModuleManager::updateModuleParams increases from 121 to 122 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 242 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp#L242

Added line #L242 was not covered by tests
updateParam<double>(
parameters, ns + "object_path_base.min_longitudinal_polygon_margin",
p->min_obj_path_based_lon_polygon_margin);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1538 to 1689, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_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 6.52 to 6.63, 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 All @@ -20,6 +20,7 @@
#include "object_recognition_utils/predicted_path_utils.hpp"
#include "signal_processing/lowpass_filter_1d.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware_lanelet2_extension/utility/utilities.hpp>

#include <boost/geometry/algorithms/buffer.hpp>
Expand Down Expand Up @@ -99,6 +100,22 @@
marker_array.markers.push_back(marker);
}

bool isEndPointsConnected(

Check warning on line 103 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L103

Added line #L103 was not covered by tests
const lanelet::ConstLanelet & left_lane, const lanelet::ConstLanelet & right_lane)
{
const auto & left_back_point_2d = right_lane.leftBound2d().back().basicPoint();
const auto & right_back_point_2d = left_lane.rightBound2d().back().basicPoint();

Check warning on line 107 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L106-L107

Added lines #L106 - L107 were not covered by tests

constexpr double epsilon = 1e-5;
return (right_back_point_2d - left_back_point_2d).norm() < epsilon;

Check warning on line 110 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L110

Added line #L110 was not covered by tests
}

template <typename T>
void pushUniqueVector(T & base_vector, const T & additional_vector)

Check warning on line 114 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L114

Added line #L114 was not covered by tests
{
base_vector.insert(base_vector.end(), additional_vector.begin(), additional_vector.end());

Check warning on line 116 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L116

Added line #L116 was not covered by tests
}

template <typename T>
std::optional<T> getObjectFromUuid(const std::vector<T> & objects, const std::string & target_uuid)
{
Expand Down Expand Up @@ -384,7 +401,7 @@

bool DynamicObstacleAvoidanceModule::canTransitSuccessState()
{
return target_objects_.empty();
return planner_data_->dynamic_object->objects.empty();

Check warning on line 404 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L404

Added line #L404 was not covered by tests
}

BehaviorModuleOutput DynamicObstacleAvoidanceModule::plan()
Expand Down Expand Up @@ -420,10 +437,19 @@
appendExtractedPolygonMarker(debug_marker_, obstacle_poly.value(), object.pose.position.z);
}
}

// generate drivable lanes
DrivableAreaInfo current_drivable_area_info;
current_drivable_area_info.drivable_lanes =
beyzanurkaya marked this conversation as resolved.
Show resolved Hide resolved
getPreviousModuleOutput().drivable_area_info.drivable_lanes;
if (parameters_->expand_drivable_area) {
auto current_lanelets =
getCurrentLanesFromPath(getPreviousModuleOutput().reference_path, planner_data_);
std::for_each(current_lanelets.begin(), current_lanelets.end(), [&](const auto & lanelet) {
current_drivable_area_info.drivable_lanes.push_back(
generateExpandedDrivableLanes(lanelet, planner_data_, parameters_));
});
} else {

Check warning on line 449 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L444-L449

Added lines #L444 - L449 were not covered by tests
current_drivable_area_info.drivable_lanes =
getPreviousModuleOutput().drivable_area_info.drivable_lanes;

Check warning on line 451 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L451

Added line #L451 was not covered by tests
}

Check warning on line 452 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

DynamicObstacleAvoidanceModule::plan increases in cyclomatic complexity from 9 to 10, 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.
current_drivable_area_info.obstacles = obstacles_for_drivable_area;
current_drivable_area_info.enable_expanding_hatched_road_markings =
parameters_->use_hatched_road_markings;
Expand Down Expand Up @@ -1932,4 +1958,164 @@
return {left_avoid_poly, right_avoid_poly};
}

lanelet::ConstLanelets DynamicObstacleAvoidanceModule::getCurrentLanesFromPath(

Check warning on line 1961 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1961

Added line #L1961 was not covered by tests
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data)
{
if (path.points.empty()) {
throw std::logic_error("empty path.");

Check warning on line 1965 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1965

Added line #L1965 was not covered by tests
}

const auto idx = planner_data->findEgoIndex(path.points);

Check warning on line 1968 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1968

Added line #L1968 was not covered by tests

if (path.points.at(idx).lane_ids.empty()) {
throw std::logic_error("empty lane ids.");

Check warning on line 1971 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1971

Added line #L1971 was not covered by tests
}

const auto start_id = path.points.at(idx).lane_ids.front();
const auto start_lane = planner_data->route_handler->getLaneletsFromId(start_id);

Check warning on line 1975 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1974-L1975

Added lines #L1974 - L1975 were not covered by tests
const auto & p = planner_data->parameters;

return planner_data->route_handler->getLaneletSequence(
start_lane, p.backward_path_length, p.forward_path_length);

Check warning on line 1979 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1979

Added line #L1979 was not covered by tests
}

DrivableLanes DynamicObstacleAvoidanceModule::generateExpandedDrivableLanes(

Check warning on line 1982 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1982

Added line #L1982 was not covered by tests
const lanelet::ConstLanelet & lanelet, const std::shared_ptr<const PlannerData> & planner_data,
const std::shared_ptr<DynamicAvoidanceParameters> & parameters)
{
const auto & route_handler = planner_data->route_handler;

Check warning on line 1986 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1986

Added line #L1986 was not covered by tests

DrivableLanes current_drivable_lanes;
current_drivable_lanes.left_lane = lanelet;
current_drivable_lanes.right_lane = lanelet;

Check warning on line 1990 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1988-L1990

Added lines #L1988 - L1990 were not covered by tests

if (parameters->use_lane_type == "current_lane") {
return current_drivable_lanes;
}

const auto use_opposite_lane = parameters->use_lane_type == "opposite_direction_lane";

Check warning on line 1996 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1996

Added line #L1996 was not covered by tests

// 1. get left/right side lanes
const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) {

Check warning on line 1999 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L1999

Added line #L1999 was not covered by tests
const auto all_left_lanelets =
route_handler->getAllLeftSharedLinestringLanelets(target_lane, use_opposite_lane, true);

Check warning on line 2001 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2001

Added line #L2001 was not covered by tests
if (!all_left_lanelets.empty()) {
current_drivable_lanes.left_lane = all_left_lanelets.back(); // leftmost lanelet
pushUniqueVector(
current_drivable_lanes.middle_lanes,
lanelet::ConstLanelets(all_left_lanelets.begin(), all_left_lanelets.end() - 1));

Check warning on line 2006 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2003-L2006

Added lines #L2003 - L2006 were not covered by tests
}
};
const auto update_right_lanelets = [&](const lanelet::ConstLanelet & target_lane) {

Check warning on line 2009 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2008-L2009

Added lines #L2008 - L2009 were not covered by tests
const auto all_right_lanelets =
route_handler->getAllRightSharedLinestringLanelets(target_lane, use_opposite_lane, true);

Check warning on line 2011 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2011

Added line #L2011 was not covered by tests
if (!all_right_lanelets.empty()) {
current_drivable_lanes.right_lane = all_right_lanelets.back(); // rightmost lanelet
pushUniqueVector(
current_drivable_lanes.middle_lanes,
lanelet::ConstLanelets(all_right_lanelets.begin(), all_right_lanelets.end() - 1));

Check warning on line 2016 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2013-L2016

Added lines #L2013 - L2016 were not covered by tests
}
};

Check warning on line 2018 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2018

Added line #L2018 was not covered by tests

update_left_lanelets(lanelet);
update_right_lanelets(lanelet);

Check warning on line 2021 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2020-L2021

Added lines #L2020 - L2021 were not covered by tests

// 2.1 when there are multiple lanes whose previous lanelet is the same
const auto get_next_lanes_from_same_previous_lane =
[&route_handler](const lanelet::ConstLanelet & lane) {

Check warning on line 2025 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2025

Added line #L2025 was not covered by tests
// get previous lane, and return false if previous lane does not exist
lanelet::ConstLanelets prev_lanes;
if (!route_handler->getPreviousLaneletsWithinRoute(lane, &prev_lanes)) {
return lanelet::ConstLanelets{};

Check warning on line 2029 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2029

Added line #L2029 was not covered by tests
}

lanelet::ConstLanelets next_lanes;
for (const auto & prev_lane : prev_lanes) {
const auto next_lanes_from_prev = route_handler->getNextLanelets(prev_lane);
pushUniqueVector(next_lanes, next_lanes_from_prev);

Check warning on line 2035 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2034-L2035

Added lines #L2034 - L2035 were not covered by tests
}
return next_lanes;
};

Check warning on line 2038 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2038

Added line #L2038 was not covered by tests

const auto next_lanes_for_right =
get_next_lanes_from_same_previous_lane(current_drivable_lanes.right_lane);

Check warning on line 2041 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2041

Added line #L2041 was not covered by tests
const auto next_lanes_for_left =
get_next_lanes_from_same_previous_lane(current_drivable_lanes.left_lane);

Check warning on line 2043 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2043

Added line #L2043 was not covered by tests

// 2.2 look for neighbor lane recursively, where end line of the lane is connected to end line
// of the original lane
const auto update_drivable_lanes =
[&](const lanelet::ConstLanelets & next_lanes, const bool is_left) {

Check warning on line 2048 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2048

Added line #L2048 was not covered by tests
for (const auto & next_lane : next_lanes) {
const auto & edge_lane =
is_left ? current_drivable_lanes.left_lane : current_drivable_lanes.right_lane;

Check warning on line 2051 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2050-L2051

Added lines #L2050 - L2051 were not covered by tests
if (next_lane.id() == edge_lane.id()) {
continue;

Check warning on line 2053 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2053

Added line #L2053 was not covered by tests
}

const auto & left_lane = is_left ? next_lane : edge_lane;
const auto & right_lane = is_left ? edge_lane : next_lane;

Check warning on line 2057 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2056-L2057

Added lines #L2056 - L2057 were not covered by tests
if (!isEndPointsConnected(left_lane, right_lane)) {
continue;

Check warning on line 2059 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2059

Added line #L2059 was not covered by tests
}

if (is_left) {
current_drivable_lanes.left_lane = next_lane;
} else {
current_drivable_lanes.right_lane = next_lane;
}

const auto & middle_lanes = current_drivable_lanes.middle_lanes;
const auto has_same_lane = std::any_of(
middle_lanes.begin(), middle_lanes.end(),
[&edge_lane](const auto & lane) { return lane.id() == edge_lane.id(); });

if (!has_same_lane) {
if (is_left) {
if (current_drivable_lanes.right_lane.id() != edge_lane.id()) {
current_drivable_lanes.middle_lanes.push_back(edge_lane);

Check warning on line 2076 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2076

Added line #L2076 was not covered by tests
}
} else {
if (current_drivable_lanes.left_lane.id() != edge_lane.id()) {
current_drivable_lanes.middle_lanes.push_back(edge_lane);

Check warning on line 2080 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2080

Added line #L2080 was not covered by tests
}
}
}

return true;
}
return false;
};

Check warning on line 2088 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2088

Added line #L2088 was not covered by tests

const auto expand_drivable_area_recursively =
[&](const lanelet::ConstLanelets & next_lanes, const bool is_left) {

Check warning on line 2091 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2091

Added line #L2091 was not covered by tests
// NOTE: set max search num to avoid infinity loop for drivable area expansion
constexpr size_t max_recursive_search_num = 3;
for (size_t i = 0; i < max_recursive_search_num; ++i) {
const bool is_update_kept = update_drivable_lanes(next_lanes, is_left);

Check warning on line 2095 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2095

Added line #L2095 was not covered by tests
if (!is_update_kept) {
break;
}
if (i == max_recursive_search_num - 1) {
RCLCPP_DEBUG(

Check warning on line 2100 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2100

Added line #L2100 was not covered by tests
rclcpp::get_logger(logger_namespace), "Drivable area expansion reaches max iteration.");
}
}
};
expand_drivable_area_recursively(next_lanes_for_right, false);
expand_drivable_area_recursively(next_lanes_for_left, true);

Check warning on line 2106 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2104-L2106

Added lines #L2104 - L2106 were not covered by tests

// 3. update again for new left/right lanes
update_left_lanelets(current_drivable_lanes.left_lane);
update_right_lanelets(current_drivable_lanes.right_lane);

Check warning on line 2110 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2109-L2110

Added lines #L2109 - L2110 were not covered by tests

// 4. compensate that current_lane is in either of left_lane, right_lane or middle_lanes.
if (
current_drivable_lanes.left_lane.id() != lanelet.id() &&

Check warning on line 2114 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2114

Added line #L2114 was not covered by tests
current_drivable_lanes.right_lane.id() != lanelet.id()) {
current_drivable_lanes.middle_lanes.push_back(lanelet);

Check warning on line 2116 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp#L2116

Added line #L2116 was not covered by tests
}

return current_drivable_lanes;
}

Check warning on line 2120 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

DynamicObstacleAvoidanceModule::generateExpandedDrivableLanes has a cyclomatic complexity of 24, 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 notice on line 2120 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Bumpy Road Ahead

DynamicObstacleAvoidanceModule::generateExpandedDrivableLanes has 4 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

Check notice on line 2120 in planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Deep, Nested Complexity

DynamicObstacleAvoidanceModule::generateExpandedDrivableLanes has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.
} // namespace autoware::behavior_path_planner
Loading