Skip to content

Commit

Permalink
refactor(goal_planner): improve log message and change level (#9562)
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <[email protected]>
Co-authored-by: Yukinari Hisaki <[email protected]>
  • Loading branch information
kosuke55 and yhisaki authored Dec 5, 2024
1 parent cf0266e commit 1aba360
Showing 1 changed file with 22 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,10 @@ GoalPlannerModule::GoalPlannerModule(
}

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

// set selected goal searcher
Expand Down Expand Up @@ -296,8 +299,8 @@ void GoalPlannerModule::onTimer()
!local_planner_data || !current_status_opt || !previous_module_output_opt ||
!last_previous_module_output_opt || !occupancy_grid_map || !parameters_opt ||
!goal_candidates_opt) {
RCLCPP_ERROR(
getLogger(),
RCLCPP_INFO_THROTTLE(
getLogger(), *clock_, 5000,
"failed to get valid "
"local_planner_data/current_status/previous_module_output/occupancy_grid_map/parameters_opt "
"in onTimer");
Expand Down Expand Up @@ -462,8 +465,8 @@ void GoalPlannerModule::onFreespaceParkingTimer()
if (
!local_planner_data || !current_status_opt || !occupancy_grid_map || !parameters_opt ||
!vehicle_footprint_opt || !goal_candidates_opt) {
RCLCPP_ERROR(
getLogger(),
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000,
"failed to get valid planner_data/current_status/parameters in "
"onFreespaceParkingTimer");
return;
Expand Down Expand Up @@ -801,7 +804,9 @@ bool GoalPlannerModule::isExecutionReady() const
// path_decision_controller.get_current_state() is valid
if (parameters_->safety_check_params.enable_safety_check && isWaitingApproval()) {
if (!path_decision_controller_.get_current_state().is_stable_safe) {
RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against dynamic objects");
RCLCPP_INFO_THROTTLE(
getLogger(), *clock_, 5000,
"Path is not safe against dynamic objects, so the candidate path is not approved.");
return false;
}
}
Expand Down Expand Up @@ -945,7 +950,8 @@ BehaviorModuleOutput GoalPlannerModule::plan()

if (utils::isAllowedGoalModification(planner_data_->route_handler)) {
if (!context_data_) {
RCLCPP_ERROR(getLogger(), " [pull_over] plan() is called without valid context_data");
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000, " [pull_over] plan() is called without valid context_data");
} else {
const auto & context_data = context_data_.value();
return planPullOver(context_data);
Expand Down Expand Up @@ -1230,7 +1236,7 @@ void GoalPlannerModule::setOutput(
if (!context_data.pull_over_path_opt) {
// situation : not safe against static objects use stop_path
output.path = generateStopPath(context_data);
RCLCPP_WARN_THROTTLE(
RCLCPP_INFO_THROTTLE(
getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path");
setDrivableAreaInfo(context_data, output);
return;
Expand All @@ -1244,7 +1250,7 @@ void GoalPlannerModule::setOutput(
// insert stop point in current path if ego is able to stop with acceleration and jerk
// constraints
output.path = generateFeasibleStopPath(pull_over_path.getCurrentPath());
RCLCPP_WARN_THROTTLE(
RCLCPP_INFO_THROTTLE(
getLogger(), *clock_, 5000, "Not safe against dynamic objects, generate stop path");
debug_stop_pose_with_info_.set(std::string("feasible stop after approval"));
} else {
Expand Down Expand Up @@ -1506,7 +1512,9 @@ void GoalPlannerModule::postProcess()
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);

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

if (utils::isAllowedGoalModification(planner_data_->route_handler)) {
if (!context_data_) {
RCLCPP_ERROR(
getLogger(), " [pull_over] planWaitingApproval() is called without valid context_data");
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000,
" [pull_over] planWaitingApproval() is called without valid context_data. use fixed goal "
"planner");
} else {
const auto & context_data = context_data_.value();
return planPullOverAsCandidate(context_data);
Expand Down

0 comments on commit 1aba360

Please sign in to comment.