Skip to content

Commit e62f328

Browse files
authored
Make node_graph::count_graph_users() const (#1320)
Signed-off-by: Stephen Brawner <[email protected]>
1 parent 10fbde8 commit e62f328

File tree

3 files changed

+3
-3
lines changed

3 files changed

+3
-3
lines changed

rclcpp/include/rclcpp/node_interfaces/node_graph.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ class NodeGraph : public NodeGraphInterface
110110

111111
RCLCPP_PUBLIC
112112
size_t
113-
count_graph_users() override;
113+
count_graph_users() const override;
114114

115115
RCLCPP_PUBLIC
116116
std::vector<rclcpp::TopicEndpointInfo>

rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -278,7 +278,7 @@ class NodeGraphInterface
278278
RCLCPP_PUBLIC
279279
virtual
280280
size_t
281-
count_graph_users() = 0;
281+
count_graph_users() const = 0;
282282

283283
/// Return the topic endpoint information about publishers on a given topic.
284284
/**

rclcpp/src/rclcpp/node_interfaces/node_graph.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -414,7 +414,7 @@ NodeGraph::wait_for_graph_change(
414414
}
415415

416416
size_t
417-
NodeGraph::count_graph_users()
417+
NodeGraph::count_graph_users() const
418418
{
419419
return graph_users_count_.load();
420420
}

0 commit comments

Comments
 (0)