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(intersection): check path margin for overshoot vehicles on red light #5394

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 @@ -56,6 +56,8 @@
object_dist_to_stopline: 10.0 # [m]
ignore_on_amber_traffic_light:
object_expected_deceleration: 2.0 # [m/ss]
ignore_on_red_traffic_light:
object_margin_to_path: 2.0

occlusion:
enable: false
Expand Down
6 changes: 6 additions & 0 deletions planning/behavior_velocity_intersection_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,6 +230,12 @@
debug_data_.amber_ignore_targets, "amber_ignore_targets", module_id_, now, 0.0, 1.0, 0.0),
&debug_marker_array, now);

appendMarkerArray(
debug::createObjectsMarkerArray(
debug_data_.red_overshoot_ignore_targets, "red_overshoot_ignore_targets", module_id_, now,
0.0, 1.0, 0.0),
&debug_marker_array, now);

Check warning on line 238 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

IntersectionModule::createDebugMarkerArray already has high cyclomatic complexity, and now it increases in Lines of Code from 95 to 100. 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.
appendMarkerArray(
debug::createObjectsMarkerArray(
debug_data_.stuck_targets, "stuck_targets", module_id_, now, 0.99, 0.99, 0.2),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,9 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
ip.collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration =
getOrDeclareParameter<double>(
node, ns + ".collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration");
ip.collision_detection.ignore_on_red_traffic_light.object_margin_to_path =
getOrDeclareParameter<double>(
node, ns + ".collision_detection.ignore_on_red_traffic_light.object_margin_to_path");

ip.occlusion.enable = getOrDeclareParameter<bool>(node, ns + ".occlusion.enable");
ip.occlusion.occlusion_attention_area_length =
Expand Down
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_intersection_module/src/scene_intersection.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 1695 to 1741, 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_velocity_intersection_module/src/scene_intersection.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 8.08 to 8.35, 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 @@ -30,6 +30,7 @@
#include <boost/geometry/algorithms/intersection.hpp>

#include <lanelet2_core/geometry/LineString.h>
#include <lanelet2_core/geometry/Point.h>
#include <lanelet2_core/geometry/Polygon.h>
#include <lanelet2_core/primitives/BasicRegulatoryElements.h>
#include <lanelet2_core/primitives/LineString.h>
Expand Down Expand Up @@ -1519,18 +1520,64 @@
.object_expected_deceleration));
return dist_to_stop_line > braking_distance;
};

const auto isTolerableOvershoot = [&](const util::TargetObject & target_object) {

Check warning on line 1523 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1523

Added line #L1523 was not covered by tests
if (
!target_object.attention_lanelet || !target_object.dist_to_stop_line ||
!target_object.stop_line) {
return false;
}
const double dist_to_stop_line = target_object.dist_to_stop_line.value();
const double v = target_object.object.kinematics.initial_twist_with_covariance.twist.linear.x;
const double braking_distance =
v * v /
(2.0 * std::fabs(planner_param_.collision_detection.ignore_on_amber_traffic_light
.object_expected_deceleration));

Check warning on line 1534 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1529-L1534

Added lines #L1529 - L1534 were not covered by tests
if (dist_to_stop_line > braking_distance) {
return false;
}
const auto stopline_front = target_object.stop_line.value().front();
const auto stopline_back = target_object.stop_line.value().back();
tier4_autoware_utils::LineString2d object_line;
object_line.emplace_back(

Check warning on line 1541 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1541

Added line #L1541 was not covered by tests
(stopline_front.x() + stopline_back.x()) / 2.0,
(stopline_front.y() + stopline_back.y()) / 2.0);
const auto stopline_mid = object_line.front();
const auto endpoint = target_object.attention_lanelet.value().centerline().back();
object_line.emplace_back(endpoint.x(), endpoint.y());
std::vector<tier4_autoware_utils::Point2d> intersections;
bg::intersection(object_line, ego_lane.centerline2d().basicLineString(), intersections);
if (intersections.empty()) {
return false;
}
const auto collision_point = intersections.front();
// distance from object expected stop position to collision point
const double stopline_to_object = -1.0 * dist_to_stop_line + braking_distance;

Check warning on line 1554 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1554

Added line #L1554 was not covered by tests
const double stopline_to_collision =
std::hypot(collision_point.x() - stopline_mid.x(), collision_point.y() - stopline_mid.y());
const double object2collision = stopline_to_collision - stopline_to_object;
const double margin =

Check warning on line 1558 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1556-L1558

Added lines #L1556 - L1558 were not covered by tests
planner_param_.collision_detection.ignore_on_red_traffic_light.object_margin_to_path;
return (object2collision > margin) || (object2collision < 0);
};

Check warning on line 1561 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1561

Added line #L1561 was not covered by tests
// check collision between predicted_path and ego_area
bool collision_detected = false;
for (const auto & target_object : target_objects->all_attention_objects) {
const auto & object = target_object.object;
// If the vehicle is expected to stop before their stopline, ignore
const bool expected_to_stop_before_stopline = expectedToStopBeforeStopLine(target_object);
if (
traffic_prioritized_level == util::TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED &&
expectedToStopBeforeStopLine(target_object)) {
expected_to_stop_before_stopline) {
debug_data_.amber_ignore_targets.objects.push_back(object);
continue;
}
const bool is_tolerable_overshoot = isTolerableOvershoot(target_object);
if (

Check warning on line 1575 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1575

Added line #L1575 was not covered by tests
traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED &&
!expected_to_stop_before_stopline && is_tolerable_overshoot) {

Check warning on line 1577 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Conditional

IntersectionModule::checkCollision has 2 complex conditionals with 4 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.
debug_data_.red_overshoot_ignore_targets.objects.push_back(object);
continue;

Check warning on line 1579 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1579

Added line #L1579 was not covered by tests
}

Check warning on line 1580 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

IntersectionModule::checkCollision increases in cyclomatic complexity from 26 to 36, 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.
for (const auto & predicted_path : object.kinematics.predicted_paths) {
if (
predicted_path.confidence <
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,10 @@ class IntersectionModule : public SceneModuleInterface
{
double object_expected_deceleration;
} ignore_on_amber_traffic_light;
struct IgnoreOnRedTrafficLight
{
double object_margin_to_path;
} ignore_on_red_traffic_light;
} collision_detection;
struct Occlusion
{
Expand Down
11 changes: 9 additions & 2 deletions planning/behavior_velocity_intersection_module/src/util.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_intersection_module/src/util.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 1191 to 1199, 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_velocity_intersection_module/src/util.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 7.24 to 7.32, 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 @@ -840,10 +840,17 @@
}
result.attention_stop_lines_.push_back(stop_line);
}
result.attention_non_preceding_ = std::move(detection_lanelets);
// TODO(Mamoru Sobue): find stop lines for attention_non_preceding_ if needed
for (unsigned i = 0; i < result.attention_non_preceding_.size(); ++i) {
result.attention_non_preceding_stop_lines_.push_back(std::nullopt);
std::optional<lanelet::ConstLineString3d> stop_line = std::nullopt;
const auto & ll = result.attention_non_preceding_.at(i);
const auto traffic_lights = ll.regulatoryElementsAs<lanelet::TrafficLight>();
for (const auto & traffic_light : traffic_lights) {
const auto stop_line_opt = traffic_light->stopLine();
if (!stop_line_opt) continue;
stop_line = stop_line_opt.get();

Check warning on line 851 in planning/behavior_velocity_intersection_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/util.cpp#L851

Added line #L851 was not covered by tests
}
result.attention_non_preceding_stop_lines_.push_back(stop_line);

Check notice on line 853 in planning/behavior_velocity_intersection_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

getObjectiveLanelets increases from 12 to 13 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.

Check warning on line 853 in planning/behavior_velocity_intersection_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

getObjectiveLanelets increases in cyclomatic complexity from 49 to 52, 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.
}
result.conflicting_ = std::move(conflicting_ex_ego_lanelets);
result.adjacent_ = planning_utils::getConstLaneletsFromIds(lanelet_map_ptr, associative_ids);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ struct DebugData
std::vector<geometry_msgs::msg::Polygon> candidate_collision_object_polygons;
autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets;
autoware_auto_perception_msgs::msg::PredictedObjects amber_ignore_targets;
autoware_auto_perception_msgs::msg::PredictedObjects red_overshoot_ignore_targets;
autoware_auto_perception_msgs::msg::PredictedObjects stuck_targets;
autoware_auto_perception_msgs::msg::PredictedObjects yield_stuck_targets;
std::vector<geometry_msgs::msg::Polygon> occlusion_polygons;
Expand Down
Loading