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(lane_change): combine terminal lane change path at waiting approval #6176

Merged
merged 10 commits into from
Jan 30, 2024
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,8 @@ class NormalLaneChange : public LaneChangeBase

LaneChangePath getLaneChangePath() const override;

BehaviorModuleOutput getTerminalLaneChangePath() const override;

BehaviorModuleOutput generateOutput() override;

void extendOutputDrivableArea(BehaviorModuleOutput & output) const override;
Expand Down Expand Up @@ -141,6 +143,10 @@ class NormalLaneChange : public LaneChangeBase
const utils::path_safety_checker::RSSparams rss_params, const bool is_stuck,
const bool check_safety = true) const override;

std::optional<LaneChangePath> calcTerminalLaneChangePath(
const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & target_lanes) const;

TurnSignalInfo calcTurnSignalInfo() const override;

bool isValidPath(const PathWithLaneId & path) const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,8 @@ class LaneChangeBase

virtual LaneChangePath getLaneChangePath() const = 0;

virtual BehaviorModuleOutput getTerminalLaneChangePath() const = 0;

virtual bool isEgoOnPreparePhase() const = 0;

virtual bool isRequiredStop(const bool is_object_coming_from_rear) = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,10 @@ ShiftLine getLaneChangingShiftLine(
const PathWithLaneId & prepare_segment, const PathWithLaneId & target_segment,
const PathWithLaneId & reference_path, const double shift_length);

ShiftLine getLaneChangingShiftLine(
const Pose & lane_changing_start_pose, const Pose & lane_changing_end_pose,
const PathWithLaneId & reference_path, const double shift_length);

PathWithLaneId getReferencePathFromTargetLane(
const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes,
const Pose & lane_changing_start_pose, const double target_lane_length,
Expand Down
18 changes: 6 additions & 12 deletions planning/behavior_path_lane_change_module/src/interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,15 +124,12 @@ BehaviorModuleOutput LaneChangeInterface::plan()
BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()
{
*prev_approved_path_ = getPreviousModuleOutput().path;
module_type_->insertStopPoint(
module_type_->getLaneChangeStatus().current_lanes, *prev_approved_path_);

BehaviorModuleOutput out;
out.path = *prev_approved_path_;
out.reference_path = getPreviousModuleOutput().reference_path;
out.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
out.drivable_area_info = getPreviousModuleOutput().drivable_area_info;
out.turn_signal_info = getCurrentTurnSignalInfo(out.path, out.turn_signal_info);
out = module_type_->getTerminalLaneChangePath();
module_type_->insertStopPoint(module_type_->getLaneChangeStatus().current_lanes, out.path);
out.turn_signal_info =
getCurrentTurnSignalInfo(out.path, getPreviousModuleOutput().turn_signal_info);

const auto & lane_change_debug = module_type_->getDebugData();
for (const auto & [uuid, data] : lane_change_debug.collision_check_objects) {
Expand Down Expand Up @@ -438,16 +435,13 @@ TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo(
const double buffer =
next_lane_change_buffer + min_length_for_turn_signal_activation + base_to_front;
const double path_length = motion_utils::calcArcLength(path.points);
const auto & front_point = path.points.front().point.pose.position;
const size_t & current_nearest_seg_idx =
motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
path.points, current_pose, nearest_dist_threshold, nearest_yaw_threshold);
const double length_front_to_ego = motion_utils::calcSignedArcLength(
path.points, front_point, static_cast<size_t>(0), current_pose.position,
current_nearest_seg_idx);
const double dist_to_terminal = utils::getDistanceToEndOfLane(current_pose, current_lanes);
const auto start_pose =
motion_utils::calcLongitudinalOffsetPose(path.points, 0, std::max(path_length - buffer, 0.0));
if (path_length - length_front_to_ego < buffer && start_pose) {
if (dist_to_terminal - base_to_front < buffer && start_pose) {
// modify turn signal
current_turn_signal_info.desired_start_point = *start_pose;
current_turn_signal_info.desired_end_point = lane_change_path.info.lane_changing_end;
Expand Down
211 changes: 211 additions & 0 deletions planning/behavior_path_lane_change_module/src/scene.cpp
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_lane_change_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 1454 to 1623, 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_lane_change_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.21 to 5.39, 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 @@ -140,6 +140,46 @@
return status_.lane_change_path;
}

BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const

Check warning on line 143 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L143

Added line #L143 was not covered by tests
{
BehaviorModuleOutput output;

Check warning on line 145 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L145

Added line #L145 was not covered by tests

const auto current_lanes = getCurrentLanes();
if (current_lanes.empty()) {
RCLCPP_WARN(logger_, "Current lanes not found!!! Something wrong.");
output.path = prev_module_path_;
output.reference_path = prev_module_reference_path_;
output.drivable_area_info = prev_drivable_area_info_;
output.turn_signal_info = prev_turn_signal_info_;
return output;

Check warning on line 154 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L153-L154

Added lines #L153 - L154 were not covered by tests
}

const auto terminal_path =
calcTerminalLaneChangePath(current_lanes, getLaneChangeLanes(current_lanes, direction_));
if (!terminal_path) {
RCLCPP_WARN(logger_, "Terminal path not found!!!");
output.path = prev_module_path_;
output.reference_path = prev_module_reference_path_;
output.drivable_area_info = prev_drivable_area_info_;
output.turn_signal_info = prev_turn_signal_info_;
return output;

Check warning on line 165 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L164-L165

Added lines #L164 - L165 were not covered by tests
}

output.path = terminal_path->path;
output.reference_path = prev_module_reference_path_;
output.turn_signal_info = updateOutputTurnSignal();

extendOutputDrivableArea(output);

const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info,
planner_data_->parameters.ego_nearest_dist_threshold,

Check warning on line 177 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L175-L177

Added lines #L175 - L177 were not covered by tests
planner_data_->parameters.ego_nearest_yaw_threshold);

return output;
}

Check warning on line 181 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L181

Added line #L181 was not covered by tests

BehaviorModuleOutput NormalLaneChange::generateOutput()
{
BehaviorModuleOutput output;
Expand Down Expand Up @@ -835,6 +875,10 @@
const auto current_pose = getEgoPose();
const auto & route_handler = *getRouteHandler();
const auto & common_parameters = planner_data_->parameters;
const auto shift_intervals =
route_handler.getLateralIntervalsToPreferredLane(current_lanes.back(), direction_);

Check warning on line 879 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L879

Added line #L879 was not covered by tests
const double minimum_lane_change_length =
utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals);

// Guard
if (objects.objects.empty()) {
Expand Down Expand Up @@ -904,6 +948,24 @@
return std::abs(lateral) > (common_parameters.vehicle_width / 2);
};

// ignore object that are ahead of terminal lane change start
{
double distance_to_terminal_from_object = std::numeric_limits<double>::max();
for (const auto & polygon_p : obj_polygon_outer) {
const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0);
Pose polygon_pose;
polygon_pose.position = obj_p;
polygon_pose.orientation = object.kinematics.initial_pose_with_covariance.pose.orientation;

Check warning on line 958 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L957-L958

Added lines #L957 - L958 were not covered by tests
const double dist = utils::getDistanceToEndOfLane(polygon_pose, current_lanes);
if (dist < distance_to_terminal_from_object) {
distance_to_terminal_from_object = dist;
}
}
if (minimum_lane_change_length > distance_to_terminal_from_object) {
continue;

Check warning on line 965 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L965

Added line #L965 was not covered by tests
}
}

Check warning on line 968 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

NormalLaneChange::filterObject increases in cyclomatic complexity from 25 to 29, 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 968 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

NormalLaneChange::filterObject increases from 3 to 4 logical blocks with deeply nested code, threshold is one single 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.
// ignore static object that are behind the ego vehicle
if (obj_velocity_norm < 1.0 && max_dist_ego_to_obj < 0.0) {
continue;
Expand Down Expand Up @@ -1413,6 +1475,151 @@
return false;
}

std::optional<LaneChangePath> NormalLaneChange::calcTerminalLaneChangePath(

Check warning on line 1478 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1478

Added line #L1478 was not covered by tests
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const
{
if (current_lanes.empty() || target_lanes.empty()) {
RCLCPP_WARN(logger_, "target_neighbor_preferred_lane_poly_2d is empty. Not expected.");
return {};
}
const auto & route_handler = *getRouteHandler();

Check warning on line 1485 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1485

Added line #L1485 was not covered by tests
const auto & common_parameters = planner_data_->parameters;

const auto forward_path_length = common_parameters.forward_path_length;

Check warning on line 1488 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1488

Added line #L1488 was not covered by tests
const auto minimum_lane_changing_velocity =
lane_change_parameters_->minimum_lane_changing_velocity;

Check warning on line 1490 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1490

Added line #L1490 was not covered by tests

const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanes.back());

Check warning on line 1492 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1492

Added line #L1492 was not covered by tests

const double lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength(
*lane_change_parameters_,
route_handler.getLateralIntervalsToPreferredLane(current_lanes.back()));

Check warning on line 1496 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1496

Added line #L1496 was not covered by tests
const double next_lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength(
*lane_change_parameters_,
route_handler.getLateralIntervalsToPreferredLane(target_lanes.back()));

Check warning on line 1499 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1499

Added line #L1499 was not covered by tests

const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanes);

Check warning on line 1501 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1501

Added line #L1501 was not covered by tests

const auto sorted_lane_ids =
utils::lane_change::getSortedLaneIds(route_handler, getEgoPose(), current_lanes, target_lanes);

Check warning on line 1504 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1504

Added line #L1504 was not covered by tests

const auto target_neighbor_preferred_lane_poly_2d =
utils::lane_change::getTargetNeighborLanesPolygon(route_handler, current_lanes, type_);
if (target_neighbor_preferred_lane_poly_2d.empty()) {
RCLCPP_WARN(logger_, "target_neighbor_preferred_lane_poly_2d is empty. Not expected.");
return {};
}

// lane changing start getEgoPose() is at the end of prepare segment
const auto current_lane_terminal_point =
lanelet::utils::conversion::toGeomMsgPt(current_lanes.back().centerline3d().back());

double distance_to_terminal_from_goal = 0;
if (is_goal_in_route) {
distance_to_terminal_from_goal =
utils::getDistanceToEndOfLane(route_handler.getGoalPose(), current_lanes);
}

const auto lane_changing_start_pose = motion_utils::calcLongitudinalOffsetPose(
prev_module_path_.points, current_lane_terminal_point,

Check warning on line 1524 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1523-L1524

Added lines #L1523 - L1524 were not covered by tests
-(lane_change_buffer + next_lane_change_buffer + distance_to_terminal_from_goal));

if (!lane_changing_start_pose) {
RCLCPP_WARN(logger_, "Reject: lane changing start pose not found!!!");
return {};
}

const auto target_length_from_lane_change_start_pose = utils::getArcLengthToTargetLanelet(
current_lanes, target_lanes.front(), lane_changing_start_pose.value());

// Check if the lane changing start point is not on the lanes next to target lanes,
if (target_length_from_lane_change_start_pose > 0.0) {
RCLCPP_WARN(logger_, "lane change start getEgoPose() is behind target lanelet!");
return {};
}

const auto shift_length = lanelet::utils::getLateralDistanceToClosestLanelet(
target_lanes, lane_changing_start_pose.value());

const auto [min_lateral_acc, max_lateral_acc] =
lane_change_parameters_->lane_change_lat_acc_map.find(minimum_lane_changing_velocity);

const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk(
shift_length, lane_change_parameters_->lane_changing_lateral_jerk, max_lateral_acc);

const auto target_segment = getTargetSegment(
target_lanes, lane_changing_start_pose.value(), target_lane_length, lane_change_buffer,
minimum_lane_changing_velocity, next_lane_change_buffer);

if (target_segment.points.empty()) {
RCLCPP_WARN(logger_, "Reject: target segment is empty!! something wrong...");
return {};
}

const lanelet::BasicPoint2d lc_start_point(
lane_changing_start_pose->position.x, lane_changing_start_pose->position.y);

const auto target_lane_polygon =
lanelet::utils::getPolygonFromArcLength(target_lanes, 0, std::numeric_limits<double>::max());
const auto target_lane_poly_2d = lanelet::utils::to2D(target_lane_polygon).basicPolygon();

const auto is_valid_start_point =
boost::geometry::covered_by(lc_start_point, target_neighbor_preferred_lane_poly_2d) ||
boost::geometry::covered_by(lc_start_point, target_lane_poly_2d);

Check warning on line 1568 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1568

Added line #L1568 was not covered by tests

LaneChangeInfo lane_change_info;
lane_change_info.longitudinal_acceleration = LaneChangePhaseInfo{0.0, 0.0};
lane_change_info.duration = LaneChangePhaseInfo{0.0, lane_changing_time};
lane_change_info.velocity =

Check warning on line 1573 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1570-L1573

Added lines #L1570 - L1573 were not covered by tests
LaneChangePhaseInfo{minimum_lane_changing_velocity, minimum_lane_changing_velocity};
lane_change_info.length = LaneChangePhaseInfo{0.0, lane_change_buffer};

Check warning on line 1575 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1575

Added line #L1575 was not covered by tests
lane_change_info.current_lanes = current_lanes;
lane_change_info.target_lanes = target_lanes;
lane_change_info.lane_changing_start = lane_changing_start_pose.value();
lane_change_info.lane_changing_end = target_segment.points.front().point.pose;
lane_change_info.lateral_acceleration = max_lateral_acc;
lane_change_info.terminal_lane_changing_velocity = minimum_lane_changing_velocity;

Check warning on line 1581 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1579-L1581

Added lines #L1579 - L1581 were not covered by tests

if (!is_valid_start_point) {
RCLCPP_WARN(
logger_,
"Reject: lane changing points are not inside of the target preferred lanes or its "
"neighbors");
return {};
}

const auto resample_interval = utils::lane_change::calcLaneChangeResampleInterval(
lane_change_buffer, minimum_lane_changing_velocity);
const auto target_lane_reference_path = utils::lane_change::getReferencePathFromTargetLane(
route_handler, target_lanes, lane_changing_start_pose.value(), target_lane_length,
lane_change_buffer, forward_path_length, resample_interval, is_goal_in_route,
next_lane_change_buffer);

if (target_lane_reference_path.points.empty()) {
RCLCPP_WARN(logger_, "Reject: target_lane_reference_path is empty!!");
return {};
}

lane_change_info.shift_line = utils::lane_change::getLaneChangingShiftLine(
lane_changing_start_pose.value(), target_segment.points.front().point.pose,
target_lane_reference_path, shift_length);

auto reference_segment = prev_module_path_;
const double length_to_lane_changing_start = motion_utils::calcSignedArcLength(

Check warning on line 1608 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1608

Added line #L1608 was not covered by tests
reference_segment.points, reference_segment.points.front().point.pose.position,
lane_changing_start_pose->position);
utils::clipPathLength(reference_segment, 0, length_to_lane_changing_start, 0.0);
// remove terminal points because utils::clipPathLength() calculates extra long path
reference_segment.points.pop_back();

Check warning on line 1613 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1613

Added line #L1613 was not covered by tests
reference_segment.points.back().point.longitudinal_velocity_mps = minimum_lane_changing_velocity;

const auto terminal_lane_change_path = utils::lane_change::constructCandidatePath(
lane_change_info, reference_segment, target_segment, target_lane_reference_path,
sorted_lane_ids);

return terminal_lane_change_path;
}

Check warning on line 1621 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

NormalLaneChange::calcTerminalLaneChangePath has a cyclomatic complexity of 11, 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 1621 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/scene.cpp#L1621

Added line #L1621 was not covered by tests

PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
{
const auto & path = status_.lane_change_path;
Expand Down Expand Up @@ -1465,6 +1672,10 @@

TurnSignalInfo turn_signal_info{};

if (path.path.points.empty()) {
return turn_signal_info;
}

// desired start pose = prepare start pose
turn_signal_info.desired_start_point = std::invoke([&]() {
const auto blinker_start_duration = planner_data_->parameters.turn_signal_search_time;
Expand Down
16 changes: 12 additions & 4 deletions planning/behavior_path_lane_change_module/src/utils/utils.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 4.89 to 4.78, 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.

Check notice on line 1 in planning/behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 34.35% to 34.07%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// 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 @@ -412,17 +412,17 @@
return std::min(dist_from_lc_start, target_lane_length - next_lane_change_buffer);
});

if (s_end - s_start < lane_changing_length) {
return PathWithLaneId();
}

RCLCPP_DEBUG(
rclcpp::get_logger("behavior_path_planner")
.get_child("lane_change")
.get_child("util")
.get_child("getReferencePathFromTargetLane"),
"start: %f, end: %f", s_start, s_end);

if (s_end - s_start < lane_changing_length) {
return PathWithLaneId();
}

const auto lane_changing_reference_path =
route_handler.getCenterLinePath(target_lanes, s_start, s_end);

Expand All @@ -437,6 +437,14 @@
const Pose & lane_changing_start_pose = prepare_segment.points.back().point.pose;
const Pose & lane_changing_end_pose = target_segment.points.front().point.pose;

return getLaneChangingShiftLine(
lane_changing_start_pose, lane_changing_end_pose, reference_path, shift_length);

Check warning on line 441 in planning/behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/utils/utils.cpp#L440-L441

Added lines #L440 - L441 were not covered by tests
}

ShiftLine getLaneChangingShiftLine(

Check warning on line 444 in planning/behavior_path_lane_change_module/src/utils/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_lane_change_module/src/utils/utils.cpp#L444

Added line #L444 was not covered by tests
const Pose & lane_changing_start_pose, const Pose & lane_changing_end_pose,
const PathWithLaneId & reference_path, const double shift_length)
{
ShiftLine shift_line;
shift_line.end_shift_length = shift_length;
shift_line.start = lane_changing_start_pose;
Expand Down
Loading