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

refactor(start_planner): add verbose parameter for debug print #5622

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
@@ -1,6 +1,9 @@
/**:
ros__parameters:
start_planner:

verbose: false

th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 1.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,8 @@ class StartPlannerModule : public SceneModuleInterface

void initializeSafetyCheckParameters();

bool receivedNewRoute() const;

bool isModuleRunning() const;
bool isCurrentPoseOnMiddleOfTheRoad() const;
bool isCloseToOriginalStartPose() const;
Expand Down Expand Up @@ -207,7 +209,7 @@ class StartPlannerModule : public SceneModuleInterface
void setDrivableAreaInfo(BehaviorModuleOutput & output) const;

// check if the goal is located behind the ego in the same route segment.
bool IsGoalBehindOfEgoInSameRouteSegment() const;
bool isGoalBehindOfEgoInSameRouteSegment() const;

// generate BehaviorPathOutput with stopping path and update status
BehaviorModuleOutput generateStopOutput();
Expand All @@ -218,6 +220,7 @@ class StartPlannerModule : public SceneModuleInterface
bool planFreespacePath();

void setDebugData() const;
void logPullOutStatus(rclcpp::Logger::Level log_level = rclcpp::Logger::Level::Info) const;
};
} // namespace behavior_path_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ struct StartPlannerParameters
double collision_check_distance_from_end{0.0};
double th_moving_object_velocity{0.0};
double center_line_path_interval{0.0};
bool verbose{false};

// shift pull out
bool enable_shift_pull_out{false};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

std::string ns = "start_planner.";

p.verbose = node->declare_parameter<bool>(ns + "verbose");

Check warning on line 36 in planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

StartPlannerModuleManager::StartPlannerModuleManager increases from 233 to 234 lines of code, 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.
p.th_arrived_distance = node->declare_parameter<double>(ns + "th_arrived_distance");
p.th_stopped_velocity = node->declare_parameter<double>(ns + "th_stopped_velocity");
p.th_stopped_time = node->declare_parameter<double>(ns + "th_stopped_time");
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check warning on line 1 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Lines of Code in a Single File

This module has 1034 lines of code, 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.
//
// 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 @@ -128,11 +128,7 @@
status_.backward_driving_complete = false;
}

const bool has_received_new_route =
!planner_data_->prev_route_id ||
*planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid();

if (has_received_new_route) {
if (receivedNewRoute()) {
status_ = PullOutStatus();
}
// check safety status when driving forward
Expand All @@ -143,6 +139,12 @@
}
}

bool StartPlannerModule::receivedNewRoute() const
{
return !planner_data_->prev_route_id ||
*planner_data_->prev_route_id != planner_data_->route_handler->getRouteUuid();
}

bool StartPlannerModule::isExecutionRequested() const
{
if (isModuleRunning()) {
Expand All @@ -161,7 +163,7 @@
}

// Check if the goal is behind the ego vehicle within the same route segment.
if (IsGoalBehindOfEgoInSameRouteSegment()) {
if (isGoalBehindOfEgoInSameRouteSegment()) {
RCLCPP_WARN_THROTTLE(
getLogger(), *clock_, 5000, "Start plan for a backward goal is not supported now");
return false;
Expand Down Expand Up @@ -228,12 +230,12 @@
return true;
}

bool StartPlannerModule::canTransitSuccessState()

Check warning on line 233 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L233

Added line #L233 was not covered by tests
{
return hasFinishedPullOut();

Check warning on line 235 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L235

Added line #L235 was not covered by tests
}

bool StartPlannerModule::canTransitIdleToRunningState()

Check warning on line 238 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L238

Added line #L238 was not covered by tests
{
return isActivated() && !isWaitingApproval();
}
Expand Down Expand Up @@ -1118,7 +1120,7 @@
return is_safe_dynamic_objects;
}

bool StartPlannerModule::IsGoalBehindOfEgoInSameRouteSegment() const
bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const

Check warning on line 1123 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1123

Added line #L1123 was not covered by tests
{
const auto & rh = planner_data_->route_handler;

Expand Down Expand Up @@ -1306,5 +1308,66 @@
planner_type_marker_array.markers.push_back(marker);
add(planner_type_marker_array);
}
if (parameters_->verbose) {
logPullOutStatus();
}
}

Check warning on line 1314 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1314

Added line #L1314 was not covered by tests

void StartPlannerModule::logPullOutStatus(rclcpp::Logger::Level log_level) const

Check warning on line 1316 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1316

Added line #L1316 was not covered by tests
{
const auto logger = getLogger();
auto logFunc = [&logger, log_level](const char * format, ...) {

Check warning on line 1319 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1319

Added line #L1319 was not covered by tests
char buffer[1024];
va_list args;
va_start(args, format);
vsnprintf(buffer, sizeof(buffer), format, args);
va_end(args);

Check warning on line 1324 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1324

Added line #L1324 was not covered by tests
switch (log_level) {
case rclcpp::Logger::Level::Debug:

Check warning on line 1326 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1326

Added line #L1326 was not covered by tests
RCLCPP_DEBUG(logger, "%s", buffer);
break;
case rclcpp::Logger::Level::Info:

Check warning on line 1329 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1329

Added line #L1329 was not covered by tests
RCLCPP_INFO(logger, "%s", buffer);
break;
case rclcpp::Logger::Level::Warn:

Check warning on line 1332 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1332

Added line #L1332 was not covered by tests
RCLCPP_WARN(logger, "%s", buffer);
break;
case rclcpp::Logger::Level::Error:

Check warning on line 1335 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1335

Added line #L1335 was not covered by tests
RCLCPP_ERROR(logger, "%s", buffer);
break;
case rclcpp::Logger::Level::Fatal:

Check warning on line 1338 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1338

Added line #L1338 was not covered by tests
RCLCPP_FATAL(logger, "%s", buffer);
break;
default:

Check warning on line 1341 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1341

Added line #L1341 was not covered by tests
RCLCPP_INFO(logger, "%s", buffer);
break;
}
};

Check warning on line 1345 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp#L1345

Added line #L1345 was not covered by tests

logFunc("======== PullOutStatus Report ========");

logFunc("[Path Info]");
logFunc(" Current Path Index: %zu", status_.current_path_idx);

logFunc("[Planner Info]");
logFunc(" Planner Type: %s", magic_enum::enum_name(status_.planner_type).data());

logFunc("[Safety and Direction Info]");
logFunc(" Found Pull Out Path: %s", status_.found_pull_out_path ? "true" : "false");
logFunc(
" Is Safe Against Dynamic Objects: %s", status_.is_safe_dynamic_objects ? "true" : "false");
logFunc(
" Previous Is Safe Dynamic Objects: %s",
status_.prev_is_safe_dynamic_objects ? "true" : "false");
logFunc(" Driving Forward: %s", status_.driving_forward ? "true" : "false");
logFunc(" Backward Driving Complete: %s", status_.backward_driving_complete ? "true" : "false");
logFunc(" Has Stop Point: %s", status_.has_stop_point ? "true" : "false");

logFunc("[Module State]");
logFunc(" isActivated: %s", isActivated() ? "true" : "false");
logFunc(" isWaitingForApproval: %s", isWaitingApproval() ? "true" : "false");
logFunc(" ModuleStatus: %s", magic_enum::enum_name(getCurrentStatus()));

logFunc("=======================================");

Check warning on line 1371 in planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

StartPlannerModule::logPullOutStatus has a cyclomatic complexity of 15, 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.
}
} // namespace behavior_path_planner
Loading