@@ -86,17 +86,18 @@ class RosTopicSubNode : public BT::ConditionNode
86
86
}
87
87
88
88
// contains the fully-qualified name of the node and the name of the topic
89
- static SubscriberInstance& getRegisteredInstance ( const std::string& key )
89
+ static std::unordered_map<std:: string, std::shared_ptr<SubscriberInstance>>& getRegistry ( )
90
90
{
91
- static std::unordered_map<std::string, SubscriberInstance> subscribers_registry;
92
- return subscribers_registry[key] ;
91
+ static std::unordered_map<std::string, std::shared_ptr< SubscriberInstance> > subscribers_registry;
92
+ return subscribers_registry;
93
93
}
94
94
95
95
std::shared_ptr<rclcpp::Node> node_;
96
- SubscriberInstance* sub_instance_ = nullptr ;
96
+ std::shared_ptr< SubscriberInstance> sub_instance_ = nullptr ;
97
97
std::shared_ptr<TopicT> last_msg_;
98
98
std::string topic_name_;
99
99
boost::signals2::connection signal_connection_;
100
+ std::string subscriber_key_;
100
101
101
102
rclcpp::Logger logger ()
102
103
{
@@ -119,6 +120,22 @@ class RosTopicSubNode : public BT::ConditionNode
119
120
virtual ~RosTopicSubNode ()
120
121
{
121
122
signal_connection_.disconnect ();
123
+ // remove the subscribers from the static registry when the ALL the
124
+ // instances of RosTopicSubNode are destroyed (i.e., the tree is destroyed)
125
+ if (sub_instance_)
126
+ {
127
+ sub_instance_.reset ();
128
+ std::unique_lock lk (registryMutex ());
129
+ auto & registry = getRegistry ();
130
+ auto it = registry.find (subscriber_key_);
131
+ // when the reference count is 1, means that the only instance is owned by the
132
+ // registry itself. Delete it
133
+ if (it != registry.end () && it->second .use_count () <= 1 )
134
+ {
135
+ registry.erase (it);
136
+ RCLCPP_INFO (logger (), " Remove subscriber [%s]" , topic_name_.c_str () );
137
+ }
138
+ }
122
139
}
123
140
124
141
/* *
@@ -225,18 +242,24 @@ template<class T> inline
225
242
226
243
// find SubscriberInstance in the registry
227
244
std::unique_lock lk (registryMutex ());
228
- const auto key = topic_name + " @" + node_->get_fully_qualified_name ();
229
- sub_instance_ = &(getRegisteredInstance (key));
245
+ subscriber_key_ = std::string (node_->get_fully_qualified_name ()) + " /" + topic_name;
230
246
231
- // just created (subscriber is not initialized)
232
- if (!sub_instance_->subscriber )
247
+ auto & registry = getRegistry ();
248
+ auto it = registry.find (subscriber_key_);
249
+ if (it == registry.end ())
233
250
{
251
+ it = registry.insert ( {subscriber_key_, std::make_shared<SubscriberInstance>() }).first ;
252
+ sub_instance_ = it->second ;
234
253
sub_instance_->init (node_, topic_name);
235
254
236
255
RCLCPP_INFO (logger (),
237
256
" Node [%s] created Subscriber to topic [%s]" ,
238
257
name ().c_str (), topic_name.c_str () );
239
258
}
259
+ else {
260
+ sub_instance_ = it->second ;
261
+ }
262
+
240
263
241
264
// add "this" as received of the broadcaster
242
265
signal_connection_ = sub_instance_->broadcaster .connect (
0 commit comments