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(obstacle_cruise_planner): ignore invalid stopping objects #10227

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 @@ -41,7 +41,7 @@ The obstacles meeting the following condition are determined as obstacles for yi

- The object type is for cruising according to `obstacle_filtering.object_type.*` and it is moving with a speed greater than `obstacle_filtering.yield.stopped_obstacle_velocity_threshold`.
- The object is not crossing the ego's trajectory (\*1).
- There is another object of type `obstacle_filtering.object_type.*` stopped in front of the moving obstacle.
- There is another object of type `obstacle_filtering.object_type.side_stopped` stopped in front of the moving obstacle.
- The lateral distance (using the ego's trajectory as reference) between both obstacles is less than `obstacle_filtering.yield.max_lat_dist_between_obstacles`
- Both obstacles, moving and stopped, are within `obstacle_filtering.yield.lat_distance_threshold` and `obstacle_filtering.yield.lat_distance_threshold` + `obstacle_filtering.yield.max_lat_dist_between_obstacles` lateral distance from the ego's trajectory respectively.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,17 @@
bicycle: false
pedestrian: false

# If an object does not have this label, the ego vehicle does not assume that the yielded obstacle will cut in due to the object.
side_stopped:
unknown: false
car: true
truck: true
bus: true
trailer: true
motorcycle: true
bicycle: false
pedestrian: false

max_lat_margin: 1.0 # lateral margin between obstacle and trajectory band with ego's width

# if crossing vehicle is determined as target obstacles or not
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2025 TIER IV, Inc. All rights reserved.

Check notice on line 1 in planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.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 4.62 to 4.50, 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 @@ -517,8 +517,8 @@
longitudinal_distance_between_obstacles / moving_object_speed <
obstacle_filtering_param_.max_obstacles_collision_time;
if (are_obstacles_aligned && obstacles_collide_within_threshold_time) {
const auto yield_obstacle =
create_yield_cruise_obstacle(moving_object, predicted_objects_stamp, traj_points);
const auto yield_obstacle = create_yield_cruise_obstacle(
moving_object, stopped_object, predicted_objects_stamp, traj_points);

Check warning on line 521 in planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp#L521

Added line #L521 was not covered by tests
if (yield_obstacle) {
yield_obstacles.push_back(*yield_obstacle);
using autoware::objects_of_interest_marker_interface::ColorName;
Expand Down Expand Up @@ -703,22 +703,32 @@
}

std::optional<CruiseObstacle> ObstacleCruiseModule::create_yield_cruise_obstacle(
const std::shared_ptr<PlannerData::Object> object, const rclcpp::Time & predicted_objects_stamp,
const std::vector<TrajectoryPoint> & traj_points)
const std::shared_ptr<PlannerData::Object> object,
const std::shared_ptr<PlannerData::Object> stopped_object,
const rclcpp::Time & predicted_objects_stamp, const std::vector<TrajectoryPoint> & traj_points)
{
if (traj_points.empty()) return std::nullopt;
// check label

const auto & obj_uuid = object->predicted_object.object_id;
const auto & obj_uuid_str = autoware_utils::to_hex_string(obj_uuid);

if (!is_outside_cruise_obstacle(object->predicted_object.classification.at(0).label)) {
RCLCPP_DEBUG(
logger_, "[Cruise] Ignore yield obstacle (%s) since its type is not designated.",
obj_uuid_str.substr(0, 4).c_str());
return std::nullopt;
}

if (!is_side_stopped_obstacle(stopped_object->predicted_object.classification.at(0).label)) {
RCLCPP_DEBUG(

Check warning on line 724 in planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp#L724

Added line #L724 was not covered by tests
logger_,
"[Cruise] Ignore yield obstacle (%s) since the corresponding stopped object type is not "
"designated as side_stopped.",
obj_uuid_str.substr(0, 4).c_str());
return std::nullopt;

Check warning on line 729 in planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp#L729

Added line #L729 was not covered by tests
}

Check warning on line 731 in planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

ObstacleCruiseModule::create_yield_cruise_obstacle has a cyclomatic complexity of 9, 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 (
std::hypot(
object->predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x,
Expand Down Expand Up @@ -779,6 +789,12 @@
return std::find(types.begin(), types.end(), label) != types.end();
}

bool ObstacleCruiseModule::is_side_stopped_obstacle(const uint8_t label) const

Check warning on line 792 in planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp#L792

Added line #L792 was not covered by tests
{
const auto & types = obstacle_filtering_param_.side_stopped_object_types;
return std::find(types.begin(), types.end(), label) != types.end();

Check warning on line 795 in planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp#L795

Added line #L795 was not covered by tests
}

bool ObstacleCruiseModule::is_cruise_obstacle(const uint8_t label) const
{
return is_inside_cruise_obstacle(label) || is_outside_cruise_obstacle(label);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,10 +119,12 @@ class ObstacleCruiseModule : public PluginModuleInterface
const bool is_driving_forward, const VehicleInfo & vehicle_info,
const TrajectoryPolygonCollisionCheck & trajectory_polygon_collision_check) const;
std::optional<CruiseObstacle> create_yield_cruise_obstacle(
const std::shared_ptr<PlannerData::Object> object, const rclcpp::Time & predicted_objects_stamp,
const std::vector<TrajectoryPoint> & traj_points);
const std::shared_ptr<PlannerData::Object> object,
const std::shared_ptr<PlannerData::Object> stopped_object,
const rclcpp::Time & predicted_objects_stamp, const std::vector<TrajectoryPoint> & traj_points);
bool is_inside_cruise_obstacle(const uint8_t label) const;
bool is_outside_cruise_obstacle(const uint8_t label) const;
bool is_side_stopped_obstacle(const uint8_t label) const;
bool is_cruise_obstacle(const uint8_t label) const;
bool is_front_collide_obstacle(
const std::vector<TrajectoryPoint> & traj_points,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@
{
std::vector<uint8_t> inside_object_types{};
std::vector<uint8_t> outside_object_types{};
std::vector<uint8_t> side_stopped_object_types{};
// bool use_pointcloud{};

double max_lat_margin{};
Expand Down Expand Up @@ -93,6 +94,8 @@
utils::get_target_object_type(node, "obstacle_cruise.obstacle_filtering.object_type.inside.");
outside_object_types = utils::get_target_object_type(
node, "obstacle_cruise.obstacle_filtering.object_type.outside.");
side_stopped_object_types = utils::get_target_object_type(

Check warning on line 97 in planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/parameters.hpp

View check run for this annotation

Codecov / codecov/patch

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/parameters.hpp#L97

Added line #L97 was not covered by tests
node, "obstacle_cruise.obstacle_filtering.object_type.side_stopped.");
// use_pointcloud = get_or_declare_parameter<bool>(
// node, "obstacle_cruise.obstacle_filtering.object_type.pointcloud");

Expand Down
Loading