Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 from geometry_msgs.msg import PoseStamped, Vector3Stamped, PointStamped
00031 import PyKDL
00032 import rospy
00033 import tf2_ros
00034 
00035 def to_msg_msg(msg):
00036     return msg
00037 
00038 tf2_ros.ConvertRegistration().add_to_msg(Vector3Stamped, to_msg_msg)
00039 tf2_ros.ConvertRegistration().add_to_msg(PoseStamped, to_msg_msg)
00040 tf2_ros.ConvertRegistration().add_to_msg(PointStamped, to_msg_msg)
00041 
00042 def from_msg_msg(msg):
00043     return msg
00044 
00045 tf2_ros.ConvertRegistration().add_from_msg(Vector3Stamped, from_msg_msg)
00046 tf2_ros.ConvertRegistration().add_from_msg(PoseStamped, from_msg_msg)
00047 tf2_ros.ConvertRegistration().add_from_msg(PointStamped, from_msg_msg)
00048 
00049 def transform_to_kdl(t):
00050     return PyKDL.Frame(PyKDL.Rotation.Quaternion(t.transform.rotation.x, t.transform.rotation.y,
00051                                                  t.transform.rotation.z, t.transform.rotation.w),
00052                        PyKDL.Vector(t.transform.translation.x, 
00053                                     t.transform.translation.y, 
00054                                     t.transform.translation.z))
00055 
00056 
00057 
00058 def do_transform_point(point, transform):
00059     p = transform_to_kdl(transform) * PyKDL.Vector(point.point.x, point.point.y, point.point.z)
00060     res = PointStamped()
00061     res.point.x = p[0]
00062     res.point.y = p[1]
00063     res.point.z = p[2]
00064     res.header = transform.header
00065     return res
00066 tf2_ros.TransformRegistration().add(PointStamped, do_transform_point)
00067 
00068 
00069 
00070 def do_transform_vector3(vector3, transform):
00071     p = transform_to_kdl(transform) * PyKDL.Vector(vector3.vector.x, vector3.vector.y, vector3.vector.z)
00072     res = Vector3Stamped()
00073     res.vector.x = p[0]
00074     res.vector.y = p[1]
00075     res.vector.z = p[2]
00076     res.header = transform.header
00077     return res
00078 tf2_ros.TransformRegistration().add(Vector3Stamped, do_transform_vector3)
00079 
00080 
00081 def do_transform_pose(pose, transform):
00082     f = transform_to_kdl(transform) * PyKDL.Frame(PyKDL.Rotation.Quaternion(pose.pose.orientation.x, pose.pose.orientation.y,
00083                                                                           pose.pose.orientation.z, pose.pose.orientation.w),
00084                                                 PyKDL.Vector(pose.pose.position.x, pose.pose.position.y, pose.pose.position.z))
00085     res = PoseStamped()
00086     res.pose.position.x = f.p[0]
00087     res.pose.position.y = f.p[1]
00088     res.pose.position.z = f.p[2]
00089     (res.pose.orientation.x, res.pose.orientation.y, res.pose.orientation.z, res.pose.orientation.w) = f.M.GetQuaternion()
00090     res.header = transform.header
00091     return res
00092 tf2_ros.TransformRegistration().add(PoseStamped, do_transform_pose)