@@ -65,7 +65,7 @@ Costmap2DROS::Costmap2DROS(
6565 const std::string & name,
6666 const std::string & parent_namespace,
6767 const std::string & local_namespace)
68- : nav2_util::LifecycleNode(name, " " , true ,
68+ : nav2_util::LifecycleNode(name, " " , false ,
6969 // NodeOption arguments take precedence over the ones provided on the command line
7070 // use this to make sure the node is placed on the provided namespace
7171 // TODO(orduno) Pass a sub-node instead of creating a new node for better handling
@@ -84,9 +84,6 @@ Costmap2DROS::Costmap2DROS(
8484 " nav2_costmap_2d::InflationLayer" }
8585{
8686 RCLCPP_INFO (get_logger (), " Creating Costmap" );
87- auto options = rclcpp::NodeOptions ().arguments (
88- {" --ros-args" , " -r" , std::string (" __node:=" ) + get_name () + " _client" , " --" });
89- client_node_ = std::make_shared<rclcpp::Node>(" _" , options);
9087
9188 std::vector<std::string> clearable_layers{" obstacle_layer" , " voxel_layer" , " range_layer" };
9289
@@ -129,6 +126,9 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
129126 RCLCPP_INFO (get_logger (), " Configuring" );
130127 getParameters ();
131128
129+ callback_group_ = create_callback_group (
130+ rclcpp::CallbackGroupType::MutuallyExclusive, false );
131+
132132 // Create the costmap itself
133133 layered_costmap_ = std::make_unique<LayeredCostmap>(
134134 global_frame_, rolling_window_, track_unknown_space_);
@@ -140,10 +140,11 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
140140 }
141141
142142 // Create the transform-related objects
143- tf_buffer_ = std::make_shared<tf2_ros::Buffer>(rclcpp_node_-> get_clock ());
143+ tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock ());
144144 auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
145- rclcpp_node_->get_node_base_interface (),
146- rclcpp_node_->get_node_timers_interface ());
145+ get_node_base_interface (),
146+ get_node_timers_interface (),
147+ callback_group_);
147148 tf_buffer_->setCreateTimerInterface (timer_interface);
148149 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
149150
@@ -157,7 +158,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
157158 // TODO(mjeronimo): instead of get(), use a shared ptr
158159 plugin->initialize (
159160 layered_costmap_.get (), plugin_names_[i], tf_buffer_.get (),
160- shared_from_this (), client_node_, rclcpp_node_ );
161+ shared_from_this (), callback_group_ );
161162
162163 RCLCPP_INFO (get_logger (), " Initialized plugin \" %s\" " , plugin_names_[i].c_str ());
163164 }
@@ -170,7 +171,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
170171
171172 filter->initialize (
172173 layered_costmap_.get (), filter_names_[i], tf_buffer_.get (),
173- shared_from_this (), client_node_, rclcpp_node_ );
174+ shared_from_this (), callback_group_ );
174175
175176 RCLCPP_INFO (get_logger (), " Initialized costmap filter \" %s\" " , filter_names_[i].c_str ());
176177 }
@@ -201,6 +202,9 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
201202 // Add cleaning service
202203 clear_costmap_service_ = std::make_unique<ClearCostmapService>(shared_from_this (), *this );
203204
205+ executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
206+ executor_->add_callback_group (callback_group_, get_node_base_interface ());
207+ executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
204208 return nav2_util::CallbackReturn::SUCCESS;
205209}
206210
@@ -284,6 +288,7 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
284288 costmap_publisher_.reset ();
285289 clear_costmap_service_.reset ();
286290
291+ executor_thread_.reset ();
287292 return nav2_util::CallbackReturn::SUCCESS;
288293}
289294
0 commit comments