Skip to content

Commit 1aba360

Browse files
kosuke55yhisaki
andauthored
refactor(goal_planner): improve log message and change level (#9562)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> Co-authored-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com>
1 parent cf0266e commit 1aba360

File tree

1 file changed

+22
-12
lines changed

1 file changed

+22
-12
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

+22-12
Original file line numberDiff line numberDiff line change
@@ -103,7 +103,10 @@ GoalPlannerModule::GoalPlannerModule(
103103
}
104104

105105
if (pull_over_planners_.empty()) {
106-
RCLCPP_ERROR(getLogger(), "Not found enabled planner");
106+
RCLCPP_WARN(
107+
getLogger(),
108+
"No enabled planner found. The vehicle will stop in the road lane without pull over. Please "
109+
"check the parameters if this is the intended behavior.");
107110
}
108111

109112
// set selected goal searcher
@@ -296,8 +299,8 @@ void GoalPlannerModule::onTimer()
296299
!local_planner_data || !current_status_opt || !previous_module_output_opt ||
297300
!last_previous_module_output_opt || !occupancy_grid_map || !parameters_opt ||
298301
!goal_candidates_opt) {
299-
RCLCPP_ERROR(
300-
getLogger(),
302+
RCLCPP_INFO_THROTTLE(
303+
getLogger(), *clock_, 5000,
301304
"failed to get valid "
302305
"local_planner_data/current_status/previous_module_output/occupancy_grid_map/parameters_opt "
303306
"in onTimer");
@@ -462,8 +465,8 @@ void GoalPlannerModule::onFreespaceParkingTimer()
462465
if (
463466
!local_planner_data || !current_status_opt || !occupancy_grid_map || !parameters_opt ||
464467
!vehicle_footprint_opt || !goal_candidates_opt) {
465-
RCLCPP_ERROR(
466-
getLogger(),
468+
RCLCPP_WARN_THROTTLE(
469+
getLogger(), *clock_, 5000,
467470
"failed to get valid planner_data/current_status/parameters in "
468471
"onFreespaceParkingTimer");
469472
return;
@@ -801,7 +804,9 @@ bool GoalPlannerModule::isExecutionReady() const
801804
// path_decision_controller.get_current_state() is valid
802805
if (parameters_->safety_check_params.enable_safety_check && isWaitingApproval()) {
803806
if (!path_decision_controller_.get_current_state().is_stable_safe) {
804-
RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against dynamic objects");
807+
RCLCPP_INFO_THROTTLE(
808+
getLogger(), *clock_, 5000,
809+
"Path is not safe against dynamic objects, so the candidate path is not approved.");
805810
return false;
806811
}
807812
}
@@ -945,7 +950,8 @@ BehaviorModuleOutput GoalPlannerModule::plan()
945950

946951
if (utils::isAllowedGoalModification(planner_data_->route_handler)) {
947952
if (!context_data_) {
948-
RCLCPP_ERROR(getLogger(), " [pull_over] plan() is called without valid context_data");
953+
RCLCPP_WARN_THROTTLE(
954+
getLogger(), *clock_, 5000, " [pull_over] plan() is called without valid context_data");
949955
} else {
950956
const auto & context_data = context_data_.value();
951957
return planPullOver(context_data);
@@ -1230,7 +1236,7 @@ void GoalPlannerModule::setOutput(
12301236
if (!context_data.pull_over_path_opt) {
12311237
// situation : not safe against static objects use stop_path
12321238
output.path = generateStopPath(context_data);
1233-
RCLCPP_WARN_THROTTLE(
1239+
RCLCPP_INFO_THROTTLE(
12341240
getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path");
12351241
setDrivableAreaInfo(context_data, output);
12361242
return;
@@ -1244,7 +1250,7 @@ void GoalPlannerModule::setOutput(
12441250
// insert stop point in current path if ego is able to stop with acceleration and jerk
12451251
// constraints
12461252
output.path = generateFeasibleStopPath(pull_over_path.getCurrentPath());
1247-
RCLCPP_WARN_THROTTLE(
1253+
RCLCPP_INFO_THROTTLE(
12481254
getLogger(), *clock_, 5000, "Not safe against dynamic objects, generate stop path");
12491255
debug_stop_pose_with_info_.set(std::string("feasible stop after approval"));
12501256
} else {
@@ -1506,7 +1512,9 @@ void GoalPlannerModule::postProcess()
15061512
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);
15071513

15081514
if (!context_data_) {
1509-
RCLCPP_ERROR(getLogger(), " [pull_over] postProcess() is called without valid context_data");
1515+
RCLCPP_WARN_THROTTLE(
1516+
getLogger(), *clock_, 5000,
1517+
" [pull_over] postProcess() is called without valid context_data. use dummy context data.");
15101518
}
15111519
const auto context_data_dummy =
15121520
PullOverContextData(true, PredictedObjects{}, PredictedObjects{}, std::nullopt, {}, {});
@@ -1544,8 +1552,10 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval()
15441552

15451553
if (utils::isAllowedGoalModification(planner_data_->route_handler)) {
15461554
if (!context_data_) {
1547-
RCLCPP_ERROR(
1548-
getLogger(), " [pull_over] planWaitingApproval() is called without valid context_data");
1555+
RCLCPP_WARN_THROTTLE(
1556+
getLogger(), *clock_, 5000,
1557+
" [pull_over] planWaitingApproval() is called without valid context_data. use fixed goal "
1558+
"planner");
15491559
} else {
15501560
const auto & context_data = context_data_.value();
15511561
return planPullOverAsCandidate(context_data);

0 commit comments

Comments
 (0)