You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
When a node subscribes to a topic, it allocated some file handles. This is to be expected. When those topics are unsubscribed, not all the file handles are released. More specifically, it leaks one eventpoll handle per topic.
This test script illustrates the problem, and the patch below fixes it. This patch has only been tested on a system that uses epoll - and not kqueue, poll or noop, though i don't see why it wouldn't work.
#!/usr/bin/env python3
import sys
import rospy
import os
import std_msgs.msg
from subprocess import Popen, PIPE
# Print the number of file handles we have open
def print_handlecount():
try:
out, err = Popen(["lsof", "-p", str(os.getpid())], stdout = PIPE, stderr = PIPE).communicate()
rospy.loginfo("Open file handles: %d" % out.decode().count('\n'))
except Exception as e:
rospy.logerr("Error counting file handles: %s" % str(e))
# Loop 5 times, subscribing to 10 topics, then unsubscribing
if __name__ == "__main__":
rospy.init_node("TestNode")
rospy.loginfo("Starting test node")
print_handlecount()
num_topics = 10
for a in range(5):
subs = [rospy.Subscriber("/test%d" % i, std_msgs.msg.String, lambda x: None) for i in range(num_topics)]
rospy.loginfo(f"Subscribed to {num_topics} topics")
print_handlecount()
for s in subs:
s.unregister()
rospy.loginfo(f"Unsubscribed")
print_handlecount()
Example output from the script above (timestamps etc. omitted):
Starting test node
Open file handles: 58
Subscribed to 10 topics
Open file handles: 71
Unsubscribed
Open file handles: 70
Subscribed to 10 topics
Open file handles: 81
Unsubscribed
Open file handles: 80
Subscribed to 10 topics
Open file handles: 91
Unsubscribed
Open file handles: 90
Subscribed to 10 topics
Open file handles: 101
Unsubscribed
Open file handles: 100
Subscribed to 10 topics
Open file handles: 111
Unsubscribed
Open file handles: 110
The patch here is for topics.py.
@@ -215,6 +215,9 @@
self.remove_fd = self.noop
self.error_iter = self.noop_iter
+ def stop(self):
+ del self.poller
+
def noop(self, *args):
pass
@@ -302,6 +305,8 @@
def __del__(self):
# very similar to close(), but have to be more careful in a __del__ what we call
+ self.connection_poll.stop()
+ del self.connection_poll
if self.closed:
return
if self.connections is not None:
The text was updated successfully, but these errors were encountered:
When a node subscribes to a topic, it allocated some file handles. This is to be expected. When those topics are unsubscribed, not all the file handles are released. More specifically, it leaks one eventpoll handle per topic.
This test script illustrates the problem, and the patch below fixes it. This patch has only been tested on a system that uses epoll - and not kqueue, poll or noop, though i don't see why it wouldn't work.
Example output from the script above (timestamps etc. omitted):
The patch here is for topics.py.
The text was updated successfully, but these errors were encountered: