|
27 | 27 |
|
28 | 28 | # author: Wim Meeussen |
29 | 29 |
|
30 | | -from geometry_msgs.msg import PoseStamped, Vector3Stamped, PointStamped, PoseWithCovarianceStamped |
| 30 | +from geometry_msgs.msg import (PoseStamped, Vector3Stamped, PointStamped, |
| 31 | + PoseWithCovarianceStamped) |
31 | 32 | import PyKDL |
32 | 33 | import tf2_ros |
33 | 34 |
|
| 35 | + |
34 | 36 | def to_msg_msg(msg): |
35 | 37 | return msg |
36 | 38 |
|
| 39 | + |
37 | 40 | tf2_ros.ConvertRegistration().add_to_msg(Vector3Stamped, to_msg_msg) |
38 | 41 | tf2_ros.ConvertRegistration().add_to_msg(PoseStamped, to_msg_msg) |
39 | 42 | tf2_ros.ConvertRegistration().add_to_msg(PointStamped, to_msg_msg) |
40 | 43 |
|
| 44 | + |
41 | 45 | def from_msg_msg(msg): |
42 | 46 | return msg |
43 | 47 |
|
| 48 | + |
44 | 49 | tf2_ros.ConvertRegistration().add_from_msg(Vector3Stamped, from_msg_msg) |
45 | 50 | tf2_ros.ConvertRegistration().add_from_msg(PoseStamped, from_msg_msg) |
46 | 51 | tf2_ros.ConvertRegistration().add_from_msg(PointStamped, from_msg_msg) |
47 | 52 |
|
| 53 | + |
48 | 54 | def transform_to_kdl(t): |
49 | | - return PyKDL.Frame(PyKDL.Rotation.Quaternion(t.transform.rotation.x, t.transform.rotation.y, |
50 | | - t.transform.rotation.z, t.transform.rotation.w), |
| 55 | + return PyKDL.Frame(PyKDL.Rotation.Quaternion(t.transform.rotation.x, |
| 56 | + t.transform.rotation.y, |
| 57 | + t.transform.rotation.z, |
| 58 | + t.transform.rotation.w), |
51 | 59 | PyKDL.Vector(t.transform.translation.x, |
52 | 60 | t.transform.translation.y, |
53 | 61 | t.transform.translation.z)) |
54 | 62 |
|
55 | 63 |
|
56 | 64 | # PointStamped |
57 | 65 | def do_transform_point(point, transform): |
58 | | - p = transform_to_kdl(transform) * PyKDL.Vector(point.point.x, point.point.y, point.point.z) |
| 66 | + p = transform_to_kdl(transform) * PyKDL.Vector(point.point.x, |
| 67 | + point.point.y, |
| 68 | + point.point.z) |
59 | 69 | res = PointStamped() |
60 | 70 | res.point.x = p[0] |
61 | 71 | res.point.y = p[1] |
62 | 72 | res.point.z = p[2] |
63 | 73 | res.header = transform.header |
64 | 74 | return res |
| 75 | + |
| 76 | + |
65 | 77 | tf2_ros.TransformRegistration().add(PointStamped, do_transform_point) |
66 | 78 |
|
67 | 79 |
|
68 | 80 | # Vector3Stamped |
69 | 81 | def do_transform_vector3(vector3, transform): |
70 | | - transform.transform.translation.x = 0.0; |
71 | | - transform.transform.translation.y = 0.0; |
72 | | - transform.transform.translation.z = 0.0; |
73 | | - p = transform_to_kdl(transform) * PyKDL.Vector(vector3.vector.x, vector3.vector.y, vector3.vector.z) |
| 82 | + transform.transform.translation.x = 0.0 |
| 83 | + transform.transform.translation.y = 0.0 |
| 84 | + transform.transform.translation.z = 0.0 |
| 85 | + p = transform_to_kdl(transform) * PyKDL.Vector(vector3.vector.x, |
| 86 | + vector3.vector.y, |
| 87 | + vector3.vector.z) |
74 | 88 | res = Vector3Stamped() |
75 | 89 | res.vector.x = p[0] |
76 | 90 | res.vector.y = p[1] |
77 | 91 | res.vector.z = p[2] |
78 | 92 | res.header = transform.header |
79 | 93 | return res |
| 94 | + |
| 95 | + |
80 | 96 | tf2_ros.TransformRegistration().add(Vector3Stamped, do_transform_vector3) |
81 | 97 |
|
| 98 | + |
82 | 99 | # PoseStamped |
83 | 100 | def do_transform_pose(pose, transform): |
84 | | - f = transform_to_kdl(transform) * PyKDL.Frame(PyKDL.Rotation.Quaternion(pose.pose.orientation.x, pose.pose.orientation.y, |
85 | | - pose.pose.orientation.z, pose.pose.orientation.w), |
86 | | - PyKDL.Vector(pose.pose.position.x, pose.pose.position.y, pose.pose.position.z)) |
| 101 | + f = transform_to_kdl(transform) * PyKDL.Frame( |
| 102 | + PyKDL.Rotation.Quaternion( |
| 103 | + pose.pose.orientation.x, pose.pose.orientation.y, |
| 104 | + pose.pose.orientation.z, pose.pose.orientation.w), |
| 105 | + PyKDL.Vector(pose.pose.position.x, |
| 106 | + pose.pose.position.y, |
| 107 | + pose.pose.position.z)) |
87 | 108 | res = PoseStamped() |
88 | 109 | res.pose.position.x = f.p[0] |
89 | 110 | res.pose.position.y = f.p[1] |
90 | 111 | res.pose.position.z = f.p[2] |
91 | | - (res.pose.orientation.x, res.pose.orientation.y, res.pose.orientation.z, res.pose.orientation.w) = f.M.GetQuaternion() |
| 112 | + (res.pose.orientation.x, |
| 113 | + res.pose.orientation.y, |
| 114 | + res.pose.orientation.z, |
| 115 | + res.pose.orientation.w) = f.M.GetQuaternion() |
92 | 116 | res.header = transform.header |
93 | 117 | return res |
| 118 | + |
| 119 | + |
94 | 120 | tf2_ros.TransformRegistration().add(PoseStamped, do_transform_pose) |
95 | 121 |
|
| 122 | + |
96 | 123 | # PoseWithCovarianceStamped |
97 | 124 | def do_transform_pose_with_covariance_stamped(pose, transform): |
98 | | - f = transform_to_kdl(transform) * PyKDL.Frame(PyKDL.Rotation.Quaternion(pose.pose.pose.orientation.x, pose.pose.pose.orientation.y, |
99 | | - pose.pose.pose.orientation.z, pose.pose.pose.orientation.w), |
100 | | - PyKDL.Vector(pose.pose.pose.position.x, pose.pose.pose.position.y, pose.pose.pose.position.z)) |
| 125 | + f = transform_to_kdl(transform) * PyKDL.Frame( |
| 126 | + PyKDL.Rotation.Quaternion(pose.pose.pose.orientation.x, |
| 127 | + pose.pose.pose.orientation.y, |
| 128 | + pose.pose.pose.orientation.z, |
| 129 | + pose.pose.pose.orientation.w), |
| 130 | + PyKDL.Vector(pose.pose.pose.position.x, |
| 131 | + pose.pose.pose.position.y, |
| 132 | + pose.pose.pose.position.z)) |
101 | 133 | res = PoseWithCovarianceStamped() |
102 | 134 | res.pose.pose.position.x = f.p[0] |
103 | 135 | res.pose.pose.position.y = f.p[1] |
104 | 136 | res.pose.pose.position.z = f.p[2] |
105 | | - (res.pose.pose.orientation.x, res.pose.pose.orientation.y, res.pose.pose.orientation.z, res.pose.pose.orientation.w) = f.M.GetQuaternion() |
| 137 | + (res.pose.pose.orientation.x, |
| 138 | + res.pose.pose.orientation.y, |
| 139 | + res.pose.pose.orientation.z, |
| 140 | + res.pose.pose.orientation.w) = f.M.GetQuaternion() |
106 | 141 | res.pose.covariance = pose.pose.covariance |
107 | 142 | res.header = transform.header |
108 | 143 | return res |
109 | | -tf2_ros.TransformRegistration().add(PoseWithCovarianceStamped, do_transform_pose_with_covariance_stamped) |
| 144 | + |
| 145 | + |
| 146 | +tf2_ros.TransformRegistration().add(PoseWithCovarianceStamped, |
| 147 | + do_transform_pose_with_covariance_stamped) |
0 commit comments