Skip to content

Commit 28ce7e8

Browse files
authored
Reduce costmap_2d_ros nodes (#2489)
* use a dedicated callback group for costmap plugin and filter instead of inner node Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com> update comment Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com> * remove unnecessary modifications Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com>
1 parent 9bb37c6 commit 28ce7e8

File tree

10 files changed

+50
-43
lines changed

10 files changed

+50
-43
lines changed

‎nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp‎

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -303,8 +303,6 @@ class Costmap2DROS : public nav2_util::LifecycleNode
303303
double getRobotRadius() {return robot_radius_;}
304304

305305
protected:
306-
rclcpp::Node::SharedPtr client_node_;
307-
308306
// Publishers and subscribers
309307
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
310308
footprint_pub_;
@@ -313,6 +311,11 @@ class Costmap2DROS : public nav2_util::LifecycleNode
313311
rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
314312
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;
315313

314+
// Dedicated callback group and executor for tf timer_interface, costmap plugins and filters
315+
rclcpp::CallbackGroup::SharedPtr callback_group_;
316+
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
317+
std::unique_ptr<nav2_util::NodeThread> executor_thread_;
318+
316319
// Transform listener
317320
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
318321
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;

‎nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp‎

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -75,8 +75,7 @@ class Layer
7575
std::string name,
7676
tf2_ros::Buffer * tf,
7777
const nav2_util::LifecycleNode::WeakPtr & node,
78-
rclcpp::Node::SharedPtr client_node,
79-
rclcpp::Node::SharedPtr rclcpp_node);
78+
rclcpp::CallbackGroup::SharedPtr callback_group);
8079
/** @brief Stop publishers. */
8180
virtual void deactivate() {}
8281
/** @brief Restart publishers if they've been stopped. */
@@ -160,8 +159,7 @@ class Layer
160159
LayeredCostmap * layered_costmap_;
161160
std::string name_;
162161
tf2_ros::Buffer * tf_;
163-
rclcpp::Node::SharedPtr client_node_;
164-
rclcpp::Node::SharedPtr rclcpp_node_;
162+
rclcpp::CallbackGroup::SharedPtr callback_group_;
165163
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
166164
rclcpp::Clock::SharedPtr clock_;
167165
rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};

‎nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp‎

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -231,7 +231,8 @@ class ObstacleLayer : public CostmapLayer
231231
/// @brief Used to project laser scans into point clouds
232232
laser_geometry::LaserProjection projector_;
233233
/// @brief Used for the observation message filters
234-
std::vector<std::shared_ptr<message_filters::SubscriberBase<>>> observation_subscribers_;
234+
std::vector<std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>>
235+
observation_subscribers_;
235236
/// @brief Used to make sure that transforms are available for each sensor
236237
std::vector<std::shared_ptr<tf2_ros::MessageFilterBase>> observation_notifiers_;
237238
/// @brief Used to store observations from various sensors

‎nav2_costmap_2d/plugins/obstacle_layer.cpp‎

Lines changed: 17 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -119,6 +119,9 @@ void ObstacleLayer::onInitialize()
119119

120120
global_frame_ = layered_costmap_->getGlobalFrameID();
121121

122+
auto sub_opt = rclcpp::SubscriptionOptions();
123+
sub_opt.callback_group = callback_group_;
124+
122125
// now we need to split the topics based on whitespace which we can use a stringstream for
123126
std::stringstream ss(topics_string);
124127

@@ -218,14 +221,15 @@ void ObstacleLayer::onInitialize()
218221

219222
// create a callback for the topic
220223
if (data_type == "LaserScan") {
221-
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> sub(
222-
new message_filters::Subscriber<sensor_msgs::msg::LaserScan>(
223-
rclcpp_node_, topic, custom_qos_profile));
224+
auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
225+
rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
224226
sub->unsubscribe();
225227

226-
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> filter(
227-
new tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>(
228-
*sub, *tf_, global_frame_, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance)));
228+
auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
229+
*sub, *tf_, global_frame_, 50,
230+
node->get_node_logging_interface(),
231+
node->get_node_clock_interface(),
232+
tf2::durationFromSec(transform_tolerance));
229233

230234
if (inf_is_valid) {
231235
filter->registerCallback(
@@ -246,9 +250,8 @@ void ObstacleLayer::onInitialize()
246250
observation_notifiers_.back()->setTolerance(rclcpp::Duration::from_seconds(0.05));
247251

248252
} else {
249-
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2>> sub(
250-
new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(
251-
rclcpp_node_, topic, custom_qos_profile));
253+
auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
254+
rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
252255
sub->unsubscribe();
253256

254257
if (inf_is_valid) {
@@ -257,9 +260,11 @@ void ObstacleLayer::onInitialize()
257260
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
258261
}
259262

260-
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>> filter(
261-
new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
262-
*sub, *tf_, global_frame_, 50, rclcpp_node_, tf2::durationFromSec(transform_tolerance)));
263+
auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>>(
264+
*sub, *tf_, global_frame_, 50,
265+
node->get_node_logging_interface(),
266+
node->get_node_clock_interface(),
267+
tf2::durationFromSec(transform_tolerance));
263268

264269
filter->registerCallback(
265270
std::bind(

‎nav2_costmap_2d/src/costmap_2d_ros.cpp‎

Lines changed: 14 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -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

‎nav2_costmap_2d/src/layer.cpp‎

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -50,16 +50,13 @@ Layer::initialize(
5050
std::string name,
5151
tf2_ros::Buffer * tf,
5252
const nav2_util::LifecycleNode::WeakPtr & node,
53-
rclcpp::Node::SharedPtr client_node,
54-
rclcpp::Node::SharedPtr rclcpp_node)
53+
rclcpp::CallbackGroup::SharedPtr callback_group)
5554
{
5655
layered_costmap_ = parent;
5756
name_ = name;
5857
tf_ = tf;
59-
client_node_ = client_node;
60-
rclcpp_node_ = rclcpp_node;
6158
node_ = node;
62-
59+
callback_group_ = callback_group;
6360
{
6461
auto node_shared_ptr = node_.lock();
6562
logger_ = node_shared_ptr->get_logger();

‎nav2_costmap_2d/test/testing_helper.hpp‎

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ void addStaticLayer(
7575
{
7676
slayer = std::make_shared<nav2_costmap_2d::StaticLayer>();
7777
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(slayer));
78-
slayer->initialize(&layers, "static", &tf, node, nullptr, nullptr /*TODO*/);
78+
slayer->initialize(&layers, "static", &tf, node, nullptr);
7979
}
8080

8181
void addObstacleLayer(
@@ -84,7 +84,7 @@ void addObstacleLayer(
8484
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> & olayer)
8585
{
8686
olayer = std::make_shared<nav2_costmap_2d::ObstacleLayer>();
87-
olayer->initialize(&layers, "obstacles", &tf, node, nullptr, nullptr /*TODO*/);
87+
olayer->initialize(&layers, "obstacles", &tf, node, nullptr);
8888
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(olayer));
8989
}
9090

@@ -94,7 +94,7 @@ void addRangeLayer(
9494
std::shared_ptr<nav2_costmap_2d::RangeSensorLayer> & rlayer)
9595
{
9696
rlayer = std::make_shared<nav2_costmap_2d::RangeSensorLayer>();
97-
rlayer->initialize(&layers, "range", &tf, node, nullptr, nullptr /*TODO*/);
97+
rlayer->initialize(&layers, "range", &tf, node, nullptr);
9898
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(rlayer));
9999
}
100100

@@ -133,7 +133,7 @@ void addInflationLayer(
133133
std::shared_ptr<nav2_costmap_2d::InflationLayer> & ilayer)
134134
{
135135
ilayer = std::make_shared<nav2_costmap_2d::InflationLayer>();
136-
ilayer->initialize(&layers, "inflation", &tf, node, nullptr, nullptr /*TODO*/);
136+
ilayer->initialize(&layers, "inflation", &tf, node, nullptr);
137137
std::shared_ptr<nav2_costmap_2d::Layer> ipointer(ilayer);
138138
layers.addPlugin(ipointer);
139139
}

‎nav2_costmap_2d/test/unit/declare_parameter_test.cpp‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ TEST(DeclareParameter, useValidParameter)
4444
tf2_ros::Buffer tf(node->get_clock());
4545
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
4646

47-
layer.initialize(&layers, "test_layer", &tf, node, nullptr, nullptr);
47+
layer.initialize(&layers, "test_layer", &tf, node, nullptr);
4848

4949
layer.declareParameter("test1", rclcpp::ParameterValue("test_val1"));
5050
try {
@@ -63,7 +63,7 @@ TEST(DeclareParameter, useInvalidParameter)
6363
tf2_ros::Buffer tf(node->get_clock());
6464
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
6565

66-
layer.initialize(&layers, "test_layer", &tf, node, nullptr, nullptr);
66+
layer.initialize(&layers, "test_layer", &tf, node, nullptr);
6767

6868
layer.declareParameter("test2", rclcpp::PARAMETER_STRING);
6969
try {

‎nav2_costmap_2d/test/unit/keepout_filter_test.cpp‎

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -225,9 +225,7 @@ void TestNode::createKeepoutFilter(const std::string & global_frame)
225225
rclcpp::Parameter(std::string(FILTER_NAME) + ".filter_info_topic", INFO_TOPIC));
226226

227227
keepout_filter_ = std::make_shared<nav2_costmap_2d::KeepoutFilter>();
228-
keepout_filter_->initialize(
229-
&layers, std::string(FILTER_NAME),
230-
tf_buffer_.get(), node_, nullptr, nullptr);
228+
keepout_filter_->initialize(&layers, std::string(FILTER_NAME), tf_buffer_.get(), node_, nullptr);
231229
keepout_filter_->initializeFilter(INFO_TOPIC);
232230

233231
// Wait until mask will be received by KeepoutFilter

‎nav2_costmap_2d/test/unit/speed_filter_test.cpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -362,7 +362,7 @@ bool TestNode::createSpeedFilter(const std::string & global_frame)
362362
rclcpp::Parameter(std::string(FILTER_NAME) + ".speed_limit_topic", SPEED_LIMIT_TOPIC));
363363

364364
speed_filter_ = std::make_shared<nav2_costmap_2d::SpeedFilter>();
365-
speed_filter_->initialize(&layers, FILTER_NAME, tf_buffer_.get(), node_, nullptr, nullptr);
365+
speed_filter_->initialize(&layers, FILTER_NAME, tf_buffer_.get(), node_, nullptr);
366366
speed_filter_->initializeFilter(INFO_TOPIC);
367367

368368
speed_limit_subscriber_ = std::make_shared<SpeedLimitSubscriber>(SPEED_LIMIT_TOPIC);

0 commit comments

Comments
 (0)