ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

TF2 transform returns exception.

asked 2023-05-18 08:48:06 -0500

hamzaay gravatar image

I am running a code where i am getting a pose from a publisher and I subscribe to it in this code: the type of message is geometry_msgs.msg.PoseStamped. I then try to transform that from the camera frame to the base frame but the tf2 transform does not work. How do I fix this? I even tried to redifine the pose stamped inside the function to make sure there where no errors.

 import rospy
from std_msgs.msg import String
import tf2_ros
import geometry_msgs.msg

def callback(pose: geometry_msgs.msg.PoseStamped):
    print(type(pose.pose))
    object_pose = geometry_msgs.msg.PoseStamped()
    pose.header.stamp = rospy.Time.now()
    object_pose.header.frame_id = "camera_link"
    object_pose.pose.position.x = 0
    object_pose.pose.position.y = 0
    object_pose.pose.position.z = 0
    object_pose.pose.orientation.x = 0
    object_pose.pose.orientation.y = 0
    object_pose.pose.orientation.z = 0
    object_pose.pose.orientation.w = 1
    try:
        object_world_pose = tf_buffer.transform(object_pose,"base_link")
    except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
            pass    

    print(object_world_pose)
    print(pose)


def listener():
    rospy.Subscriber("chatter", geometry_msgs.msg.PoseStamped, callback)

    rospy.spin()

if __name__ == '__main__':
    # Initialize ROS node to transform object pose.
    print("Initializing node ...")
    rospy.init_node('transform_object_poses', anonymous=True)

    # Create a TF buffer in the global scope
    print("Creating tf buffer ...")
    tf_buffer = tf2_ros.Buffer()
    tf_listener = tf2_ros.TransformListener(tf_buffer)
    listener()

The error message:

Traceback (most recent call last): File "/opt/ros/noetic/lib/python3/dist-packages/rospy/topics.py", line 750, in _invoke_callback cb(msg) File "/home/hamza/ros_ws/src/intention_application/src/pose_sender.py", line 19, in callback object_world_pose = tf_buffer.transform(object_pose,"base_link") File "/opt/ros/noetic/lib/python3/dist-packages/tf2_ros/buffer_interface.py", line 64, in transform do_transform = self.registration.get(type(object_stamped)) File "/opt/ros/noetic/lib/python3/dist-packages/tf2_ros/buffer_interface.py", line 203, in get raise TypeException('Type %s if not loaded or supported'% str(key)) tf2_ros.buffer_interface.TypeException: Type <class 'geometry_msgs.msg._posestamped.posestamped'=""> if not loaded or supported

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2023-05-30 19:55:56 -0500

tfoote gravatar image

If you want to transform objects you need to include the implementation of their conversions. You need to import the right module from https://index.ros.org/p/tf2_geometry_...

The implementation is here: with to and from message conversions and transform implementations: https://github.com/ros/geometry2/blob...

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2023-05-18 08:48:06 -0500

Seen: 254 times

Last updated: May 30 '23