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
My understanding was that the executor had weak ownership of the subscriber and would only get a shared_ptr when executing the callback. Hence, in a single threaded context when a callback from one subscriber is called it should be possible to destroy another subscriber and clean related objects.
Even in a multi threaded context I would expect the same if the two subscribers interacting with each other are part a mutually exclusive callback group.
Actual behavior
Here when the callback for /sub is called MyClass is destroyed but the subscriber to /test it contains is held by someone else (the count of the share_ptr is 2).
This worked fine with ROS2 humble, the subscriber count was 1 when it's callback wasn't being called.
Assuming this is the intended behavior it becomes difficult cleanup objects used by subscribers (or containing subscribers as in the example). I'm sure it still feasible by keeping a weak_ptr before resting our shared_ptr, then the executor will hopefully release its shared_ptr and only after that destroy the object. But what was as simple as destroying the object becomes more convoluted.
Additional information
I found these issues that are somewhat related but I think it's a different issue since they had callbacks called in parallel which is not the case here:
// Secure thread-safety (if provided) and shared ownership (if needed).
this->get_wait_set().wait_result_acquire();
}
When handling each ready wait (call callback function), the ownerships for all waitable entities are hold (I understand that this is probably done for efficiency reasons).
Is this something that needs to be changed? Let's hear what others think.
Bug report
Required Info:
Steps to reproduce issue
You should be able to build the executable with just
rclcpp
andstd_msgs
linked.I recommend compiling with the address sanitizer to make sure it crashes once the issue occurs. Without it, it might not crash but it's definitely UB.
In three terminals
Expected behavior
My understanding was that the executor had weak ownership of the subscriber and would only get a shared_ptr when executing the callback. Hence, in a single threaded context when a callback from one subscriber is called it should be possible to destroy another subscriber and clean related objects.
Even in a multi threaded context I would expect the same if the two subscribers interacting with each other are part a mutually exclusive callback group.
Actual behavior
Here when the callback for
/sub
is calledMyClass
is destroyed but the subscriber to/test
it contains is held by someone else (the count of the share_ptr is 2).This worked fine with ROS2 humble, the subscriber count was 1 when it's callback wasn't being called.
Assuming this is the intended behavior it becomes difficult cleanup objects used by subscribers (or containing subscribers as in the example). I'm sure it still feasible by keeping a weak_ptr before resting our shared_ptr, then the executor will hopefully release its shared_ptr and only after that destroy the object. But what was as simple as destroying the object becomes more convoluted.
Additional information
I found these issues that are somewhat related but I think it's a different issue since they had callbacks called in parallel which is not the case here:
initial_pose_sub_
innav2_amcl
may cause use-after-free bug ros-navigation/navigation2#4166 (comment)The text was updated successfully, but these errors were encountered: