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(intersection): divide source files and modifyPathVelocity #6134

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
9 changes: 7 additions & 2 deletions planning/behavior_velocity_intersection_module/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,16 @@ pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml)
find_package(OpenCV REQUIRED)

ament_auto_add_library(${PROJECT_NAME} SHARED
src/debug.cpp
src/manager.cpp
src/util.cpp
src/scene_intersection.cpp
src/intersection_lanelets.cpp
src/scene_intersection_prepare_data.cpp
src/scene_intersection_stuck.cpp
src/scene_intersection_occlusion.cpp
src/scene_intersection_collision.cpp
src/scene_merge_from_private_road.cpp
src/util.cpp
src/debug.cpp
)

target_link_libraries(${PROJECT_NAME}
Expand Down
203 changes: 203 additions & 0 deletions planning/behavior_velocity_intersection_module/src/decision_result.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,203 @@
// Copyright 2024 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DECISION_RESULT_HPP_
#define DECISION_RESULT_HPP_

#include <optional>
#include <string>
#include <variant>

namespace behavior_velocity_planner::intersection
{

/**
* @struct
* @brief Internal error or ego already passed pass_judge_line
*/
struct Indecisive
{
std::string error;
};

/**
* @struct
* @brief detected stuck vehicle
*/
struct StuckStop
{
size_t closest_idx{0};
size_t stuck_stopline_idx{0};
std::optional<size_t> occlusion_stopline_idx{std::nullopt};
};

/**
* @struct
* @brief yielded by vehicle on the attention area
*/
struct YieldStuckStop
{
size_t closest_idx{0};
size_t stuck_stopline_idx{0};
};

/**
* @struct
* @brief only collision is detected
*/
struct NonOccludedCollisionStop
{
size_t closest_idx{0};
size_t collision_stopline_idx{0};
size_t occlusion_stopline_idx{0};
};

/**
* @struct
* @brief occlusion is detected so ego needs to stop at the default stop line position
*/
struct FirstWaitBeforeOcclusion
{
bool is_actually_occlusion_cleared{false};
size_t closest_idx{0};
size_t first_stopline_idx{0};
size_t occlusion_stopline_idx{0};
};

/**
* @struct
* @brief ego is approaching the boundary of attention area in the presence of traffic light
*/
struct PeekingTowardOcclusion
{
//! if intersection_occlusion is disapproved externally through RTC, it indicates
//! "is_forcefully_occluded"
bool is_actually_occlusion_cleared{false};
bool temporal_stop_before_attention_required{false};
size_t closest_idx{0};
size_t collision_stopline_idx{0};
size_t first_attention_stopline_idx{0};
size_t occlusion_stopline_idx{0};
//! if null, it is dynamic occlusion and shows up intersection_occlusion(dyn). if valid, it
//! contains the remaining time to release the static occlusion stuck and shows up
//! intersection_occlusion(x.y)
std::optional<double> static_occlusion_timeout{std::nullopt};
};

/**
* @struct
* @brief both collision and occlusion are detected in the presence of traffic light
*/
struct OccludedCollisionStop
{
bool is_actually_occlusion_cleared{false};
bool temporal_stop_before_attention_required{false};
size_t closest_idx{0};
size_t collision_stopline_idx{0};
size_t first_attention_stopline_idx{0};
size_t occlusion_stopline_idx{0};
//! if null, it is dynamic occlusion and shows up intersection_occlusion(dyn). if valid, it
//! contains the remaining time to release the static occlusion stuck
std::optional<double> static_occlusion_timeout{std::nullopt};
};

/**
* @struct
* @brief at least occlusion is detected in the absence of traffic light
*/
struct OccludedAbsenceTrafficLight
{
bool is_actually_occlusion_cleared{false};
bool collision_detected{false};
bool temporal_stop_before_attention_required{false};
size_t closest_idx{0};
size_t first_attention_area_stopline_idx{0};
size_t peeking_limit_line_idx{0};
};

/**
* @struct
* @brief both collision and occlusion are not detected
*/
struct Safe
{
size_t closest_idx{0};
size_t collision_stopline_idx{0};
size_t occlusion_stopline_idx{0};
};

/**
* @struct
* @brief traffic light is red or arrow signal
*/
struct FullyPrioritized
{
bool collision_detected{false};
size_t closest_idx{0};
size_t collision_stopline_idx{0};
size_t occlusion_stopline_idx{0};
};

using DecisionResult = std::variant<
Indecisive, //! internal process error, or over the pass judge line
StuckStop, //! detected stuck vehicle
YieldStuckStop, //! detected yield stuck vehicle
NonOccludedCollisionStop, //! detected collision while FOV is clear
FirstWaitBeforeOcclusion, //! stop for a while before peeking to occlusion
PeekingTowardOcclusion, //! peeking into occlusion while collision is not detected
OccludedCollisionStop, //! occlusion and collision are both detected
OccludedAbsenceTrafficLight, //! occlusion is detected in the absence of traffic light
Safe, //! judge as safe
FullyPrioritized //! only detect vehicles violating traffic rules
>;

inline std::string formatDecisionResult(const DecisionResult & decision_result)
{
if (std::holds_alternative<Indecisive>(decision_result)) {
const auto indecisive = std::get<Indecisive>(decision_result);
return "Indecisive because " + indecisive.error;
}
if (std::holds_alternative<StuckStop>(decision_result)) {
return "StuckStop";

Check warning on line 172 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L172

Added line #L172 was not covered by tests
}
if (std::holds_alternative<YieldStuckStop>(decision_result)) {
return "YieldStuckStop";

Check warning on line 175 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L175

Added line #L175 was not covered by tests
}
if (std::holds_alternative<NonOccludedCollisionStop>(decision_result)) {
return "NonOccludedCollisionStop";

Check warning on line 178 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L178

Added line #L178 was not covered by tests
}
if (std::holds_alternative<FirstWaitBeforeOcclusion>(decision_result)) {
return "FirstWaitBeforeOcclusion";

Check warning on line 181 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L181

Added line #L181 was not covered by tests
}
if (std::holds_alternative<PeekingTowardOcclusion>(decision_result)) {
return "PeekingTowardOcclusion";

Check warning on line 184 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L184

Added line #L184 was not covered by tests
}
if (std::holds_alternative<OccludedCollisionStop>(decision_result)) {
return "OccludedCollisionStop";

Check warning on line 187 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L187

Added line #L187 was not covered by tests
}
if (std::holds_alternative<OccludedAbsenceTrafficLight>(decision_result)) {
return "OccludedAbsenceTrafficLight";

Check warning on line 190 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L190

Added line #L190 was not covered by tests
}
if (std::holds_alternative<Safe>(decision_result)) {
return "Safe";

Check warning on line 193 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L193

Added line #L193 was not covered by tests
}
if (std::holds_alternative<FullyPrioritized>(decision_result)) {
return "FullyPrioritized";

Check warning on line 196 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L196

Added line #L196 was not covered by tests
}
return "";

Check warning on line 198 in planning/behavior_velocity_intersection_module/src/decision_result.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/decision_result.hpp#L198

Added line #L198 was not covered by tests
}

} // namespace behavior_velocity_planner::intersection

#endif // DECISION_RESULT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,26 +12,18 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef UTIL_TYPE_HPP_
#define UTIL_TYPE_HPP_
#ifndef INTERPOLATED_PATH_INFO_HPP_
#define INTERPOLATED_PATH_INFO_HPP_

#include <tier4_autoware_utils/geometry/geometry.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/polygon.hpp>
#include <geometry_msgs/msg/pose.hpp>

#include <lanelet2_core/primitives/CompoundPolygon.h>
#include <lanelet2_core/primitives/Lanelet.h>
#include <lanelet2_core/Forward.h>

#include <optional>
#include <set>
#include <utility>
#include <vector>

namespace behavior_velocity_planner::util
namespace behavior_velocity_planner::intersection
{

/**
Expand All @@ -52,6 +44,6 @@ struct InterpolatedPathInfo
std::optional<std::pair<size_t, size_t>> lane_id_interval{std::nullopt};
};

} // namespace behavior_velocity_planner::util
} // namespace behavior_velocity_planner::intersection

#endif // UTIL_TYPE_HPP_
#endif // INTERPOLATED_PATH_INFO_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
// Copyright 2024 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "intersection_lanelets.hpp"

#include "util.hpp"

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

#include <string>

namespace behavior_velocity_planner::intersection
{

void IntersectionLanelets::update(

Check warning on line 27 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L27

Added line #L27 was not covered by tests
const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info,
const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length,
lanelet::routing::RoutingGraphPtr routing_graph_ptr)
{
is_prioritized_ = is_prioritized;
// find the first conflicting/detection area polygon intersecting the path
if (!first_conflicting_area_) {
auto first = util::getFirstPointInsidePolygonsByFootprint(
conflicting_area_, interpolated_path_info, footprint, vehicle_length);

Check warning on line 36 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L36

Added line #L36 was not covered by tests
if (first) {
first_conflicting_lane_ = conflicting_.at(first.value().second);
first_conflicting_area_ = conflicting_area_.at(first.value().second);

Check warning on line 39 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L38-L39

Added lines #L38 - L39 were not covered by tests
}
}
if (!first_attention_area_) {
const auto first = util::getFirstPointInsidePolygonsByFootprint(
attention_non_preceding_area_, interpolated_path_info, footprint, vehicle_length);

Check warning on line 44 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L44

Added line #L44 was not covered by tests
if (first) {
first_attention_lane_ = attention_non_preceding_.at(first.value().second);
first_attention_area_ = attention_non_preceding_area_.at(first.value().second);

Check warning on line 47 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L46-L47

Added lines #L46 - L47 were not covered by tests
}
}
if (first_attention_lane_ && !second_attention_lane_ && !second_attention_lane_empty_) {

Check warning on line 50 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Conditional

IntersectionLanelets::update has 1 complex conditionals with 2 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
const auto first_attention_lane = first_attention_lane_.value();
// remove first_attention_area_ and non-straight lanelets from attention_non_preceding
lanelet::ConstLanelets attention_non_preceding_ex_first;
lanelet::ConstLanelets sibling_first_attention_lanelets;
for (const auto & previous : routing_graph_ptr->previous(first_attention_lane)) {
for (const auto & following : routing_graph_ptr->following(previous)) {
sibling_first_attention_lanelets.push_back(following);
}
}

Check warning on line 59 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L58-L59

Added lines #L58 - L59 were not covered by tests
for (const auto & ll : attention_non_preceding_) {
// the sibling lanelets of first_attention_lanelet are ruled out
if (lanelet::utils::contains(sibling_first_attention_lanelets, ll)) {
continue;

Check warning on line 63 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L63

Added line #L63 was not covered by tests
}
if (std::string(ll.attributeOr("turn_direction", "else")).compare("straight") == 0) {
attention_non_preceding_ex_first.push_back(ll);
}
}
if (attention_non_preceding_ex_first.empty()) {
second_attention_lane_empty_ = true;

Check warning on line 70 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L70

Added line #L70 was not covered by tests
}
const auto attention_non_preceding_ex_first_area =
util::getPolygon3dFromLanelets(attention_non_preceding_ex_first);
const auto second = util::getFirstPointInsidePolygonsByFootprint(
attention_non_preceding_ex_first_area, interpolated_path_info, footprint, vehicle_length);
if (second) {
second_attention_lane_ = attention_non_preceding_ex_first.at(second.value().second);
second_attention_area_ = second_attention_lane_.value().polygon3d();
}
}
}

Check warning on line 81 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

IntersectionLanelets::update has a cyclomatic complexity of 16, 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 81 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

IntersectionLanelets::update 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 warning on line 81 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Excess Number of Function Arguments

IntersectionLanelets::update has 5 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.

Check warning on line 81 in planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp#L80-L81

Added lines #L80 - L81 were not covered by tests
} // namespace behavior_velocity_planner::intersection
Loading
Loading