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(obstacle_cruise_planner): yield function for ocp #6242

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
14 changes: 14 additions & 0 deletions planning/obstacle_cruise_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,20 @@ The obstacles meeting the following condition are determined as obstacles for cr
| `behavior_determination.cruise.outside_obstacle.obstacle_velocity_threshold` | double | maximum obstacle velocity for cruise obstacle outside the trajectory |
| `behavior_determination.cruise.outside_obstacle.ego_obstacle_overlap_time_threshold` | double | maximum overlap time of the collision between the ego and obstacle |

##### Yield for vehicles that might cut in into the ego's lane

It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle's current lane.

The obstacles meeting the following condition are determined as obstacles for yielding (cruising).

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

If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego's lane to avoid the stopped obstacle.

#### Determine stop vehicles

Among obstacles which are not for cruising, the obstacles meeting the following condition are determined as obstacles for stopping.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,12 @@
obstacle_velocity_threshold : 3.5 # minimum velocity threshold of obstacles outside the trajectory to cruise or stop [m/s]
ego_obstacle_overlap_time_threshold : 2.0 # time threshold to decide cut-in obstacle for cruise or stop [s]
max_prediction_time_for_collision_check : 20.0 # prediction time to check collision between obstacle and ego

yield:
enable_yield: false
lat_distance_threshold: 5.0 # lateral margin between obstacle in neighbor lanes and trajectory band with ego's width for yielding
max_lat_dist_between_obstacles: 2.5 # lateral margin between moving obstacle in neighbor lanes and stopped obstacle in front of it
max_obstacles_collision_time: 10.0 # how far the blocking obstacle
stopped_obstacle_velocity_threshold: 0.5
slow_down:
max_lat_margin: 1.1 # lateral margin between obstacle and trajectory band with ego's width
lat_hysteresis_margin: 0.2
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,15 +55,18 @@
{
Obstacle(
const rclcpp::Time & arg_stamp, const PredictedObject & object,
const geometry_msgs::msg::Pose & arg_pose)
const geometry_msgs::msg::Pose & arg_pose, const double ego_to_obstacle_distance,
const double lat_dist_from_obstacle_to_traj)
: stamp(arg_stamp),
pose(arg_pose),
orientation_reliable(true),
twist(object.kinematics.initial_twist_with_covariance.twist),
twist_reliable(true),
classification(object.classification.at(0)),
uuid(tier4_autoware_utils::toHexString(object.object_id)),
shape(object.shape)
shape(object.shape),
ego_to_obstacle_distance(ego_to_obstacle_distance),
lat_dist_from_obstacle_to_traj(lat_dist_from_obstacle_to_traj)

Check warning on line 69 in planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp#L68-L69

Added lines #L68 - L69 were not covered by tests
{
predicted_paths.clear();
for (const auto & path : object.kinematics.predicted_paths) {
Expand All @@ -82,6 +85,8 @@
std::string uuid;
Shape shape;
std::vector<PredictedPath> predicted_paths;
double ego_to_obstacle_distance;
double lat_dist_from_obstacle_to_traj;
};

struct TargetObstacleInterface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,10 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
std::optional<geometry_msgs::msg::Point> createCollisionPointForStopObstacle(
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
const Obstacle & obstacle) const;
std::optional<CruiseObstacle> createYieldCruiseObstacle(
const Obstacle & obstacle, const std::vector<TrajectoryPoint> & traj_points);
std::optional<std::vector<CruiseObstacle>> findYieldCruiseObstacles(
const std::vector<Obstacle> & obstacles, const std::vector<TrajectoryPoint> & traj_points);
std::optional<CruiseObstacle> createCruiseObstacle(
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
const Obstacle & obstacle, const double precise_lat_dist);
Expand Down Expand Up @@ -196,8 +200,14 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
int successive_num_to_entry_slow_down_condition;
int successive_num_to_exit_slow_down_condition;
// consideration for the current ego pose
bool enable_to_consider_current_pose{false};
double time_to_convergence{1.5};
bool enable_to_consider_current_pose{false};
// yield related parameters
bool enable_yield{false};
double yield_lat_distance_threshold;
double max_lat_dist_between_obstacles;
double stopped_obstacle_velocity_threshold;
double max_obstacles_collision_time;
};
BehaviorDeterminationParam behavior_determination_param_;

Expand Down
204 changes: 187 additions & 17 deletions planning/obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check notice on line 1 in planning/obstacle_cruise_planner/src/node.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 1055 to 1201, 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 warning on line 1 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Overall Code Complexity

This module has a mean cyclomatic complexity of 4.37 across 43 functions. The mean complexity threshold is 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.

Check notice on line 1 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 35.42% to 32.69%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// 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 @@ -54,20 +54,15 @@
return *itr;
}

bool isFrontObstacle(
std::optional<double> calcDistanceToFrontVehicle(

Check warning on line 57 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L57

Added line #L57 was not covered by tests
const std::vector<TrajectoryPoint> & traj_points, const size_t ego_idx,
const geometry_msgs::msg::Point & obstacle_pos)
{
const size_t obstacle_idx = motion_utils::findNearestIndex(traj_points, obstacle_pos);

const double ego_to_obstacle_distance =
const auto ego_to_obstacle_distance =
motion_utils::calcSignedArcLength(traj_points, ego_idx, obstacle_idx);

if (ego_to_obstacle_distance < 0) {
return false;
}

return true;
if (ego_to_obstacle_distance < 0.0) return std::nullopt;
return ego_to_obstacle_distance;

Check warning on line 65 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L65

Added line #L65 was not covered by tests
}

PredictedPath resampleHighestConfidencePredictedPath(
Expand Down Expand Up @@ -254,6 +249,15 @@
node.declare_parameter<double>("behavior_determination.stop.max_lat_margin");
max_lat_margin_for_cruise =
node.declare_parameter<double>("behavior_determination.cruise.max_lat_margin");
enable_yield = node.declare_parameter<bool>("behavior_determination.cruise.yield.enable_yield");
yield_lat_distance_threshold =
node.declare_parameter<double>("behavior_determination.cruise.yield.lat_distance_threshold");
max_lat_dist_between_obstacles = node.declare_parameter<double>(
"behavior_determination.cruise.yield.max_lat_dist_between_obstacles");
stopped_obstacle_velocity_threshold = node.declare_parameter<double>(
"behavior_determination.cruise.yield.stopped_obstacle_velocity_threshold");
max_obstacles_collision_time = node.declare_parameter<double>(
"behavior_determination.cruise.yield.max_obstacles_collision_time");
max_lat_margin_for_slow_down =
node.declare_parameter<double>("behavior_determination.slow_down.max_lat_margin");
lat_hysteresis_margin_for_slow_down =
Expand Down Expand Up @@ -309,6 +313,20 @@
parameters, "behavior_determination.stop.max_lat_margin", max_lat_margin_for_stop);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.max_lat_margin", max_lat_margin_for_cruise);
tier4_autoware_utils::updateParam<bool>(
parameters, "behavior_determination.cruise.yield.enable_yield", enable_yield);

Check warning on line 317 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L317

Added line #L317 was not covered by tests
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.yield.lat_distance_threshold",
yield_lat_distance_threshold);

Check warning on line 320 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L320

Added line #L320 was not covered by tests
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.yield.max_lat_dist_between_obstacles",
max_lat_dist_between_obstacles);

Check warning on line 323 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L323

Added line #L323 was not covered by tests
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.yield.stopped_obstacle_velocity_threshold",
stopped_obstacle_velocity_threshold);

Check warning on line 326 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L326

Added line #L326 was not covered by tests
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.yield.max_obstacles_collision_time",
max_obstacles_collision_time);

Check warning on line 329 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Large Method

ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam has 71 lines, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 329 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L329

Added line #L329 was not covered by tests
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.slow_down.max_lat_margin", max_lat_margin_for_slow_down);
tier4_autoware_utils::updateParam<double>(
Expand Down Expand Up @@ -493,7 +511,7 @@
// (3) not too far from trajectory
const auto target_obstacles = convertToObstacles(traj_points);

// 2. Determine ego's behavior against each obstacle from stop, cruise and slow down.
// 2. Determine ego's behavior against each obstacle from stop, cruise and slow down.
const auto & [stop_obstacles, cruise_obstacles, slow_down_obstacles] =
determineEgoBehaviorAgainstObstacles(traj_points, target_obstacles);

Expand Down Expand Up @@ -590,6 +608,7 @@
stop_watch_.tic(__func__);

const auto obj_stamp = rclcpp::Time(objects_ptr_->header.stamp);
const auto & p = behavior_determination_param_;

std::vector<Obstacle> target_obstacles;
for (const auto & predicted_object : objects_ptr_->objects) {
Expand All @@ -611,24 +630,25 @@

// 2. Check if the obstacle is in front of the ego.
const size_t ego_idx = ego_nearest_param_.findIndex(traj_points, ego_odom_ptr_->pose.pose);
const bool is_front_obstacle =
isFrontObstacle(traj_points, ego_idx, current_obstacle_pose.pose.position);
if (!is_front_obstacle) {
const auto ego_to_obstacle_distance =
calcDistanceToFrontVehicle(traj_points, ego_idx, current_obstacle_pose.pose.position);
if (!ego_to_obstacle_distance) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_, "Ignore obstacle (%s) since it is not front obstacle.",
object_id.c_str());
continue;
}

// 3. Check if rough lateral distance is smaller than the threshold
const double lat_dist_from_obstacle_to_traj =
motion_utils::calcLateralOffset(traj_points, current_obstacle_pose.pose.position);

const double min_lat_dist_to_traj_poly = [&]() {
const double lat_dist_from_obstacle_to_traj =
motion_utils::calcLateralOffset(traj_points, current_obstacle_pose.pose.position);
const double obstacle_max_length = calcObstacleMaxLength(predicted_object.shape);
return std::abs(lat_dist_from_obstacle_to_traj) - vehicle_info_.vehicle_width_m -
obstacle_max_length;
}();
const auto & p = behavior_determination_param_;

const double max_lat_margin = std::max(
std::max(p.max_lat_margin_for_stop, p.max_lat_margin_for_cruise),
p.max_lat_margin_for_slow_down);
Expand All @@ -639,7 +659,9 @@
continue;
}

const auto target_obstacle = Obstacle(obj_stamp, predicted_object, current_obstacle_pose.pose);
const auto target_obstacle = Obstacle(
obj_stamp, predicted_object, current_obstacle_pose.pose, ego_to_obstacle_distance.value(),
lat_dist_from_obstacle_to_traj);
target_obstacles.push_back(target_obstacle);
}

Expand Down Expand Up @@ -741,6 +763,23 @@
continue;
}
}
const auto & p = behavior_determination_param_;
if (p.enable_yield) {
const auto yield_obstacles = findYieldCruiseObstacles(obstacles, decimated_traj_points);
if (yield_obstacles) {
for (const auto & y : yield_obstacles.value()) {
// Check if there is no member with the same UUID in cruise_obstacles
auto it = std::find_if(
cruise_obstacles.begin(), cruise_obstacles.end(),
[&y](const auto & c) { return y.uuid == c.uuid; });

// If no matching UUID found, insert yield obstacle into cruise_obstacles
if (it == cruise_obstacles.end()) {
cruise_obstacles.push_back(y);
}
}
}
}

Check warning on line 782 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles increases in cyclomatic complexity from 9 to 13, 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 782 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles 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.

Check warning on line 782 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.
slow_down_condition_counter_.removeCounterUnlessUpdated();

// Check target obstacles' consistency
Expand Down Expand Up @@ -829,6 +868,137 @@
tangent_vel, normal_vel, *collision_points};
}

std::optional<CruiseObstacle> ObstacleCruisePlannerNode::createYieldCruiseObstacle(

Check warning on line 871 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L871

Added line #L871 was not covered by tests
const Obstacle & obstacle, const std::vector<TrajectoryPoint> & traj_points)
{
if (traj_points.empty()) return std::nullopt;
// check label
const auto & object_id = obstacle.uuid.substr(0, 4);

Check warning on line 876 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L876

Added line #L876 was not covered by tests
const auto & p = behavior_determination_param_;

if (!isOutsideCruiseObstacle(obstacle.classification.label)) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"[Cruise] Ignore yield obstacle (%s) since its type is not designated.", object_id.c_str());
return std::nullopt;

Check warning on line 883 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L883

Added line #L883 was not covered by tests
}

if (
std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y) <

Check warning on line 887 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L886-L887

Added lines #L886 - L887 were not covered by tests
p.outside_obstacle_min_velocity_threshold) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"[Cruise] Ignore yield obstacle (%s) since the obstacle velocity is low.", object_id.c_str());
return std::nullopt;

Check warning on line 892 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L892

Added line #L892 was not covered by tests
}

if (isObstacleCrossing(traj_points, obstacle)) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"[Cruise] Ignore yield obstacle (%s) since it's crossing the ego's trajectory..",
object_id.c_str());
return std::nullopt;

Check warning on line 900 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L900

Added line #L900 was not covered by tests
}

const auto collision_points = [&]() -> std::optional<std::vector<PointWithStamp>> {

Check warning on line 903 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L903

Added line #L903 was not covered by tests
const auto obstacle_idx = motion_utils::findNearestIndex(traj_points, obstacle.pose);
if (!obstacle_idx) return std::nullopt;
const auto collision_traj_point = traj_points.at(obstacle_idx.value());

Check warning on line 906 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L906

Added line #L906 was not covered by tests
const auto object_time = now() + traj_points.at(obstacle_idx.value()).time_from_start;

PointWithStamp collision_traj_point_with_stamp;
collision_traj_point_with_stamp.stamp = object_time;
collision_traj_point_with_stamp.point.x = collision_traj_point.pose.position.x;
collision_traj_point_with_stamp.point.y = collision_traj_point.pose.position.y;

Check warning on line 912 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L911-L912

Added lines #L911 - L912 were not covered by tests
collision_traj_point_with_stamp.point.z = collision_traj_point.pose.position.z;
std::vector<PointWithStamp> collision_points_vector{collision_traj_point_with_stamp};
return collision_points_vector;
}();

if (!collision_points) return std::nullopt;
const auto [tangent_vel, normal_vel] = projectObstacleVelocityToTrajectory(traj_points, obstacle);
// check if obstacle is driving on the opposite direction
if (tangent_vel < 0.0) return std::nullopt;
return CruiseObstacle{obstacle.uuid, obstacle.stamp, obstacle.pose,
tangent_vel, normal_vel, collision_points.value()};
}

std::optional<std::vector<CruiseObstacle>> ObstacleCruisePlannerNode::findYieldCruiseObstacles(

Check warning on line 926 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L926

Added line #L926 was not covered by tests
const std::vector<Obstacle> & obstacles, const std::vector<TrajectoryPoint> & traj_points)
{
if (obstacles.empty() || traj_points.empty()) return std::nullopt;
const auto & p = behavior_determination_param_;

Check warning on line 930 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L930

Added line #L930 was not covered by tests

std::vector<Obstacle> stopped_obstacles;
std::vector<Obstacle> moving_obstacles;

std::for_each(
obstacles.begin(), obstacles.end(),
[&stopped_obstacles, &moving_obstacles, &p](const auto & o) {

Check warning on line 937 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L937

Added line #L937 was not covered by tests
const bool is_moving =
std::hypot(o.twist.linear.x, o.twist.linear.y) > p.stopped_obstacle_velocity_threshold;

Check warning on line 939 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L939

Added line #L939 was not covered by tests
if (is_moving) {
const bool is_within_lat_dist_threshold =
o.lat_dist_from_obstacle_to_traj < p.yield_lat_distance_threshold;

Check warning on line 942 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L942

Added line #L942 was not covered by tests
if (is_within_lat_dist_threshold) moving_obstacles.push_back(o);
return;

Check warning on line 944 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L944

Added line #L944 was not covered by tests
}
// lat threshold is larger for stopped obstacles
const bool is_within_lat_dist_threshold =
o.lat_dist_from_obstacle_to_traj <
p.yield_lat_distance_threshold + p.max_lat_dist_between_obstacles;

Check warning on line 949 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L948-L949

Added lines #L948 - L949 were not covered by tests
if (is_within_lat_dist_threshold) stopped_obstacles.push_back(o);
return;
});

if (stopped_obstacles.empty() || moving_obstacles.empty()) return std::nullopt;

std::sort(
stopped_obstacles.begin(), stopped_obstacles.end(), [](const auto & o1, const auto & o2) {
return o1.ego_to_obstacle_distance < o2.ego_to_obstacle_distance;
});

std::sort(moving_obstacles.begin(), moving_obstacles.end(), [](const auto & o1, const auto & o2) {

Check warning on line 961 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L961

Added line #L961 was not covered by tests
return o1.ego_to_obstacle_distance < o2.ego_to_obstacle_distance;
});

std::vector<CruiseObstacle> yield_obstacles;
for (const auto & moving_obstacle : moving_obstacles) {
for (const auto & stopped_obstacle : stopped_obstacles) {
const bool is_moving_obs_behind_of_stopped_obs =
moving_obstacle.ego_to_obstacle_distance < stopped_obstacle.ego_to_obstacle_distance;
const bool is_moving_obs_ahead_of_ego_front =
moving_obstacle.ego_to_obstacle_distance > vehicle_info_.vehicle_length_m;

Check warning on line 971 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L968-L971

Added lines #L968 - L971 were not covered by tests

if (!is_moving_obs_ahead_of_ego_front || !is_moving_obs_behind_of_stopped_obs) continue;

const double lateral_distance_between_obstacles = std::abs(
moving_obstacle.lat_dist_from_obstacle_to_traj -

Check warning on line 976 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L975-L976

Added lines #L975 - L976 were not covered by tests
stopped_obstacle.lat_dist_from_obstacle_to_traj);

const double longitudinal_distance_between_obstacles = std::abs(

Check warning on line 979 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L979

Added line #L979 was not covered by tests
moving_obstacle.ego_to_obstacle_distance - stopped_obstacle.ego_to_obstacle_distance);

const double moving_obstacle_speed =
std::hypot(moving_obstacle.twist.linear.x, moving_obstacle.twist.linear.y);

Check warning on line 983 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L983

Added line #L983 was not covered by tests

const bool are_obstacles_aligned =
lateral_distance_between_obstacles < p.max_lat_dist_between_obstacles;
const bool obstacles_collide_within_threshold_time =
longitudinal_distance_between_obstacles / moving_obstacle_speed <
p.max_obstacles_collision_time;

Check warning on line 989 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L985-L989

Added lines #L985 - L989 were not covered by tests
if (are_obstacles_aligned && obstacles_collide_within_threshold_time) {
const auto yield_obstacle = createYieldCruiseObstacle(moving_obstacle, traj_points);
if (yield_obstacle) {
yield_obstacles.push_back(*yield_obstacle);
}
}
}
}
if (yield_obstacles.empty()) return std::nullopt;
return yield_obstacles;
}

Check warning on line 1000 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

ObstacleCruisePlannerNode::findYieldCruiseObstacles has a cyclomatic complexity of 17, 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 1000 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

ObstacleCruisePlannerNode::findYieldCruiseObstacles has 3 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 1000 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

ObstacleCruisePlannerNode::findYieldCruiseObstacles has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.

Check warning on line 1000 in planning/obstacle_cruise_planner/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/obstacle_cruise_planner/src/node.cpp#L1000

Added line #L1000 was not covered by tests

std::optional<std::vector<PointWithStamp>>
ObstacleCruisePlannerNode::createCollisionPointsForInsideCruiseObstacle(
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
Expand Down
Loading