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): consider abnormal violating vehicles #6433

Closed
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
7 changes: 7 additions & 0 deletions planning/behavior_velocity_intersection_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -291,6 +291,13 @@
&debug_marker_array);
}

if (debug_data_.yield_area) {
appendMarkerArray(
::createLaneletPolygonsMarkerArray(
debug_data_.yield_area.value(), "yield_area", lane_id_, 0.6588235, 0.34509, 0.6588235),
&debug_marker_array);
}

Check warning on line 300 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 increases in cyclomatic complexity from 21 to 22, 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.
if (debug_data_.ego_lane) {
appendMarkerArray(
::createLaneletPolygonsMarkerArray(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,20 +52,29 @@ struct IntersectionLanelets
{
return is_prioritized_ ? attention_non_preceding_stoplines_ : attention_stoplines_;
}
const lanelet::ConstLanelets & attention_non_preceding() const
{
return attention_non_preceding_;
}
const lanelet::ConstLanelets & conflicting() const { return conflicting_; }
const lanelet::ConstLanelets & adjacent() const { return adjacent_; }
const lanelet::ConstLanelets & occlusion_attention() const
{
return is_prioritized_ ? attention_non_preceding_ : occlusion_attention_;
}
const lanelet::ConstLanelets & attention_non_preceding() const
const lanelet::ConstLanelets & yield() const { return yield_; }
const std::vector<std::optional<lanelet::ConstLineString3d>> & yield_stoplines() const
{
return attention_non_preceding_;
return yield_stoplines_;
}
const std::vector<lanelet::CompoundPolygon3d> & attention_area() const
{
return is_prioritized_ ? attention_non_preceding_area_ : attention_area_;
}
const std::optional<lanelet::CompoundPolygon3d> & first_attention_area() const
{
return first_attention_area_;
}
const std::vector<lanelet::CompoundPolygon3d> & conflicting_area() const
{
return conflicting_area_;
Expand All @@ -75,6 +84,7 @@ struct IntersectionLanelets
{
return occlusion_attention_area_;
}
const std::vector<lanelet::CompoundPolygon3d> & yield_area() const { return yield_area_; }
const std::optional<lanelet::ConstLanelet> & first_conflicting_lane() const
{
return first_conflicting_lane_;
Expand All @@ -87,10 +97,6 @@ struct IntersectionLanelets
{
return first_attention_lane_;
}
const std::optional<lanelet::CompoundPolygon3d> & first_attention_area() const
{
return first_attention_area_;
}
const std::optional<lanelet::ConstLanelet> & second_attention_lane() const
{
return second_attention_lane_;
Expand All @@ -103,48 +109,55 @@ struct IntersectionLanelets
/**
* the set of attention lanelets which is topologically merged
*/
lanelet::ConstLanelets attention_;
std::vector<lanelet::CompoundPolygon3d> attention_area_;
lanelet::ConstLanelets attention_{};
std::vector<lanelet::CompoundPolygon3d> attention_area_{};

/**
* the stop lines for each attention_lanelets associated with traffic lights. At intersection
* without traffic lights, each value is null
*/
std::vector<std::optional<lanelet::ConstLineString3d>> attention_stoplines_;
std::vector<std::optional<lanelet::ConstLineString3d>> attention_stoplines_{};

/**
* the conflicting part of attention lanelets
*/
lanelet::ConstLanelets attention_non_preceding_;
std::vector<lanelet::CompoundPolygon3d> attention_non_preceding_area_;
lanelet::ConstLanelets attention_non_preceding_{};
std::vector<lanelet::CompoundPolygon3d> attention_non_preceding_area_{};

/**
* the stop lines for each attention_non_preceding_
*/
std::vector<std::optional<lanelet::ConstLineString3d>> attention_non_preceding_stoplines_;
std::vector<std::optional<lanelet::ConstLineString3d>> attention_non_preceding_stoplines_{};

/**
* the conflicting lanelets of the objective intersection lanelet
*/
lanelet::ConstLanelets conflicting_;
std::vector<lanelet::CompoundPolygon3d> conflicting_area_;
lanelet::ConstLanelets conflicting_{};
std::vector<lanelet::CompoundPolygon3d> conflicting_area_{};

/**
*
*/
lanelet::ConstLanelets adjacent_;
std::vector<lanelet::CompoundPolygon3d> adjacent_area_;
lanelet::ConstLanelets adjacent_{};
std::vector<lanelet::CompoundPolygon3d> adjacent_area_{};

/**
* the set of attention lanelets for occlusion detection which is topologically merged
*/
lanelet::ConstLanelets occlusion_attention_;
std::vector<lanelet::CompoundPolygon3d> occlusion_attention_area_;
lanelet::ConstLanelets occlusion_attention_{};
std::vector<lanelet::CompoundPolygon3d> occlusion_attention_area_{};

/**
* the set of lanelets that the objective intersection lanelet has RightOfWay over
*/
lanelet::ConstLanelets yield_{};
std::vector<std::optional<lanelet::ConstLineString3d>> yield_stoplines_{};
std::vector<lanelet::CompoundPolygon3d> yield_area_{};

/**
* the vector of sum of each occlusion_attention lanelet
*/
std::vector<double> occlusion_attention_size_;
std::vector<double> occlusion_attention_size_{};

/**
* the first conflicting lanelet which ego path points intersect for the first time
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -197,38 +197,47 @@
}

std::shared_ptr<ObjectInfo> ObjectInfoManager::registerObject(
const unique_identifier_msgs::msg::UUID & uuid, const bool belong_attention_area,
const bool belong_intersection_area, const bool is_parked_vehicle)
const unique_identifier_msgs::msg::UUID & uuid, const bool belong_violating_area,
const bool belong_attention_area, const bool belong_intersection_area,
const bool is_parked_vehicle)
{
if (objects_info_.count(uuid) == 0) {
auto object = std::make_shared<intersection::ObjectInfo>(uuid);
objects_info_[uuid] = object;
}
auto object = objects_info_[uuid];
if (belong_attention_area) {
attention_area_objects_.push_back(object);
} else if (belong_intersection_area) {
intersection_area_objects_.push_back(object);
}
if (is_parked_vehicle) {
parked_objects_.push_back(object);
if (belong_violating_area) {
violating_objects_.push_back(object);
} else {
if (belong_attention_area) {
attention_area_objects_.push_back(object);
} else if (belong_intersection_area) {
intersection_area_objects_.push_back(object);
}
if (is_parked_vehicle) {
parked_objects_.push_back(object);
}

Check notice on line 219 in planning/behavior_velocity_intersection_module/src/object_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Excess Number of Function Arguments

ObjectInfoManager::registerObject has 5 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.
}
return object;
}

void ObjectInfoManager::registerExistingObject(
const unique_identifier_msgs::msg::UUID & uuid, const bool belong_attention_area,
const bool belong_intersection_area, const bool is_parked_vehicle,
std::shared_ptr<intersection::ObjectInfo> object)
const unique_identifier_msgs::msg::UUID & uuid, const bool belong_violating_area,
const bool belong_attention_area, const bool belong_intersection_area,
const bool is_parked_vehicle, std::shared_ptr<intersection::ObjectInfo> object)
{
objects_info_[uuid] = object;
if (belong_attention_area) {
attention_area_objects_.push_back(object);
} else if (belong_intersection_area) {
intersection_area_objects_.push_back(object);
}
if (is_parked_vehicle) {
parked_objects_.push_back(object);
if (belong_violating_area) {
violating_objects_.push_back(object);
} else {
if (belong_attention_area) {
attention_area_objects_.push_back(object);
} else if (belong_intersection_area) {
intersection_area_objects_.push_back(object);
}
if (is_parked_vehicle) {
parked_objects_.push_back(object);
}

Check notice on line 240 in planning/behavior_velocity_intersection_module/src/object_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Excess Number of Function Arguments

ObjectInfoManager::registerExistingObject increases from 5 to 6 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.
}
}

Expand All @@ -240,7 +249,7 @@
parked_objects_.clear();
};

std::vector<std::shared_ptr<ObjectInfo>> ObjectInfoManager::allObjects() const
std::vector<std::shared_ptr<ObjectInfo>> ObjectInfoManager::allAttentionObjects() const
{
std::vector<std::shared_ptr<ObjectInfo>> all_objects = attention_area_objects_;
all_objects.insert(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -229,12 +229,12 @@ class ObjectInfoManager
{
public:
std::shared_ptr<ObjectInfo> registerObject(
const unique_identifier_msgs::msg::UUID & uuid, const bool belong_attention_area,
const bool belong_intersection_area, const bool is_parked);
const unique_identifier_msgs::msg::UUID & uuid, const bool belong_violating_area,
const bool belong_attention_area, const bool belong_intersection_area, const bool is_parked);

void registerExistingObject(
const unique_identifier_msgs::msg::UUID & uuid, const bool belong_attention_area,
const bool belong_intersection_area, const bool is_parked,
const unique_identifier_msgs::msg::UUID & uuid, const bool belong_violating_area,
const bool belong_attention_area, const bool belong_intersection_area, const bool is_parked,
std::shared_ptr<intersection::ObjectInfo> object);

void clearObjects();
Expand All @@ -244,9 +244,17 @@ class ObjectInfoManager
return attention_area_objects_;
}

const std::vector<std::shared_ptr<ObjectInfo>> & parkedObjects() const { return parked_objects_; }
const std::vector<std::shared_ptr<ObjectInfo>> & parkedAttentionObjects() const
{
return parked_objects_;
}

const std::vector<std::shared_ptr<ObjectInfo>> & violatingObjects() const
{
return violating_objects_;
}

std::vector<std::shared_ptr<ObjectInfo>> allObjects() const;
std::vector<std::shared_ptr<ObjectInfo>> allAttentionObjects() const;

const std::unordered_map<unique_identifier_msgs::msg::UUID, std::shared_ptr<ObjectInfo>> &
getObjectsMap()
Expand Down Expand Up @@ -275,6 +283,9 @@ class ObjectInfoManager
//! parked objects on attention_area/intersection_area
std::vector<std::shared_ptr<ObjectInfo>> parked_objects_;

//! objects violating right of way
std::vector<std::shared_ptr<ObjectInfo>> violating_objects_;

std::optional<rclcpp::Time> passed_1st_judge_line_first_time_{std::nullopt};
std::optional<rclcpp::Time> passed_2nd_judge_line_first_time_{std::nullopt};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -224,6 +224,7 @@ class IntersectionModule : public SceneModuleInterface
std::optional<lanelet::CompoundPolygon3d> ego_lane{std::nullopt};
std::optional<geometry_msgs::msg::Polygon> stuck_vehicle_detect_area{std::nullopt};
std::optional<std::vector<lanelet::CompoundPolygon3d>> yield_stuck_detect_area{std::nullopt};
std::optional<std::vector<lanelet::CompoundPolygon3d>> yield_area{std::nullopt};

std::optional<geometry_msgs::msg::Polygon> candidate_collision_ego_lane_polygon{std::nullopt};
autoware_auto_perception_msgs::msg::PredictedObjects safe_under_traffic_control_targets;
Expand Down Expand Up @@ -558,10 +559,7 @@ class IntersectionModule : public SceneModuleInterface
/**
* @brief generate IntersectionLanelets
*/
intersection::IntersectionLanelets generateObjectiveLanelets(
lanelet::LaneletMapConstPtr lanelet_map_ptr,
lanelet::routing::RoutingGraphPtr routing_graph_ptr,
const lanelet::ConstLanelet assigned_lanelet) const;
intersection::IntersectionLanelets generateObjectiveLanelets() const;

/**
* @brief generate PathLanelets
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 Tier IV, Inc.

Check notice on line 1 in planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Function Size

The median function size increase from 59.0 to 66.0 LOC, threshold = 50.0. This file contains overly long functions, measured by their lines of code.

Check notice on line 1 in planning/behavior_velocity_intersection_module/src/scene_intersection_collision.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 15.10 to 15.00, 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 @@ -74,67 +74,84 @@
const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr();
const auto & assigned_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id_);
const auto intersection_area = util::getIntersectionArea(assigned_lanelet, lanelet_map_ptr);
const auto & violating_lanelets = intersection_lanelets.yield();
const auto & violating_stoplines = intersection_lanelets.yield_stoplines();

// ==========================================================================================
// entries that are not observed in this iteration need to be cleared
//
// NOTE: old_map is not referenced because internal data of object_info_manager is cleared
// ==========================================================================================
const auto old_map = object_info_manager_.getObjectsMap();
object_info_manager_.clearObjects();

for (const auto & predicted_object : planner_data_->predicted_objects->objects) {
if (!isTargetCollisionVehicleType(predicted_object)) {
continue;
}

// ==========================================================================================
// NOTE: is_parked_vehicle is used because sometimes slow vehicle direction is
// incorrect/reversed/flipped due to tracking. if is_parked_vehicle is true, object direction
// is not checked
// ==========================================================================================
const auto object_direction =
util::getObjectPoseWithVelocityDirection(predicted_object.kinematics);
const auto is_parked_vehicle =
std::fabs(predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x) <
planner_param_.occlusion.ignore_parked_vehicle_speed_threshold;

const auto belong_adjacent_lanelet_id =
checkAngleForTargetLanelets(object_direction, adjacent_lanelets, false);
if (belong_adjacent_lanelet_id) {
continue;
}
const auto belong_attention_lanelet_id =
checkAngleForTargetLanelets(object_direction, attention_lanelets, is_parked_vehicle);
const auto & obj_pos = predicted_object.kinematics.initial_pose_with_covariance.pose.position;
const bool in_intersection_area = [&]() {
if (!intersection_area) {
return false;
}
return bg::within(
tier4_autoware_utils::Point2d{obj_pos.x, obj_pos.y}, intersection_area.value());
}();

std::optional<lanelet::ConstLanelet> attention_lanelet{std::nullopt};
std::optional<lanelet::ConstLineString3d> stopline{std::nullopt};
if (!belong_attention_lanelet_id && !in_intersection_area) {
continue;
} else if (belong_attention_lanelet_id) {
const auto idx = belong_attention_lanelet_id.value();
attention_lanelet = attention_lanelets.at(idx);
stopline = attention_lanelet_stoplines.at(idx);

const auto belong_violating_lanelet_id = checkAngleForTargetLanelets(
object_direction, violating_lanelets, false /* if is_parked, it is negligible */);
bool is_violating_vehicle{false};
if (belong_violating_lanelet_id) {
const auto idx = belong_violating_lanelet_id.value();
attention_lanelet = violating_lanelets.at(idx);
stopline = violating_stoplines.at(idx);
is_violating_vehicle = true;
}

std::optional<size_t> belong_attention_lanelet_id{std::nullopt};
bool in_intersection_area{false};
if (!is_violating_vehicle) {
belong_attention_lanelet_id =
checkAngleForTargetLanelets(object_direction, attention_lanelets, is_parked_vehicle);
in_intersection_area = [&]() {
const auto & obj_pos =
predicted_object.kinematics.initial_pose_with_covariance.pose.position;
if (!intersection_area) {
return false;
}
return bg::within(
tier4_autoware_utils::Point2d{obj_pos.x, obj_pos.y}, intersection_area.value());
}();
if (belong_attention_lanelet_id) {
const auto idx = belong_attention_lanelet_id.value();
attention_lanelet = attention_lanelets.at(idx);
stopline = attention_lanelet_stoplines.at(idx);
}
}

const auto object_it = old_map.find(predicted_object.object_id);
if (object_it != old_map.end()) {
auto object_info = object_it->second;
object_info_manager_.registerExistingObject(
predicted_object.object_id, belong_attention_lanelet_id.has_value(), in_intersection_area,
is_parked_vehicle, object_info);
predicted_object.object_id, is_violating_vehicle, belong_attention_lanelet_id.has_value(),
in_intersection_area, is_parked_vehicle, object_info);
object_info->initialize(predicted_object, attention_lanelet, stopline);
} else {
auto object_info = object_info_manager_.registerObject(
predicted_object.object_id, belong_attention_lanelet_id.has_value(), in_intersection_area,
is_parked_vehicle);
predicted_object.object_id, is_violating_vehicle, belong_attention_lanelet_id.has_value(),
in_intersection_area, is_parked_vehicle);

Check notice on line 154 in planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

IntersectionModule::updateObjectInfoManagerArea decreases in cyclomatic complexity from 12 to 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 154 in planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

IntersectionModule::updateObjectInfoManagerArea 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.
object_info->initialize(predicted_object, attention_lanelet, stopline);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
// re-use attention_mask
attention_mask = cv::Mat(width, height, CV_8UC1, cv::Scalar(0));
// (3.1) draw all cells on attention_mask behind blocking vehicles as not occluded
const auto & blocking_attention_objects = object_info_manager_.parkedObjects();
const auto & blocking_attention_objects = object_info_manager_.parkedAttentionObjects();
for (const auto & blocking_attention_object_info : blocking_attention_objects) {
debug_data_.parked_targets.objects.push_back(
blocking_attention_object_info->predicted_object());
Expand Down Expand Up @@ -403,7 +403,7 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
LineString2d ego_occlusion_line;
ego_occlusion_line.emplace_back(current_pose.position.x, current_pose.position.y);
ego_occlusion_line.emplace_back(nearest_occlusion_point.point.x, nearest_occlusion_point.point.y);
for (const auto & attention_object_info : object_info_manager_.allObjects()) {
for (const auto & attention_object_info : object_info_manager_.allAttentionObjects()) {
const auto obj_poly =
tier4_autoware_utils::toPolygon2d(attention_object_info->predicted_object());
if (bg::intersects(obj_poly, ego_occlusion_line)) {
Expand Down
Loading
Loading