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): disable stuck detection against private lane #5910

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 @@ -23,8 +23,7 @@
stuck_vehicle_velocity_threshold: 0.833
# enable_front_car_decel_prediction: false
# assumed_front_car_decel: 1.0
timeout_private_area: 3.0
enable_private_area_stuck_disregard: false
disable_against_private_lane: true

yield_stuck:
turn_direction:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,10 +74,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.stuck_vehicle_detect_dist");
ip.stuck_vehicle.stuck_vehicle_velocity_threshold =
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.stuck_vehicle_velocity_threshold");
ip.stuck_vehicle.timeout_private_area =
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.timeout_private_area");
ip.stuck_vehicle.enable_private_area_stuck_disregard =
getOrDeclareParameter<bool>(node, ns + ".stuck_vehicle.enable_private_area_stuck_disregard");
ip.stuck_vehicle.disable_against_private_lane =
getOrDeclareParameter<bool>(node, ns + ".stuck_vehicle.disable_against_private_lane");

ip.yield_stuck.turn_direction.left =
getOrDeclareParameter<bool>(node, ns + ".yield_stuck.turn_direction.left");
Expand Down Expand Up @@ -201,7 +199,6 @@ void IntersectionModuleManager::launchNewModules(
}

const std::string location = ll.attributeOr("location", "else");
const bool is_private_area = (location.compare("private") == 0);
const auto associative_ids =
planning_utils::getAssociativeIntersectionLanelets(ll, lanelet_map, routing_graph);
bool has_traffic_light = false;
Expand All @@ -213,7 +210,7 @@ void IntersectionModuleManager::launchNewModules(
}
const auto new_module = std::make_shared<IntersectionModule>(
module_id, lane_id, planner_data_, intersection_param_, associative_ids, turn_direction,
has_traffic_light, enable_occlusion_detection, is_private_area, node_,
has_traffic_light, enable_occlusion_detection, node_,
logger_.get_child("intersection_module"), clock_);
generateUUID(module_id);
/* set RTC status as non_occluded status initially */
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 1832 to 1834, 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.
//
// 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 @@ -97,8 +97,8 @@
[[maybe_unused]] std::shared_ptr<const PlannerData> planner_data,
const PlannerParam & planner_param, const std::set<lanelet::Id> & associative_ids,
const std::string & turn_direction, const bool has_traffic_light,
const bool enable_occlusion_detection, const bool is_private_area, rclcpp::Node & node,
const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock)
const bool enable_occlusion_detection, rclcpp::Node & node, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock)

Check warning on line 101 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#L101

Added line #L101 was not covered by tests
: SceneModuleInterface(module_id, logger, clock),
node_(node),
lane_id_(lane_id),
Expand All @@ -107,7 +107,6 @@
has_traffic_light_(has_traffic_light),
enable_occlusion_detection_(enable_occlusion_detection),
occlusion_attention_divisions_(std::nullopt),
is_private_area_(is_private_area),
occlusion_uuid_(tier4_autoware_utils::generateUUID())
{
velocity_factor_.init(PlanningBehavior::INTERSECTION);
Expand Down Expand Up @@ -1056,8 +1055,11 @@
// stuck vehicle detection is viable even if attention area is empty
// so this needs to be checked before attention area validation
const bool stuck_detected = checkStuckVehicle(planner_data_, path_lanelets);
const bool is_first_conflicting_lane_private =
(std::string(first_conflicting_lane.attributeOr("location", "else")).compare("private") == 0);
if (stuck_detected) {
if (is_private_area_ && planner_param_.stuck_vehicle.enable_private_area_stuck_disregard) {
if (!(is_first_conflicting_lane_private &&
planner_param_.stuck_vehicle.disable_against_private_lane)) {

Check warning on line 1062 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::modifyPathVelocityDetail already has high cyclomatic complexity, and now it increases in Lines of Code from 381 to 384. 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.
} else {
std::optional<size_t> stopline_idx = std::nullopt;
if (stuck_stopline_idx_opt) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,7 @@ class IntersectionModule : public SceneModuleInterface
bool use_stuck_stopline;
double stuck_vehicle_detect_dist;
double stuck_vehicle_velocity_threshold;
double timeout_private_area;
bool enable_private_area_stuck_disregard;
bool disable_against_private_lane;
} stuck_vehicle;

struct YieldStuck
Expand Down Expand Up @@ -263,8 +262,8 @@ class IntersectionModule : public SceneModuleInterface
const int64_t module_id, const int64_t lane_id, std::shared_ptr<const PlannerData> planner_data,
const PlannerParam & planner_param, const std::set<lanelet::Id> & associative_ids,
const std::string & turn_direction, const bool has_traffic_light,
const bool enable_occlusion_detection, const bool is_private_area, rclcpp::Node & node,
const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock);
const bool enable_occlusion_detection, rclcpp::Node & node, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock);

/**
* @brief plan go-stop velocity at traffic crossing with collision check between reference path
Expand Down Expand Up @@ -314,9 +313,6 @@ class IntersectionModule : public SceneModuleInterface
// vehicles are very slow
std::optional<rclcpp::Time> initial_green_light_observed_time_{std::nullopt};

// for stuck vehicle detection
const bool is_private_area_;

// for RTC
const UUID occlusion_uuid_;
bool occlusion_safety_{true};
Expand Down
Loading