-
Notifications
You must be signed in to change notification settings - Fork 201
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
spin_thread is not working in rclpy. #743
Comments
That's actually not true; the C++ code uses the same node. However, when geometry2/tf2_ros/include/tf2_ros/transform_listener.h Lines 186 to 216 in 84dd504
The tf2_ros_py code isn't as sophisticated as this, and instead just creates a thread with an executor, and adds the node to it: geometry2/tf2_ros_py/tf2_ros/transform_listener.py Lines 110 to 119 in 84dd504
/tf and /tf_static topics, since they are all in the same callback group.
Probably the correct solution here is to make the tf2_ros_py code more like the tf2_ros C++ code, and add a new callback group to the executor. However, I'll note that the rclpy executor code isn't nearly as sophisticated as the rclcpp executor code, so there is some possibility this will also require changes to rclpy. |
I thought a new node was being created here, but is that not? geometry2/tf2_ros/src/transform_listener.cpp Lines 46 to 68 in 84dd504
|
This is correct, but it seems that if you spin the same node with another executor, the executor that was supposed to run in a separate thread stops functioning. In the following script, the import rclpy
from rclpy.duration import Duration
from rclpy.node import Node
from rclpy.time import Time
import tf2_ros
class TFListener(Node):
def __init__(self, node_name):
super().__init__(node_name)
self.tf_buffer = tf2_ros.Buffer()
self.tf_listener = tf2_ros.TransformListener(self.tf_buffer, self, spin_thread=True)
def run(self):
while rclpy.ok():
try:
transform = self.tf_buffer.lookup_transform('base_link', 'map', Time())
self.get_logger().info(
f'Latest transform stamp: {transform.header.stamp.sec + transform.header.stamp.nanosec * 1e-9}')
except Exception as e:
self.get_logger().error(str(e))
self.get_clock().sleep_for(Duration(seconds=0.1))
if __name__ == '__main__':
rclpy.init()
node = TFListener('test_tf_listener')
rclpy.spin_once(node) # overwrite executor?
node.run()
rclpy.shutdown() This might be because the |
Bug report
Required Info:
The spin thread is not working as intended.
As mentioned in #438, when running a transform listener on the same node as the main process with a single-threaded executor specified, the TF updates can be delayed. (See the example code below.)
To avoid this, you can either create a separate node for the transform listener or switch the main executor to a multi-threaded executor. While these workarounds exist, it concerns me that the spin_thread argument alone is almost meaningless.
I understand this may not be the best solution, but for example, in rclcpp, a separate node is internally created for the transform listener. Wouldn't it have been possible for rclpy to do the same?
Steps to reproduce issue
Expected behavior
Actual behavior
Additional information
The text was updated successfully, but these errors were encountered: