Skip to content

Commit c8eba78

Browse files
committed
fix intertia tests
1 parent e032d8b commit c8eba78

File tree

2 files changed

+9
-6
lines changed

2 files changed

+9
-6
lines changed

roboticstoolbox/robot/DHRobot.py

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1235,6 +1235,9 @@ def jacob0_analytical(self, q, representation=None, T=None):
12351235
# compute Jacobian in world frame
12361236
J0 = self.jacob0(q, T)
12371237

1238+
if representation is None:
1239+
return J0
1240+
12381241
# compute rotational transform if analytical Jacobian required
12391242

12401243
if representation == "rpy/xyz":
@@ -1385,10 +1388,10 @@ def rne(self, q, qd=None, qdd=None, gravity=None, fext=None, base_wrench=False):
13851388
"""
13861389

13871390
if base_wrench:
1388-
return self.rne_python(q, qd, qdd,
1389-
gravity=gravity, fext=fext,
1390-
base_wrench=base_wrench)
1391-
1391+
return self.rne_python(
1392+
q, qd, qdd, gravity=gravity, fext=fext, base_wrench=base_wrench
1393+
)
1394+
13921395
trajn = 1
13931396

13941397
try:

tests/test_DHRobot.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1140,8 +1140,8 @@ def test_inertia_x(self):
11401140
[0.0000, -0.9652, -0.0000, 0.1941, 0.0000, 0.5791],
11411141
]
11421142

1143-
M0 = puma.inertia_x(q, representation="rpy/xyz")
1144-
M1 = puma.inertia_x(np.c_[q, q].T, representation="rpy/xyz")
1143+
M0 = puma.inertia_x(q, representation=None)
1144+
M1 = puma.inertia_x(np.c_[q, q].T, representation=None)
11451145

11461146
nt.assert_array_almost_equal(M0, Mr, decimal=4)
11471147
nt.assert_array_almost_equal(M1[0, :, :], Mr, decimal=4)

0 commit comments

Comments
 (0)