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
Currently, subscriptions that are not manually destroyed hold a reference to the callback. This can lead to unexpected issues where a class has a callback, which was created internally (not visible to the user creating the class). If all normal references to this class are dropped, it still exists because of the reference through the ROS internals to the subscription. The object could be dropped as only the subscription is referencing it, but it isn't. It would be nice if ROS only holds a weak ref and automatically destroys the subscription if the weak red callback is destroyed. Otherwise, users might create many subscriptions on the same topic without knowing that they are still around.
One could easily add a destroy method which clears all subscriptions in a given object, but the user would need to remember calling it when an object is not used anymore. This contradicts the typical comfort in a garbage collected language and resembles you manually need to free your memory at the correct moment.
The same also might be true for services, actions and other components.
Weak refs are part of the python standard library. But adding them adds overhead and complexity in rclpy.
Bug report
Required Info:
Operating System:
Ubuntu 22.04
Installation type:
Binary
Version or commit hash:
ROS Iron
DDS implementation:
cyclone dds
Client library (if applicable):
rclpy
Steps to reproduce issue
See this case:
importgcimportrclpyfromrclpy.nodeimportNodefromstd_msgs.msgimportStringrclpy.init()
# Create a nodenode=Node("test_node")
# Create a test class that we want to destroy laterclassTestClass:
def__init__(self, n: Node, number: int):
self.sub=n.create_subscription(
String,
"test_topic",
self.callback,
10
)
self.number=numberdefcallback(self, msg):
print(msg.data)
def__del__(self):
print(f"TestClass {self.number} deleted")
# Create an instance of the test classtest=TestClass(node, 0)
# Create another instance of the test class, dereferencing the first onetest=TestClass(node, 1)
# Call the garbage collector to make sure it tries to delete the first instancegc.collect()
# Spin the noderclpy.spin(node)
If we cancel the program manually after a few seconds, it destroys both instances. But only at shutdown, not before that.
If we don't reference the class in our subscription, we see that the first class is directly destroyed.
importgcimportrclpyfromrclpy.nodeimportNodefromstd_msgs.msgimportStringrclpy.init()
# Create a nodenode=Node("test_node")
# Create a test class that we want to destroy laterclassTestClass:
def__init__(self, n: Node, number: int):
self.sub=n.create_subscription(
String,
"test_topic",
lambdamsg: print(msg.data),
10
)
self.number=numberdefcallback(self, msg):
print(msg.data)
def__del__(self):
print(f"TestClass {self.number} deleted")
# Create an instance of the test classtest=TestClass(node, 0)
# Create another instance of the test class, dereferencing the first onetest=TestClass(node, 1)
# Call the garbage collector to make sure it tries to delete the first instancegc.collect()
# Spin the noderclpy.spin(node)
It is a bit of both bug and feature imo., so I answered both.
Implementation considerations
This is a very hacky ad hoc implementation of a weak ref subscriber that works with methods of classes as well as standalone functions. It is more a feasability test then an actual implementation suggestion. Just to see some limitations etc. of this.
importgcimportweakrefimportrclpyfromrclpy.nodeimportNodefromstd_msgs.msgimportStringrclpy.init()
# Create a nodenode=Node("test_node")
defcreate_weak_subscription(n: Node, callback) ->rclpy.subscription.Subscription:
# Create a subscription with a placehoder, because we need the reference in the callbacksub=node.create_subscription(String, "test_topic", lambdamsg: None, 1)
# Check if callback if a bound method or a functionifhasattr(callback, "__self__"):
# Create a weak reference to the bound methodweak_callback=weakref.WeakMethod(callback)
else:
# Create a weak reference to the functionweak_callback=weakref.ref(callback)
# Create a callback wrapper that checks if the bound method is still alive and deletes the subscription if notdefcallback(msg):
# Check if the bound method is still aliveifweak_callback() isNone:
# Delete the subscription if notn.destroy_subscription(sub)
print("Subscription deleted")
else:
# Call the bound methodweak_callback()(msg)
# Set the callback if the subscription (the function or weak bound method)sub.callback=callbackreturnsub# Create a test class that we want to destroy laterclassTestClass:
def__init__(self, n: Node, number: int):
self.sub=create_weak_subscription(n, self.callback)
self.number=numberdefcallback(self, msg):
print(msg, self.number)
def__del__(self):
print(f"TestClass {self.number} deleted")
# Create an instance of the test classtest=TestClass(node, 0)
rclpy.spin_once(node)
# Create another instance of the test class, dereferencing the first onetest=TestClass(node, 1)
# Call the garbage collector to make sure it tries to delete the first instancegc.collect()
# Spin the noderclpy.spin(node)
Together with a simple publisher on the String topic, it results in this output:
It sounds like the behavior you're looking for is that the subscription would destroy's itself when the callback it was supposed to call is garbage collected. I think that would be a problem when using temporary functions or lambdas for callbacks, like in this example.
I agree there's something weird, but I think it's that the node keeps a reference to the subscription. It would make more sense to me that droping a reference to a subscription would cause it to be destroyed (and in turn cause the callback to be garbage collected if nothing else has a reference to it).
Currently, subscriptions that are not manually destroyed hold a reference to the callback. This can lead to unexpected issues where a class has a callback, which was created internally (not visible to the user creating the class). If all normal references to this class are dropped, it still exists because of the reference through the ROS internals to the subscription. The object could be dropped as only the subscription is referencing it, but it isn't. It would be nice if ROS only holds a weak ref and automatically destroys the subscription if the weak red callback is destroyed. Otherwise, users might create many subscriptions on the same topic without knowing that they are still around.
One could easily add a
destroy
method which clears all subscriptions in a given object, but the user would need to remember calling it when an object is not used anymore. This contradicts the typical comfort in a garbage collected language and resembles you manually need to free your memory at the correct moment.The same also might be true for services, actions and other components.
Weak refs are part of the python standard library. But adding them adds overhead and complexity in rclpy.
Bug report
Required Info:
Steps to reproduce issue
See this case:
If we cancel the program manually after a few seconds, it destroys both instances. But only at shutdown, not before that.
Output:
Expected behavior
If we don't reference the class in our subscription, we see that the first class is directly destroyed.
Output:
Actual behavior
It is not destroyed
Additional information
Feature request
Feature description
It is a bit of both bug and feature imo., so I answered both.
Implementation considerations
This is a very hacky ad hoc implementation of a weak ref subscriber that works with methods of classes as well as standalone functions. It is more a feasability test then an actual implementation suggestion. Just to see some limitations etc. of this.
Together with a simple publisher on the String topic, it results in this output:
The text was updated successfully, but these errors were encountered: