Skip to content

fix(behavior_path_planner, behavior_static_obstacle_avoidance_module): crash during goal changes #10205

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

Merged
merged 8 commits into from
Mar 26, 2025
Original file line number Diff line number Diff line change
Expand Up @@ -575,6 +575,8 @@ class PlannerManager
ModuleUpdateInfo debug_info_;

std::shared_ptr<SceneModuleVisitor> debug_msg_ptr_;

mutable std::optional<BehaviorModuleOutput> last_valid_reference_path_;
};
} // namespace autoware::behavior_path_planner

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.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 5.55 to 5.43, 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 @@ -40,7 +40,8 @@
"autoware_behavior_path_planner",
"autoware::behavior_path_planner::SceneModuleManagerInterface"),
logger_(node.get_logger().get_child("planner_manager")),
clock_(*node.get_clock())
clock_(*node.get_clock()),
last_valid_reference_path_(std::nullopt)
{
current_route_lanelet_ = std::make_shared<std::optional<lanelet::ConstLanelet>>(std::nullopt);
processing_time_.emplace("total_time", 0.0);
Expand Down Expand Up @@ -272,6 +273,23 @@
const std::shared_ptr<PlannerData> & data) const
{
const auto reference_path = utils::getReferencePath(current_route_lanelet_->value(), data);

if (reference_path.path.points.empty()) {
RCLCPP_WARN_THROTTLE(

Check warning on line 278 in planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp#L278

Added line #L278 was not covered by tests
logger_, clock_, 5000,
"Empty reference path detected. Using last valid reference path if available.");

if (last_valid_reference_path_.has_value()) {
return last_valid_reference_path_.value();
}

RCLCPP_WARN_THROTTLE(

Check warning on line 286 in planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp#L286

Added line #L286 was not covered by tests
logger_, clock_, 5000, "No valid previous reference path available. Creating empty path.");
return BehaviorModuleOutput{};

Check warning on line 288 in planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp#L288

Added line #L288 was not covered by tests
}

last_valid_reference_path_ = reference_path;

publishDebugRootReferencePath(reference_path);
return reference_path;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -472,6 +472,14 @@
*route_handler, current_lanes_with_backward_margin, no_shift_pose, backward_length,
p.forward_path_length, p);

if (reference_path.points.empty()) {
auto clock{rclcpp::Clock{RCL_ROS_TIME}};
RCLCPP_WARN_THROTTLE(

Check warning on line 477 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp#L477

Added line #L477 was not covered by tests
rclcpp::get_logger("path_utils"), clock, 5000, "Empty reference path detected.");
BehaviorModuleOutput output;
return output;
}

Check warning on line 481 in planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp#L480-L481

Added lines #L480 - L481 were not covered by tests

// clip backward length
// NOTE: In order to keep backward_path_length at least, resampling interval is added to the
// backward.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -201,6 +201,13 @@
AvoidancePlanningData & data, DebugData & debug)
{
autoware_utils::ScopedTimeTrack st(__func__, *time_keeper_);

if (getPreviousModuleOutput().reference_path.points.empty()) {
RCLCPP_WARN_THROTTLE(

Check warning on line 206 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp#L206

Added line #L206 was not covered by tests
getLogger(), *clock_, 5000, "Previous module reference path is empty. Skip processing.");
return;

Check warning on line 208 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp#L208

Added line #L208 was not covered by tests
}

// reference pose
data.reference_pose =
utils::getUnshiftedEgoPose(getEgoPose(), helper_->getPreviousSplineShiftPath());
Expand All @@ -209,6 +216,11 @@
data.current_lanelets = utils::static_obstacle_avoidance::getCurrentLanesFromPath(
getPreviousModuleOutput().reference_path, planner_data_);

if (data.current_lanelets.empty()) {
RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Current lanelets is empty. Skip processing.");
return;

Check warning on line 221 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp#L220-L221

Added lines #L220 - L221 were not covered by tests
}

Check warning on line 223 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

StaticObstacleAvoidanceModule::fillFundamentalData increases in cyclomatic complexity from 9 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.
data.extend_lanelets = utils::static_obstacle_avoidance::getExtendLanes(
data.current_lanelets, getEgoPose(), planner_data_);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1487,6 +1487,12 @@
const lanelet::ConstLanelets & lanelets, const Pose & ego_pose,
const std::shared_ptr<const PlannerData> & planner_data)
{
if (lanelets.empty()) {
RCLCPP_WARN(
rclcpp::get_logger("static_obstacle_avoidance"), "Empty lanelets provided to getExtendLanes");
return lanelets;

Check warning on line 1493 in planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp#L1493

Added line #L1493 was not covered by tests
}

lanelet::ConstLanelets extend_lanelets = lanelets;

while (rclcpp::ok()) {
Expand Down
Loading