diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 55ed5a4cf57b0..832df4a58fd1a 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -107,13 +107,10 @@ double project_goal_to_map( namespace mission_planner::lanelet2 { -void DefaultPlanner::initialize(rclcpp::Node * node) +void DefaultPlanner::initialize_common(rclcpp::Node * node) { is_graph_ready_ = false; node_ = node; - map_subscriber_ = node_->create_subscription( - "input/vector_map", rclcpp::QoS{10}.transient_local(), - std::bind(&DefaultPlanner::map_callback, this, std::placeholders::_1)); const auto durable_qos = rclcpp::QoS(1).transient_local(); pub_goal_footprint_marker_ = @@ -123,10 +120,17 @@ void DefaultPlanner::initialize(rclcpp::Node * node) param_.goal_angle_threshold_deg = node_->declare_parameter("goal_angle_threshold_deg", 45.0); } +void DefaultPlanner::initialize(rclcpp::Node * node) +{ + initialize_common(node); + map_subscriber_ = node_->create_subscription( + "input/vector_map", rclcpp::QoS{10}.transient_local(), + std::bind(&DefaultPlanner::map_callback, this, std::placeholders::_1)); +} + void DefaultPlanner::initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) { - is_graph_ready_ = false; - node_ = node; + initialize_common(node); map_callback(msg); } diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 20f731953667a..4441856857f63 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -66,6 +66,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin rclcpp::Subscription::SharedPtr map_subscriber_; rclcpp::Publisher::SharedPtr pub_goal_footprint_marker_; + void initialize_common(rclcpp::Node * node); void map_callback(const HADMapBin::ConstSharedPtr msg); bool check_goal_footprint( const lanelet::ConstLanelet & current_lanelet,