Skip to content

Commit 9189789

Browse files
committed
[tf2_geometry_msgs] pep8 formatting
1 parent c565ee6 commit 9189789

File tree

3 files changed

+65
-22
lines changed

3 files changed

+65
-22
lines changed

tf2_geometry_msgs/scripts/test.py

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -2,10 +2,12 @@
22

33
import unittest
44
import rclpy
5-
import PyKDL
65
import tf2_ros
76
import tf2_geometry_msgs
8-
from geometry_msgs.msg import TransformStamped, PointStamped, Vector3Stamped, PoseStamped, PoseWithCovarianceStamped, Quaternion
7+
from geometry_msgs.msg import (TransformStamped, PointStamped,
8+
Vector3Stamped, PoseStamped,
9+
PoseWithCovarianceStamped, Quaternion)
10+
911

1012
class GeometryMsgs(unittest.TestCase):
1113
def test_transform(self):
@@ -17,7 +19,9 @@ def test_transform(self):
1719
t.header.frame_id = 'a'
1820
t.child_frame_id = 'b'
1921
b.set_transform(t, 'eitan_rocks')
20-
out = b.lookup_transform('a','b', rclpy.time.Time(seconds=2.0).to_msg(), rclpy.time.Duration(seconds=2))
22+
out = b.lookup_transform('a', 'b',
23+
rclpy.time.Time(seconds=2.0).to_msg(),
24+
rclpy.time.Duration(seconds=2))
2125
self.assertEqual(out.transform.translation.x, 1)
2226
self.assertEqual(out.transform.rotation.x, 1)
2327
self.assertEqual(out.header.frame_id, 'a')
@@ -30,7 +34,7 @@ def test_transform(self):
3034
v.point.y = 2.0
3135
v.point.z = 3.0
3236
# b.registration.add(PointStamped)
33-
out = b.transform(v, 'b', new_type = PointStamped)
37+
out = b.transform(v, 'b', new_type=PointStamped)
3438
self.assertEqual(out.point.x, 0)
3539
self.assertEqual(out.point.y, -2)
3640
self.assertEqual(out.point.z, -3)
@@ -100,6 +104,7 @@ def test_transform(self):
100104
self.assertEqual(out.vector.y, 0)
101105
self.assertEqual(out.vector.z, 0)
102106

107+
103108
if __name__ == '__main__':
104109
rclpy.init(args=None)
105110
unittest.main()
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
from .tf2_geometry_msgs import *
1+
from .tf2_geometry_msgs import * # noqa

tf2_geometry_msgs/src/tf2_geometry_msgs/tf2_geometry_msgs.py

Lines changed: 55 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -27,83 +27,121 @@
2727

2828
# author: Wim Meeussen
2929

30-
from geometry_msgs.msg import PoseStamped, Vector3Stamped, PointStamped, PoseWithCovarianceStamped
30+
from geometry_msgs.msg import (PoseStamped, Vector3Stamped, PointStamped,
31+
PoseWithCovarianceStamped)
3132
import PyKDL
3233
import tf2_ros
3334

35+
3436
def to_msg_msg(msg):
3537
return msg
3638

39+
3740
tf2_ros.ConvertRegistration().add_to_msg(Vector3Stamped, to_msg_msg)
3841
tf2_ros.ConvertRegistration().add_to_msg(PoseStamped, to_msg_msg)
3942
tf2_ros.ConvertRegistration().add_to_msg(PointStamped, to_msg_msg)
4043

44+
4145
def from_msg_msg(msg):
4246
return msg
4347

48+
4449
tf2_ros.ConvertRegistration().add_from_msg(Vector3Stamped, from_msg_msg)
4550
tf2_ros.ConvertRegistration().add_from_msg(PoseStamped, from_msg_msg)
4651
tf2_ros.ConvertRegistration().add_from_msg(PointStamped, from_msg_msg)
4752

53+
4854
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),
5159
PyKDL.Vector(t.transform.translation.x,
5260
t.transform.translation.y,
5361
t.transform.translation.z))
5462

5563

5664
# PointStamped
5765
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)
5969
res = PointStamped()
6070
res.point.x = p[0]
6171
res.point.y = p[1]
6272
res.point.z = p[2]
6373
res.header = transform.header
6474
return res
75+
76+
6577
tf2_ros.TransformRegistration().add(PointStamped, do_transform_point)
6678

6779

6880
# Vector3Stamped
6981
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)
7488
res = Vector3Stamped()
7589
res.vector.x = p[0]
7690
res.vector.y = p[1]
7791
res.vector.z = p[2]
7892
res.header = transform.header
7993
return res
94+
95+
8096
tf2_ros.TransformRegistration().add(Vector3Stamped, do_transform_vector3)
8197

98+
8299
# PoseStamped
83100
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))
87108
res = PoseStamped()
88109
res.pose.position.x = f.p[0]
89110
res.pose.position.y = f.p[1]
90111
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()
92116
res.header = transform.header
93117
return res
118+
119+
94120
tf2_ros.TransformRegistration().add(PoseStamped, do_transform_pose)
95121

122+
96123
# PoseWithCovarianceStamped
97124
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))
101133
res = PoseWithCovarianceStamped()
102134
res.pose.pose.position.x = f.p[0]
103135
res.pose.pose.position.y = f.p[1]
104136
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()
106141
res.pose.covariance = pose.pose.covariance
107142
res.header = transform.header
108143
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

Comments
 (0)