Skip to content

Commit 86b3d90

Browse files
committed
refactor(bpp, avoidance): remove unnecessary verbose flag (autowarefoundation#6822)
* refactor(avoidance): logger small change Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * refactor(bpp): remove verbose flag Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 3b6f2ae commit 86b3d90

File tree

14 files changed

+33
-46
lines changed

14 files changed

+33
-46
lines changed

common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,8 @@ Planning:
3737
behavior_path_planner_avoidance:
3838
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
3939
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance
40+
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
41+
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance.utils
4042

4143
behavior_path_planner_goal_planner:
4244
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -294,4 +294,3 @@
294294
# for debug
295295
debug:
296296
marker: false
297-
console: false

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -325,7 +325,6 @@ struct AvoidanceParameters
325325

326326
// debug
327327
bool publish_debug_marker = false;
328-
bool print_debug_info = false;
329328
};
330329

331330
struct ObjectData // avoidance target

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -382,7 +382,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
382382
{
383383
const std::string ns = "avoidance.debug.";
384384
p.publish_debug_marker = getOrDeclareParameter<bool>(*node, ns + "marker");
385-
p.print_debug_info = getOrDeclareParameter<bool>(*node, ns + "console");
386385
}
387386

388387
return p;

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,9 @@ using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPoly
3131
using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped;
3232
using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon;
3333

34+
static constexpr const char * logger_namespace =
35+
"planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance.utils";
36+
3437
bool isOnRight(const ObjectData & obj);
3538

3639
double calcShiftLength(

planning/behavior_path_avoidance_module/schema/avoidance.schema.json

+1-6
Original file line numberDiff line numberDiff line change
@@ -1392,14 +1392,9 @@
13921392
"type": "boolean",
13931393
"description": "Publish debug marker.",
13941394
"default": "false"
1395-
},
1396-
"console": {
1397-
"type": "boolean",
1398-
"description": "Output debug info on console.",
1399-
"default": "false"
14001395
}
14011396
},
1402-
"required": ["marker", "console"],
1397+
"required": ["marker"],
14031398
"additionalProperties": false
14041399
}
14051400
},

planning/behavior_path_avoidance_module/src/manager.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -262,7 +262,6 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector<rclcpp::Parame
262262
{
263263
const std::string ns = "avoidance.debug.";
264264
updateParam<bool>(parameters, ns + "marker", p->publish_debug_marker);
265-
updateParam<bool>(parameters, ns + "console", p->print_debug_info);
266265
}
267266

268267
std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) {

planning/behavior_path_avoidance_module/src/scene.cpp

+11-12
Original file line numberDiff line numberDiff line change
@@ -40,12 +40,6 @@
4040
#include <string>
4141
#include <vector>
4242

43-
// set as macro so that calling function name will be printed.
44-
// debug print is heavy. turn on only when debugging.
45-
#define DEBUG_PRINT(...) \
46-
RCLCPP_DEBUG_EXPRESSION(getLogger(), parameters_->print_debug_info, __VA_ARGS__)
47-
#define printShiftLines(p, msg) DEBUG_PRINT("[%s] %s", msg, toStrInfo(p).c_str())
48-
4943
namespace behavior_path_planner
5044
{
5145

@@ -109,7 +103,7 @@ AvoidanceModule::AvoidanceModule(
109103

110104
bool AvoidanceModule::isExecutionRequested() const
111105
{
112-
DEBUG_PRINT("AVOIDANCE isExecutionRequested");
106+
RCLCPP_DEBUG(getLogger(), "AVOIDANCE isExecutionRequested");
113107

114108
// Check ego is in preferred lane
115109
updateInfoMarker(avoid_data_);
@@ -132,7 +126,11 @@ bool AvoidanceModule::isExecutionRequested() const
132126

133127
bool AvoidanceModule::isExecutionReady() const
134128
{
135-
DEBUG_PRINT("AVOIDANCE isExecutionReady");
129+
RCLCPP_DEBUG_STREAM(getLogger(), "---Avoidance GO/NO-GO status---");
130+
RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "SAFE:" << avoid_data_.safe);
131+
RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "COMFORTABLE:" << avoid_data_.comfortable);
132+
RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "VALID:" << avoid_data_.valid);
133+
RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "READY:" << avoid_data_.ready);
136134
return avoid_data_.safe && avoid_data_.comfortable && avoid_data_.valid && avoid_data_.ready;
137135
}
138136

@@ -1117,7 +1115,7 @@ void AvoidanceModule::addNewShiftLines(
11171115
const auto new_shift_length = front_new_shift_line.end_shift_length;
11181116
const auto new_shift_end_idx = front_new_shift_line.end_idx;
11191117

1120-
DEBUG_PRINT("min_start_idx = %lu", min_start_idx);
1118+
RCLCPP_DEBUG(getLogger(), "min_start_idx = %lu", min_start_idx);
11211119

11221120
// Remove shift points that starts later than the new_shift_line from path_shifter.
11231121
//
@@ -1130,8 +1128,9 @@ void AvoidanceModule::addNewShiftLines(
11301128
// farther avoidance.
11311129
for (const auto & sl : current_shift_lines) {
11321130
if (sl.start_idx >= min_start_idx) {
1133-
DEBUG_PRINT(
1134-
"sl.start_idx = %lu, this sl starts after new proposal. remove this one.", sl.start_idx);
1131+
RCLCPP_DEBUG(
1132+
getLogger(), "sl.start_idx = %lu, this sl starts after new proposal. remove this one.",
1133+
sl.start_idx);
11351134
continue;
11361135
}
11371136

@@ -1149,7 +1148,7 @@ void AvoidanceModule::addNewShiftLines(
11491148
}
11501149
}
11511150

1152-
DEBUG_PRINT("sl.start_idx = %lu, no conflict. keep this one.", sl.start_idx);
1151+
RCLCPP_DEBUG(getLogger(), "sl.start_idx = %lu, no conflict. keep this one.", sl.start_idx);
11531152
future.push_back(sl);
11541153
}
11551154

planning/behavior_path_avoidance_module/src/utils.cpp

+11-8
Original file line numberDiff line numberDiff line change
@@ -662,13 +662,15 @@ bool isNeverAvoidanceTarget(
662662
if (object.is_within_intersection) {
663663
if (object.behavior == ObjectData::Behavior::NONE) {
664664
object.reason = "ParallelToEgoLane";
665-
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object belongs to ego lane. never avoid it.");
665+
RCLCPP_DEBUG(
666+
rclcpp::get_logger(logger_namespace), "object belongs to ego lane. never avoid it.");
666667
return true;
667668
}
668669

669670
if (object.behavior == ObjectData::Behavior::MERGING) {
670671
object.reason = "MergingToEgoLane";
671-
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object belongs to ego lane. never avoid it.");
672+
RCLCPP_DEBUG(
673+
rclcpp::get_logger(logger_namespace), "object belongs to ego lane. never avoid it.");
672674
return true;
673675
}
674676
}
@@ -720,15 +722,17 @@ bool isNeverAvoidanceTarget(
720722
planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, false);
721723
if (right_lane.has_value() && left_lane.has_value()) {
722724
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
723-
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane. never avoid it.");
725+
RCLCPP_DEBUG(
726+
rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it.");
724727
return true;
725728
}
726729
}
727730

728731
if (isCloseToStopFactor(object, data, planner_data, parameters)) {
729732
if (object.is_on_ego_lane && !object.is_parked) {
730733
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
731-
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is close to stop factor. never avoid it.");
734+
RCLCPP_DEBUG(
735+
rclcpp::get_logger(logger_namespace), "object is close to stop factor. never avoid it.");
732736
return true;
733737
}
734738
}
@@ -743,12 +747,12 @@ bool isObviousAvoidanceTarget(
743747
{
744748
if (!object.is_within_intersection) {
745749
if (object.is_parked && object.behavior == ObjectData::Behavior::NONE) {
746-
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is obvious parked vehicle.");
750+
RCLCPP_DEBUG(rclcpp::get_logger(logger_namespace), "object is obvious parked vehicle.");
747751
return true;
748752
}
749753

750754
if (!object.is_on_ego_lane && object.behavior == ObjectData::Behavior::NONE) {
751-
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is adjacent vehicle.");
755+
RCLCPP_DEBUG(rclcpp::get_logger(logger_namespace), "object is adjacent vehicle.");
752756
return true;
753757
}
754758
}
@@ -2323,8 +2327,7 @@ DrivableLanes generateExpandedDrivableLanes(
23232327
}
23242328
if (i == max_recursive_search_num - 1) {
23252329
RCLCPP_ERROR(
2326-
rclcpp::get_logger("behavior_path_planner").get_child("avoidance"),
2327-
"Drivable area expansion reaches max iteration.");
2330+
rclcpp::get_logger(logger_namespace), "Drivable area expansion reaches max iteration.");
23282331
}
23292332
}
23302333
};

planning/behavior_path_planner/config/behavior_path_planner.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
/**:
22
ros__parameters:
3-
verbose: false
43
max_iteration_num: 100
54
traffic_light_signal_timeout: 1.0
65
planning_hz: 10.0

planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ struct SceneModuleStatus
9696
class PlannerManager
9797
{
9898
public:
99-
PlannerManager(rclcpp::Node & node, const size_t max_iteration_num, const bool verbose);
99+
PlannerManager(rclcpp::Node & node, const size_t max_iteration_num);
100100

101101
/**
102102
* @brief run all candidate and approved modules.
@@ -471,8 +471,6 @@ class PlannerManager
471471
mutable std::shared_ptr<SceneModuleVisitor> debug_msg_ptr_;
472472

473473
size_t max_iteration_num_{100};
474-
475-
bool verbose_{false};
476474
};
477475
} // namespace behavior_path_planner
478476

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
133133
const std::lock_guard<std::mutex> lock(mutex_manager_); // for planner_manager_
134134

135135
const auto & p = planner_data_->parameters;
136-
planner_manager_ = std::make_shared<PlannerManager>(*this, p.max_iteration_num, p.verbose);
136+
planner_manager_ = std::make_shared<PlannerManager>(*this, p.max_iteration_num);
137137

138138
for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
139139
// workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter.
@@ -207,7 +207,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
207207
{
208208
BehaviorPathPlannerParameters p{};
209209

210-
p.verbose = declare_parameter<bool>("verbose");
211210
p.max_iteration_num = declare_parameter<int>("max_iteration_num");
212211
p.traffic_light_signal_timeout = declare_parameter<double>("traffic_light_signal_timeout");
213212

planning/behavior_path_planner/src/planner_manager.cpp

+3-9
Original file line numberDiff line numberDiff line change
@@ -30,13 +30,11 @@
3030

3131
namespace behavior_path_planner
3232
{
33-
PlannerManager::PlannerManager(
34-
rclcpp::Node & node, const size_t max_iteration_num, const bool verbose)
33+
PlannerManager::PlannerManager(rclcpp::Node & node, const size_t max_iteration_num)
3534
: plugin_loader_("behavior_path_planner", "behavior_path_planner::SceneModuleManagerInterface"),
3635
logger_(node.get_logger().get_child("planner_manager")),
3736
clock_(*node.get_clock()),
38-
max_iteration_num_{max_iteration_num},
39-
verbose_{verbose}
37+
max_iteration_num_{max_iteration_num}
4038
{
4139
processing_time_.emplace("total_time", 0.0);
4240
debug_publisher_ptr_ = std::make_unique<DebugPublisher>(&node, "~/debug");
@@ -946,11 +944,7 @@ void PlannerManager::print() const
946944

947945
state_publisher_ptr_->publish<DebugStringMsg>("internal_state", string_stream.str());
948946

949-
if (!verbose_) {
950-
return;
951-
}
952-
953-
RCLCPP_INFO_STREAM(logger_, string_stream.str());
947+
RCLCPP_DEBUG_STREAM(logger_, string_stream.str());
954948
}
955949

956950
void PlannerManager::publishProcessingTime() const

planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,6 @@ struct ModuleConfigParameters
3030

3131
struct BehaviorPathPlannerParameters
3232
{
33-
bool verbose;
3433
size_t max_iteration_num{100};
3534
double traffic_light_signal_timeout{1.0};
3635

0 commit comments

Comments
 (0)