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
Launch static transform publisher ros2 run tf2_ros static_transform_publisher --x 1.0 --y 2.0 --frame-id world --child-frame-id child_frame
Launch the following node:
import rclpy
from geometry_msgs.msg import PoseStamped
from rclpy.node import Node
from tf2_ros import TransformException
from tf2_ros.buffer import Buffer
class TestPoseTransformation(Node):
def __init__(self):
super().__init__("test_pose_transform_node")
self.tf_buffer = Buffer()
self.pose_stamped = PoseStamped()
self.pose_stamped.header.frame_id = "child_frame"
self.pose_stamped.header.stamp = self.get_clock().now().to_msg()
self.pose_stamped.pose.position.x = 0.1
self.pose_stamped.pose.position.z = 0.4
self.pose_stamped.pose.orientation.w = 1.0
self.get_logger().info("Initialized Node")
self.timer = self.create_timer(1.0, self.transform_pose_stamped)
def transform_pose_stamped(self):
try:
t = self.tf_buffer.transform(self.pose_stamped, "world")
print(t)
except TransformException as e:
self.get_logger().error(f"Could not transform: {e}")
def main(args=None):
rclpy.init(args=args)
node = TestPoseTransformation()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__":
main()
Expected behavior
I would expect that the pose_stamped is transformed from child_frame to world.
Actual behavior
TypeException: Type <class 'geometry_msgs.msg._pose_stamped.PoseStamped'> is not loaded or suported.
Additional information
Complete Stacktrace
[INFO] [1720622250.237926650] [test_pose_transform_node]: Initialized Node
Traceback (most recent call last):
File "/home/ros/ros_ws/install/neura_lara8_description/lib/neura_lara8_description/test_pose_transformation", line 33, in <module>
sys.exit(load_entry_point('neura-lara8-description', 'console_scripts', 'test_pose_transformation')())
File "/home/ros/ros_ws/build/neura_lara8_description/neura_lara8_description/test_pose_transformation.py", line 37, in main
rclpy.spin(node)
File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/__init__.py", line 222, in spin
executor.spin_once()
File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 739, in spin_once
self._spin_once_impl(timeout_sec)
File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 736, in _spin_once_impl
raise handler.exception()
File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/task.py", line 239, in __call__
self._handler.send(None)
File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 437, in handler
await call_coroutine(entity, arg)
File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 351, in _execute_timer
await await_or_execute(tmr.callback)
File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 107, in await_or_execute
return callback(*args)
File "/home/ros/ros_ws/build/neura_lara8_description/neura_lara8_description/test_pose_transformation.py", line 26, in transform_pose_stamped
t = self.tf_buffer.transform(self.pose_stamped, "world")
File "/opt/ros/humble/lib/python3.10/site-packages/tf2_ros/buffer_interface.py", line 95, in transform
do_transform = self.registration.get(type(object_stamped))
File "/opt/ros/humble/lib/python3.10/site-packages/tf2_ros/buffer_interface.py", line 278, in get
raise TypeException('Type %s is not loaded or supported' % str(key))
tf2_ros.buffer_interface.TypeException: Type <class 'geometry_msgs.msg._pose_stamped.PoseStamped'> is not loaded or supported
[ros2run]: Process exited with failure 1
The text was updated successfully, but these errors were encountered:
So, there is a simple, if non-obvious, fix for this. And that is to add in import tf2_geometry_msgs at the top of the Python file. That will go ahead and load in the registration for the PoseStamped message, along with other things.
That said, I don't love how this shakes out, because it is really non-obvious that this is what is required. I'd have to think about a better way to restructure this whole thing to make it work better, or at least be more obvious what needs to be done.
Bug report
Required Info:
Ubuntu 22.04.02
Binaries inside Docker Container
rclpy
Steps to reproduce issue
Launch static transform publisher
ros2 run tf2_ros static_transform_publisher --x 1.0 --y 2.0 --frame-id world --child-frame-id child_frame
Launch the following node:
Expected behavior
I would expect that the pose_stamped is transformed from child_frame to world.
Actual behavior
TypeException: Type <class 'geometry_msgs.msg._pose_stamped.PoseStamped'> is not loaded or suported.
Additional information
Complete Stacktrace
The text was updated successfully, but these errors were encountered: