Skip to content

Commit d089776

Browse files
committed
t defaults to zero
1 parent 9705f34 commit d089776

File tree

1 file changed

+3
-1
lines changed

1 file changed

+3
-1
lines changed

spatialmath/pose3d.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1549,7 +1549,7 @@ def Tz(cls, z):
15491549
return cls([base.transl(0, 0, _z) for _z in base.getvector(z)], check=False)
15501550

15511551
@classmethod
1552-
def Rt(cls, R, t, check=True):
1552+
def Rt(cls, R, t=None, check=True):
15531553
"""
15541554
Create an SE(3) from rotation and translation
15551555
@@ -1570,6 +1570,8 @@ def Rt(cls, R, t, check=True):
15701570
else:
15711571
raise ValueError('expecting SO3 or rotation matrix')
15721572

1573+
if t is None:
1574+
t = np.zeros((3,))
15731575
return cls(base.rt2tr(R, t))
15741576

15751577
def angdist(self, other, metric=6):

0 commit comments

Comments
 (0)