Skip to content

Commit e25dd91

Browse files
committed
Removed internally packaged (legacy) transformations.py and ported to tf_transformations
1 parent a416200 commit e25dd91

File tree

5 files changed

+10
-1721
lines changed

5 files changed

+10
-1721
lines changed

package.xml

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -16,15 +16,17 @@
1616
<!-- Github does not seem to allow a fork to have its own issue tracker -->
1717
<url type="bugtracker">https://github.com/eric-wieser/ros_numpy/issues</url>
1818

19-
<exec_depend>python3-numpy</exec_depend>
20-
<exec_depend>sensor_msgs</exec_depend>
21-
<exec_depend>nav_msgs</exec_depend>
22-
<exec_depend>geometry_msgs</exec_depend>
19+
<depend>geometry_msgs</depend>
20+
<depend>nav_msgs</depend>
21+
<depend>python-transformations3d-pip</depend>
22+
<depend>python3-numpy</depend>
23+
<depend>sensor_msgs</depend>
24+
<depend>tf_transformations</depend>
2325

2426
<buildtool_depend>ament_cmake_python</buildtool_depend>
2527

26-
<test_depend>python3-nose</test_depend>
2728
<test_depend>ament_cmake_nose</test_depend>
29+
<test_depend>python3-nose</test_depend>
2830
<test_depend>rclpy</test_depend>
2931

3032
<export>

ros2_numpy/geometry.py

Lines changed: 1 addition & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
from .registry import converts_from_numpy, converts_to_numpy
22
from geometry_msgs.msg import Transform, Vector3, Quaternion, Point, Pose
3+
import tf_transformations as transformations
34
from . import numpify
45

56
import numpy as np
@@ -65,17 +66,13 @@ def numpy_to_quat(arr):
6566

6667
@converts_to_numpy(Transform)
6768
def transform_to_numpy(msg):
68-
from . import transformations
69-
7069
return np.dot(
7170
transformations.translation_matrix(numpify(msg.translation)),
7271
transformations.quaternion_matrix(numpify(msg.rotation))
7372
)
7473

7574
@converts_from_numpy(Transform)
7675
def numpy_to_transform(arr):
77-
from . import transformations
78-
7976
shape, rest = arr.shape[:-2], arr.shape[-2:]
8077
assert rest == (4,4)
8178

@@ -103,17 +100,13 @@ def numpy_to_transform(arr):
103100

104101
@converts_to_numpy(Pose)
105102
def pose_to_numpy(msg):
106-
from . import transformations
107-
108103
return np.dot(
109104
transformations.translation_matrix(numpify(msg.position)),
110105
transformations.quaternion_matrix(numpify(msg.orientation))
111106
)
112107

113108
@converts_from_numpy(Pose)
114109
def numpy_to_pose(arr):
115-
from . import transformations
116-
117110
shape, rest = arr.shape[:-2], arr.shape[-2:]
118111
assert rest == (4,4)
119112

0 commit comments

Comments
 (0)