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

fix(lane_change): orientation check when constructing path #6339

Merged
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
16 changes: 16 additions & 0 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 worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.78 to 4.86, 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 @@ -23,6 +23,7 @@
#include "behavior_path_planner_common/utils/path_utils.hpp"
#include "behavior_path_planner_common/utils/utils.hpp"
#include "object_recognition_utils/predicted_path_utils.hpp"
#include "tier4_autoware_utils/math/unit_conversion.hpp"

#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
Expand All @@ -40,7 +41,9 @@
#include <tf2_ros/transform_listener.h>

#include <algorithm>
#include <iterator>
#include <limits>
#include <optional>
#include <string>
#include <vector>

Expand Down Expand Up @@ -385,6 +388,19 @@
return std::nullopt;
}

if (prepare_segment.points.size() > 1 && shifted_path.path.points.size() > 1) {
const auto & prepare_segment_second_last_point =
std::prev(prepare_segment.points.end() - 1)->point.pose;
const auto & lane_change_start_from_shifted =
std::next(shifted_path.path.points.begin())->point.pose;
const auto yaw_diff2 = std::abs(tier4_autoware_utils::normalizeRadian(

Check warning on line 396 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#L396

Added line #L396 was not covered by tests
tf2::getYaw(prepare_segment_second_last_point.orientation) -
tf2::getYaw(lane_change_start_from_shifted.orientation)));
if (yaw_diff2 > tier4_autoware_utils::deg2rad(5.0)) {
return std::nullopt;

Check warning on line 400 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#L400

Added line #L400 was not covered by tests
}
}

Check warning on line 403 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 worse: Complex Method

constructCandidatePath increases in cyclomatic complexity from 9 to 12, 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 403 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)

❌ New issue: Bumpy Road Ahead

constructCandidatePath has 2 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.
candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path);
candidate_path.shifted_path = shifted_path;

Expand Down
Loading