Skip to content

Commit 1d350cc

Browse files
committed
rebuilt docs
1 parent 1943623 commit 1d350cc

File tree

2 files changed

+11
-8
lines changed

2 files changed

+11
-8
lines changed

gh-pages

+1-1
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
Subproject commit 4024302031b48bd8eb0ce30a49417041ba3169f5
1+
Subproject commit 83ac40b277c147cda090e9db6d05dc42b6bc53de

spatialmath/pose3d.py

+10-7
Original file line numberDiff line numberDiff line change
@@ -1487,18 +1487,21 @@ def Trans(cls, x, y=None, z=None):
14871487
:return: SE(3) matrix
14881488
:rtype: SE3 instance
14891489
1490-
``T = SE3.Trans(x, y, z)`` is an SE(3) representing pure translation.
1490+
- ``SE3.Trans(x, y, z)`` is an SE(3) representing pure translation.
14911491
1492-
``T = SE3.Trans([x, y, z])`` as above, but translation is given as an
1493-
array.
1492+
- ``SE3.Trans([x, y, z])`` as above, but translation is given as an
1493+
array.
1494+
1495+
- ``SE3.Trans(t)`` where ``t`` is Nx3 then create an SE3 object with
1496+
N elements whose translation is defined by the rows of ``t``.
14941497
14951498
"""
14961499
if y is None and z is None:
1497-
# single passed value, assume is 3-vector
1498-
t = base.getvector(x, 3)
1500+
# single passed value, assume is 3-vector or Nx3
1501+
t = base.getmatrix(x, (None, 3))
1502+
return cls([base.transl(_t) for _t in t], check=False)
14991503
else:
1500-
t = np.array([x, y, z])
1501-
return cls(t)
1504+
return cls(np.array([x, y, z]))
15021505

15031506
@classmethod
15041507
def Tx(cls, x):

0 commit comments

Comments
 (0)