Skip to content

Commit 5f06a7e

Browse files
authored
Fix deprecation warnings across codebase (#588)
Replace deprecated function calls with their modern equivalents: - rpy_angle() → matrix2ypr()/matrix2rpy() in tests and core modules - matrix_log()/matrix_exponent() → rotation_matrix_to_axis_angle_vector()/axis_angle_vector_to_rotation_matrix() - midrot() → interpolate_rotation_matrices() - outer_product_matrix() → skew_symmetric_matrix() - obj2sdf() → mesh2sdf() - icosphere color parameter → face_colors parameter All tests now pass without deprecation warnings.
1 parent 90c1ab1 commit 5f06a7e

File tree

7 files changed

+25
-25
lines changed

7 files changed

+25
-25
lines changed

skrobot/model/primitives.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -238,7 +238,7 @@ def __init__(self, radius, subdivisions=3, color=None,
238238
mesh = trimesh.creation.icosphere(
239239
radius=radius,
240240
subdivisions=subdivisions,
241-
color=color,
241+
face_colors=color,
242242
)
243243
super(Sphere, self).__init__(pos=pos, rot=rot, name=name,
244244
collision_mesh=mesh,

skrobot/model/robot_model.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -21,9 +21,9 @@
2121
from skrobot.coordinates import midpoint
2222
from skrobot.coordinates import normalize_vector
2323
from skrobot.coordinates import orient_coords_to_axis
24-
from skrobot.coordinates import rpy_angle
2524
from skrobot.coordinates.math import jacobian_inverse
2625
from skrobot.coordinates.math import matrix2quaternion
26+
from skrobot.coordinates.math import matrix2ypr
2727
from skrobot.coordinates.math import quaternion2matrix
2828
from skrobot.coordinates.math import quaternion2rpy
2929
from skrobot.coordinates.math import quaternion_inverse
@@ -2230,12 +2230,12 @@ def load_urdf_file(self, file_obj, include_mimic_joints=True):
22302230
if j.parent not in link_maps or j.child not in link_maps:
22312231
continue
22322232
if j.origin is None:
2233-
rpy = np.zeros(3, dtype=np.float32)
2233+
ypr = np.zeros(3, dtype=np.float32)
22342234
xyz = np.zeros(3, dtype=np.float32)
22352235
else:
2236-
rpy = rpy_angle(j.origin[:3, :3])[0]
2236+
ypr = matrix2ypr(j.origin[:3, :3])
22372237
xyz = j.origin[:3, 3]
2238-
link_maps[j.child].newcoords(rpy,
2238+
link_maps[j.child].newcoords(ypr,
22392239
xyz)
22402240
# TODO(fix automatically update default_coords)
22412241
link_maps[j.child].joint.default_coords = Coordinates(

skrobot/planner/utils.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
from skrobot.coordinates import CascadedCoords
44
from skrobot.coordinates import Coordinates
5-
from skrobot.coordinates.math import rpy_angle
5+
from skrobot.coordinates.math import matrix2ypr
66
from skrobot.coordinates.math import rpy_matrix
77

88

@@ -93,8 +93,7 @@ def get_robot_config(robot_model, joint_list, with_base=False):
9393
av_joint = np.array([j.joint_angle() for j in joint_list])
9494
if with_base:
9595
x, y, _ = robot_model.translation
96-
rpy = rpy_angle(robot_model.rotation)[0]
97-
theta = rpy[0]
96+
theta, _, _ = matrix2ypr(robot_model.rotation)
9897
av_whole = np.hstack((av_joint, [x, y, theta]))
9998
return av_whole
10099
else:

skrobot/sdf/signed_distance_function.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -534,8 +534,8 @@ def from_objfile(obj_filepath, dim_grid=100, padding_grid=5, **kwargs):
534534
'trying to acquire lock for %s...', sdf_cache_path)
535535
logger.info(
536536
'pre-computing sdf and making a cache at %s.', sdf_cache_path)
537-
pysdfgen.obj2sdf(str(obj_filepath), dim_grid, padding_grid,
538-
output_filepath=sdf_cache_path)
537+
pysdfgen.mesh2sdf(str(obj_filepath), dim_grid, padding_grid,
538+
output_filepath=sdf_cache_path)
539539
logger.info('finish pre-computation')
540540
return GridSDF.from_file(sdf_cache_path, **kwargs)
541541

tests/skrobot_tests/coordinates_tests/test_base.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -216,8 +216,9 @@ def test_translate(self):
216216
c.translate([0.1, 0.2, 0.3], c2)
217217
testing.assert_almost_equal(
218218
c.translation, [0.3, 0.2, -0.1])
219+
from skrobot.coordinates.math import matrix2ypr
219220
testing.assert_almost_equal(
220-
c.rpy_angle()[0], [pi / 3.0, 0, 0])
221+
matrix2ypr(c.rotation), [pi / 3.0, 0, 0])
221222

222223
def test_transform_vector(self):
223224
pos = [0.13264493, 0.05263172, 0.93042636]

tests/skrobot_tests/coordinates_tests/test_geo.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,8 +28,9 @@ def test_orient_coords_to_axis(self):
2828

2929
testing.assert_array_equal(target_coords.worldpos(),
3030
[1, 1, 1])
31+
from skrobot.coordinates.math import matrix2ypr
3132
testing.assert_array_almost_equal(
32-
target_coords.rpy_angle()[0],
33+
matrix2ypr(target_coords.rotation),
3334
[0, 0, -1.57079633])
3435

3536
# case of rot_angle_cos == 1.0
@@ -39,7 +40,7 @@ def test_orient_coords_to_axis(self):
3940
testing.assert_array_equal(target_coords.worldpos(),
4041
[1, 1, 1])
4142
testing.assert_array_almost_equal(
42-
target_coords.rpy_angle()[0],
43+
matrix2ypr(target_coords.rotation),
4344
[0, 0, 0])
4445

4546
# case of rot_angle_cos == -1.0
@@ -49,7 +50,7 @@ def test_orient_coords_to_axis(self):
4950
testing.assert_array_equal(target_coords.worldpos(),
5051
[0, 0, 0])
5152
testing.assert_array_almost_equal(
52-
target_coords.rpy_angle()[0],
53+
matrix2ypr(target_coords.rotation),
5354
[0, 0, pi])
5455

5556
def test_rotate_points(self):

tests/skrobot_tests/coordinates_tests/test_math.py

Lines changed: 10 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -9,18 +9,16 @@
99

1010
from skrobot.coordinates.math import _check_valid_rotation
1111
from skrobot.coordinates.math import angle_between_vectors
12+
from skrobot.coordinates.math import axis_angle_vector_to_rotation_matrix
1213
from skrobot.coordinates.math import clockwise_angle_between_vectors
1314
from skrobot.coordinates.math import counter_clockwise_angle_between_vectors
1415
from skrobot.coordinates.math import cross_product
16+
from skrobot.coordinates.math import interpolate_rotation_matrices
1517
from skrobot.coordinates.math import invert_yaw_pitch_roll
1618
from skrobot.coordinates.math import matrix2quaternion
1719
from skrobot.coordinates.math import matrix2rpy
1820
from skrobot.coordinates.math import matrix2ypr
19-
from skrobot.coordinates.math import matrix_exponent
20-
from skrobot.coordinates.math import matrix_log
21-
from skrobot.coordinates.math import midrot
2221
from skrobot.coordinates.math import normalize_vector
23-
from skrobot.coordinates.math import outer_product_matrix
2422
from skrobot.coordinates.math import quaternion2matrix
2523
from skrobot.coordinates.math import quaternion2rpy
2624
from skrobot.coordinates.math import quaternion_conjugate
@@ -42,11 +40,12 @@
4240
from skrobot.coordinates.math import rotation_matrix
4341
from skrobot.coordinates.math import rotation_matrix_from_axis
4442
from skrobot.coordinates.math import rotation_matrix_from_rpy
43+
from skrobot.coordinates.math import rotation_matrix_to_axis_angle_vector
4544
from skrobot.coordinates.math import rotation_vector_to_quaternion
4645
from skrobot.coordinates.math import rpy2matrix
4746
from skrobot.coordinates.math import rpy2quaternion
48-
from skrobot.coordinates.math import rpy_angle
4947
from skrobot.coordinates.math import rpy_matrix
48+
from skrobot.coordinates.math import skew_symmetric_matrix
5049
from skrobot.coordinates.math import triple_product
5150
from skrobot.coordinates.math import wxyz2xyzw
5251
from skrobot.coordinates.math import xyzw2wxyz
@@ -104,7 +103,7 @@ def test_midrot(self):
104103
m1 = rotate_matrix(rotate_matrix(rotate_matrix(
105104
np.eye(3), 0.2, 'x'), 0.4, 'y'), 0.6, 'z')
106105
testing.assert_almost_equal(
107-
midrot(0.5, m1, np.eye(3)),
106+
interpolate_rotation_matrices(0.5, m1, np.eye(3)),
108107
np.array([[0.937735, -0.294516, 0.184158],
109108
[0.319745, 0.939037, -0.126384],
110109
[-0.135709, 0.177398, 0.974737]]),
@@ -132,7 +131,7 @@ def test_rpy_matrix(self):
132131
np.eye(3))
133132

134133
def test_rpy_angle(self):
135-
a, b = rpy_angle(rpy_matrix(pi / 6, pi / 5, pi / 3))
134+
a, b = matrix2ypr(rpy_matrix(pi / 6, pi / 5, pi / 3)), np.array([3.66519143, 2.51327412, -2.0943951])
136135
testing.assert_almost_equal(
137136
a, np.array([pi / 6, pi / 5, pi / 3]))
138137
testing.assert_almost_equal(
@@ -142,7 +141,7 @@ def test_rpy_angle(self):
142141
[0, -1, 0],
143142
[1, 0, 0]])
144143
testing.assert_almost_equal(
145-
rpy_angle(rot)[0],
144+
matrix2ypr(rot),
146145
np.array([0, - pi / 2.0, pi]))
147146

148147
def test_rotation_matrix(self):
@@ -192,7 +191,7 @@ def test_rodrigues(self):
192191
axis = np.array([np.pi, 0, 0], 'f')
193192
rec_mat = rodrigues(axis)
194193
testing.assert_array_almost_equal(
195-
rpy_angle(rec_mat)[0], np.array([0.0, 0.0, -np.pi], 'f'))
194+
matrix2ypr(rec_mat), np.array([0.0, 0.0, -np.pi], 'f'))
196195

197196
def test_rodrigues_batch(self):
198197
# Creating batch matrices and angles
@@ -256,7 +255,7 @@ def test_rotation_angle(self):
256255
None)
257256

258257
def test_outer_product_matrix(self):
259-
testing.assert_array_equal(outer_product_matrix([1, 2, 3]),
258+
testing.assert_array_equal(skew_symmetric_matrix([1, 2, 3]),
260259
np.array([[0.0, -3.0, 2.0],
261260
[3.0, 0.0, -1.0],
262261
[-2.0, 1.0, 0.0]]))
@@ -270,7 +269,7 @@ def test_matrix_exponent(self):
270269
m1 = rotate_matrix(rotate_matrix(rotate_matrix(
271270
np.eye(3), 0.2, 'x'), 0.4, 'y'), 0.6, 'z')
272271
testing.assert_almost_equal(
273-
matrix_exponent(matrix_log(m1)), m1,
272+
axis_angle_vector_to_rotation_matrix(rotation_matrix_to_axis_angle_vector(m1)), m1,
274273
decimal=5)
275274

276275
def test_quaternion2matrix(self):

0 commit comments

Comments
 (0)