Skip to content

Commit

Permalink
refactor(bpp): remove verbose flag
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota committed Apr 18, 2024
1 parent c5ae54a commit e47ef27
Show file tree
Hide file tree
Showing 5 changed files with 6 additions and 17 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
/**:
ros__parameters:
verbose: false
max_iteration_num: 100
traffic_light_signal_timeout: 1.0
planning_hz: 10.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -474,8 +474,6 @@ class PlannerManager
mutable std::shared_ptr<SceneModuleVisitor> debug_msg_ptr_;

size_t max_iteration_num_{100};

bool verbose_{false};
};
} // namespace behavior_path_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
const std::lock_guard<std::mutex> lock(mutex_manager_); // for planner_manager_

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

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

p.verbose = declare_parameter<bool>("verbose");
p.max_iteration_num = declare_parameter<int>("max_iteration_num");
p.traffic_light_signal_timeout = declare_parameter<double>("traffic_light_signal_timeout");

Expand Down
14 changes: 4 additions & 10 deletions planning/behavior_path_planner/src/planner_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<DebugPublisher>(&node, "~/debug");
Expand Down Expand Up @@ -928,7 +926,7 @@ void PlannerManager::resetRootLanelet(const std::shared_ptr<PlannerData> & 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
Expand Down Expand Up @@ -984,11 +982,7 @@ void PlannerManager::print() const

state_publisher_ptr_->publish<DebugStringMsg>("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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@ struct ModuleConfigParameters

struct BehaviorPathPlannerParameters
{
bool verbose;
size_t max_iteration_num{100};
double traffic_light_signal_timeout{1.0};

Expand Down

0 comments on commit e47ef27

Please sign in to comment.