diff --git a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml index f3f6870085e02..2c181489ba4c2 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -1,6 +1,5 @@ /**: ros__parameters: - verbose: false max_iteration_num: 100 traffic_light_signal_timeout: 1.0 planning_hz: 10.0 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 5e773eba96aee..a5dedee07e89e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -96,7 +96,7 @@ struct SceneModuleStatus class PlannerManager { public: - PlannerManager(rclcpp::Node & node, const size_t max_iteration_num, const bool verbose); + PlannerManager(rclcpp::Node & node, const size_t max_iteration_num); /** * @brief run all candidate and approved modules. @@ -474,8 +474,6 @@ class PlannerManager mutable std::shared_ptr debug_msg_ptr_; size_t max_iteration_num_{100}; - - bool verbose_{false}; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index d250fd97c3aec..8577dc74918d6 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -133,7 +133,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod const std::lock_guard lock(mutex_manager_); // for planner_manager_ const auto & p = planner_data_->parameters; - planner_manager_ = std::make_shared(*this, p.max_iteration_num, p.verbose); + planner_manager_ = std::make_shared(*this, p.max_iteration_num); for (const auto & name : declare_parameter>("launch_modules")) { // workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter. @@ -208,7 +208,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() { BehaviorPathPlannerParameters p{}; - p.verbose = declare_parameter("verbose"); p.max_iteration_num = declare_parameter("max_iteration_num"); p.traffic_light_signal_timeout = declare_parameter("traffic_light_signal_timeout"); diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 5ec34ebbab6e3..e9e0002c0c634 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -30,13 +30,11 @@ namespace behavior_path_planner { -PlannerManager::PlannerManager( - rclcpp::Node & node, const size_t max_iteration_num, const bool verbose) +PlannerManager::PlannerManager(rclcpp::Node & node, const size_t max_iteration_num) : plugin_loader_("behavior_path_planner", "behavior_path_planner::SceneModuleManagerInterface"), logger_(node.get_logger().get_child("planner_manager")), clock_(*node.get_clock()), - max_iteration_num_{max_iteration_num}, - verbose_{verbose} + max_iteration_num_{max_iteration_num} { processing_time_.emplace("total_time", 0.0); debug_publisher_ptr_ = std::make_unique(&node, "~/debug"); @@ -928,7 +926,7 @@ void PlannerManager::resetRootLanelet(const std::shared_ptr & data) root_lanelet_ = root_lanelet; - RCLCPP_INFO_EXPRESSION(logger_, verbose_, "change ego's following lane. reset."); + RCLCPP_DEBUG(logger_, "change ego's following lane. reset."); } void PlannerManager::print() const @@ -984,11 +982,7 @@ void PlannerManager::print() const state_publisher_ptr_->publish("internal_state", string_stream.str()); - if (!verbose_) { - return; - } - - RCLCPP_INFO_STREAM(logger_, string_stream.str()); + RCLCPP_DEBUG_STREAM(logger_, string_stream.str()); } void PlannerManager::publishProcessingTime() const diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp index 1eae4a1c4c345..1241f98daa747 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp @@ -30,7 +30,6 @@ struct ModuleConfigParameters struct BehaviorPathPlannerParameters { - bool verbose; size_t max_iteration_num{100}; double traffic_light_signal_timeout{1.0};