Skip to content

Commit

Permalink
feat: Remove max_iteration_num parameter from PlannerManager constructor
Browse files Browse the repository at this point in the history
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
  • Loading branch information
kyoichi-sugahara committed Jul 9, 2024
1 parent f3055b6 commit d2c8977
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 8 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
/**:
ros__parameters:
max_iteration_num: 100
traffic_light_signal_timeout: 1.0
planning_hz: 10.0
backward_path_length: 5.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);
explicit PlannerManager(rclcpp::Node & node);

/**
* @brief run all candidate and approved modules.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,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);
planner_manager_ = std::make_shared<PlannerManager>(*this);

size_t scene_module_num = 0;
for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
Expand Down Expand Up @@ -150,7 +149,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
{
BehaviorPathPlannerParameters p{};

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

// vehicle info
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,12 @@

namespace autoware::behavior_path_planner
{
PlannerManager::PlannerManager(rclcpp::Node & node, const size_t max_iteration_num)
PlannerManager::PlannerManager(rclcpp::Node & node)
: plugin_loader_(
"autoware_behavior_path_planner",
"autoware::behavior_path_planner::SceneModuleManagerInterface"),
logger_(node.get_logger().get_child("planner_manager")),
clock_(*node.get_clock()),
max_iteration_num_{max_iteration_num}
clock_(*node.get_clock())
{
processing_time_.emplace("total_time", 0.0);
debug_publisher_ptr_ = std::make_unique<DebugPublisher>(&node, "~/debug");
Expand Down

0 comments on commit d2c8977

Please sign in to comment.