Skip to content

Navigation Menu

Sign in
Appearance settings

Search code, repositories, users, issues, pull requests...

Provide feedback

We read every piece of feedback, and take your input very seriously.

Saved searches

Use saved searches to filter your results more quickly

Appearance settings

Commit ed93f18

Browse filesBrowse files
committed
doco update, focus on seealso and pycon example blocks
1 parent 9a578e5 commit ed93f18
Copy full SHA for ed93f18

File tree

Expand file treeCollapse file tree

3 files changed

+87
-59
lines changed
Filter options
Expand file treeCollapse file tree

3 files changed

+87
-59
lines changed

‎spatialmath/baseposematrix.py

Copy file name to clipboardExpand all lines: spatialmath/baseposematrix.py
+34-24Lines changed: 34 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -404,7 +404,7 @@ def interp(self, end=None, s=None):
404404
405405
- For SO3 and SE3 rotation is interpolated using quaternion spherical linear interpolation (slerp).
406406
- Values of ``s`` outside the range [0,1] are silently clipped
407-
:seealso: :func:`interp1`, :func:`~spatialmath.base.transforms3d.trinterp`, :func:`~spatialmath.base.quaternions.slerp`, :func:`~spatialmath.base.transforms2d.trinterp2`
407+
:seealso: :func:`interp1`, :func:`~spatialmath.base.transforms3d.trinterp`, :func:`~spatialmath.base.quaternions.qslerp`, :func:`~spatialmath.base.transforms2d.trinterp2`
408408
409409
:SymPy: not supported
410410
"""
@@ -482,7 +482,7 @@ def interp1(self, s=None):
482482
483483
#. For SO3 and SE3 rotation is interpolated using quaternion spherical linear interpolation (slerp).
484484
485-
:seealso: :func:`interp`, :func:`~spatialmath.base.transforms3d.trinterp`, :func:`~spatialmath.base.quaternions.slerp`, :func:`~spatialmath.base.transforms2d.trinterp2`
485+
:seealso: :func:`interp`, :func:`~spatialmath.base.transforms3d.trinterp`, :func:`~spatialmath.base.quaternions.qslerp`, :func:`~spatialmath.base.transforms2d.trinterp2`
486486
487487
:SymPy: not supported
488488
"""
@@ -590,8 +590,8 @@ def stack(self):
590590

591591
# ----------------------- i/o stuff
592592

593-
def printline(self, arg=None, **kwargs):
594-
"""
593+
def printline(self, *args, **kwargs):
594+
r"""
595595
Print pose in compact single line format (superclass method)
596596
597597
:param arg: value for orient option, optional
@@ -618,7 +618,6 @@ def printline(self, arg=None, **kwargs):
618618
============= =================================================
619619
``orient`` description
620620
============= =================================================
621-
622621
``'rpy/zyx'`` roll-pitch-yaw angles in ZYX axis order [default]
623622
``'rpy/yxz'`` roll-pitch-yaw angles in YXZ axis order
624623
``'rpy/zyx'`` roll-pitch-yaw angles in ZYX axis order
@@ -631,38 +630,33 @@ def printline(self, arg=None, **kwargs):
631630
632631
.. runblock:: pycon
633632
633+
>>> from spatialmath import SE2, SE3
634634
>>> x = SE3.Rx(0.3)
635635
>>> x.printline()
636-
>>> x = SE3.Rx([0.2, 0.3], 'rpy/xyz')
636+
>>> x = SE3.Rx([0.2, 0.3])
637637
>>> x.printline()
638638
>>> x.printline('angvec')
639639
>>> x.printline(orient='angvec', fmt="{:.6f}")
640640
>>> x = SE2(1, 2, 0.3)
641641
>>> x.printline()
642-
>>> SE3.Rand(N=3).printline(fmt='{:8.3g}')
643642
644643
.. note::
645644
- Default formatting is for compact display of data
646645
- For tabular data set ``fmt`` to a fixed width format such as
647646
``fmt='{:.3g}'``
648647
649-
:seealso: :func:`trprint`, :func:`trprint2`
648+
:seealso: :meth:`strline` :func:`trprint`, :func:`trprint2`
650649
"""
651-
if arg is not None and kwargs == {}:
652-
if isinstance(arg, str):
653-
kwargs = dict(orient=arg)
654-
else:
655-
raise ValueError('single argument must be a string')
656650
if self.N == 2:
657651
for x in self.data:
658-
base.trprint2(x, **kwargs)
652+
base.trprint2(x, *args, **kwargs)
659653
else:
660654
for x in self.data:
661-
base.trprint(x, **kwargs)
655+
base.trprint(x, *args, **kwargs)
662656

663657
def strline(self, *args, **kwargs):
664658
"""
665-
Print pose in compact single line format (superclass method)
659+
Convert pose to compact single line string (superclass method)
666660
667661
:param label: text label to put at start of line
668662
:type label: str
@@ -675,28 +669,44 @@ def strline(self, *args, **kwargs):
675669
:type orient: str
676670
:param unit: angular units: 'rad' [default], or 'deg'
677671
:type unit: str
672+
:return: pose in string format
673+
:rtype: str
678674
679-
Print pose in a compact single line format. If ``X`` has multiple
680-
values, print one per line.
675+
Convert pose in a compact single line format. If ``X`` has multiple
676+
values, the string has one pose per line.
677+
678+
Orientation can be displayed in various formats:
679+
680+
============= =================================================
681+
``orient`` description
682+
============= =================================================
683+
``'rpy/zyx'`` roll-pitch-yaw angles in ZYX axis order [default]
684+
``'rpy/yxz'`` roll-pitch-yaw angles in YXZ axis order
685+
``'rpy/zyx'`` roll-pitch-yaw angles in ZYX axis order
686+
``'eul'`` Euler angles in ZYZ axis order
687+
``'angvec'`` angle and axis
688+
============= =================================================
681689
682690
Example:
683691
684692
.. runblock:: pycon
685693
694+
>>> from spatialmath import SE2, SE3
686695
>>> x = SE3.Rx(0.3)
687-
>>> x.printline()
688-
>>> x = SE3.Rx([0.2, 0.3], 'rpy/xyz')
689-
>>> x.printline()
696+
>>> x.strline()
697+
>>> x = SE3.Rx([0.2, 0.3])
698+
>>> x.strline()
699+
>>> x.strline('angvec')
700+
>>> x.strline(orient='angvec', fmt="{:.6f}")
690701
>>> x = SE2(1, 2, 0.3)
691-
>>> x.printline()
692-
>>> SE3.Rand(N=3).printline(fmt='{:8.3g}')
702+
>>> x.strline()
693703
694704
.. note::
695705
- Default formatting is for compact display of data
696706
- For tabular data set ``fmt`` to a fixed width format such as
697707
``fmt='{:.3g}'``
698708
699-
:seealso: :func:`trprint`, :func:`trprint2`
709+
:seealso: :meth:`printline` :func:`trprint`, :func:`trprint2`
700710
"""
701711
s = ""
702712
if self.N == 2:

‎spatialmath/pose3d.py

Copy file name to clipboardExpand all lines: spatialmath/pose3d.py
+34-33Lines changed: 34 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -743,7 +743,7 @@ def angdist(self, other, metric=6):
743743
744744
.. runblock:: pycon
745745
746-
>>> from spatialmath import UnitQuaternion
746+
>>> from spatialmath import SO3
747747
>>> R1 = SO3.Rx(0.3)
748748
>>> R2 = SO3.Ry(0.3)
749749
>>> print(R1.angdist(R1))
@@ -875,18 +875,15 @@ def t(self):
875875
``x.t`` is the translational component of ``x`` as an array with
876876
shape (3,). If ``len(x) > 1``, return an array with shape=(N,3).
877877
878-
.. runblock:: pycon
878+
Example:
879879
880-
>>> from spatialmath import UnitQuaternion
880+
.. runblock:: pycon
881881
882+
>>> from spatialmath import SE3
882883
>>> x = SE3(1,2,3)
883884
>>> x.t
884-
array([1., 2., 3.])
885885
>>> x = SE3([ SE3(1,2,3), SE3(4,5,6)])
886886
>>> x.t
887-
array([[1., 2., 3.],
888-
[4., 5., 6.]])
889-
890887
891888
:SymPy: supported
892889
"""
@@ -918,14 +915,14 @@ def inv(self):
918915
T = \left[ \begin{array}{cc} \mat{R} & \vec{t} \\ 0 & 1 \end{array} \right],
919916
\mat{T}^{-1} = \left[ \begin{array}{cc} \mat{R}^T & -\mat{R}^T \vec{t} \\ 0 & 1 \end{array} \right]`
920917
921-
Example::
918+
Example:
919+
920+
.. runblock:: pycon
922921
922+
>>> from spatialmath import SE3
923923
>>> x = SE3(1,2,3)
924924
>>> x.inv()
925-
SE3(array([[ 1., 0., 0., -1.],
926-
[ 0., 1., 0., -2.],
927-
[ 0., 0., 1., -3.],
928-
[ 0., 0., 0., 1.]]))
925+
929926
930927
:seealso: :func:`~spatialmath.base.transforms3d.trinv`
931928
@@ -949,13 +946,15 @@ def delta(self, X2=None):
949946
The vector :math:`d = [\delta_x, \delta_y, \delta_z, \theta_x, \theta_y, \theta_z]`
950947
represents infinitesimal translation and rotation.
951948
952-
Example::
949+
Example:
950+
951+
.. runblock:: pycon
953952
953+
>>> from spatialmath import SE3
954954
>>> x1 = SE3.Rx(0.3)
955955
>>> x2 = SE3.Rx(0.3001)
956956
>>> x1.delta(x2)
957-
array([0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 9.99999998e-05,
958-
0.00000000e+00, 0.00000000e+00])
957+
959958
960959
.. note::
961960
@@ -1032,11 +1031,13 @@ def twist(self):
10321031
:return: equivalent rigid-body motion as a twist vector
10331032
:rtype: Twist3 instance
10341033
1035-
Example::
1034+
Example:
10361035
1036+
.. runblock:: pycon
1037+
1038+
>>> from spatialmath import SE3
10371039
>>> x = SE3(1,2,3)
10381040
>>> x.twist()
1039-
Twist3([1, 2, 3, 0, 0, 0])
10401041
10411042
:seealso: :func:`spatialmath.twist.Twist3`
10421043
"""
@@ -1089,6 +1090,7 @@ def Rx(cls, theta, unit='rad', t=None):
10891090
10901091
.. runblock:: pycon
10911092
1093+
>>> from spatialmath import SE3
10921094
>>> SE3.Rx(0.3)
10931095
>>> SE3.Rx([0.3, 0.4])
10941096
@@ -1124,6 +1126,7 @@ def Ry(cls, theta, unit='rad', t=None):
11241126
11251127
.. runblock:: pycon
11261128
1129+
>>> from spatialmath import SE3
11271130
>>> SE3.Ry(0.3)
11281131
>>> SE3.Ry([0.3, 0.4])
11291132
@@ -1159,6 +1162,7 @@ def Rz(cls, theta, unit='rad', t=None):
11591162
11601163
.. runblock:: pycon
11611164
1165+
>>> from spatialmath import SE3
11621166
>>> SE3.Rz(0.3)
11631167
>>> SE3.Rz([0.3, 0.4])
11641168
@@ -1189,18 +1193,13 @@ def Rand(cls, N=1, xrange=(-1, 1), yrange=(-1, 1), zrange=(-1, 1)): # pylint: d
11891193
- ``SE3.Rand(N)`` is an SE3 object containing a sequence of N random
11901194
poses.
11911195
1192-
Example::
11931196
1197+
Example:
1198+
1199+
.. runblock:: pycon
1200+
1201+
>>> from spatialmath import SE3
11941202
>>> SE3.Rand(2)
1195-
SE3([
1196-
array([[ 0.58076657, 0.64578702, -0.49565041, -0.78585825],
1197-
[-0.57373134, -0.10724881, -0.8119914 , 0.72069253],
1198-
[-0.57753142, 0.75594763, 0.30822173, 0.12291999],
1199-
[ 0. , 0. , 0. , 1. ]]),
1200-
array([[ 0.96481299, -0.26267256, -0.01179066, 0.80294729],
1201-
[ 0.06421463, 0.19190584, 0.97931028, -0.15021311],
1202-
[-0.25497525, -0.94560841, 0.20202067, 0.02684599],
1203-
[ 0. , 0. , 0. , 1. ]]) ])
12041203
12051204
:seealso: :func:`~spatialmath.quaternions.UnitQuaternion.Rand`
12061205
"""
@@ -1333,13 +1332,12 @@ def OA(cls, o, a):
13331332
- ``o`` and ``a`` do not have to be orthogonal, so long as they are not parallel
13341333
``o`` is adjusted to be orthogonal to ``a``.
13351334
1336-
Example::
1335+
Example:
1336+
1337+
.. runblock:: pycon
13371338
1339+
>>> from spatialmath import SE3
13381340
>>> SE3.OA([1, 0, 0], [0, 0, -1])
1339-
SE3(array([[-0., 1., 0., 0.],
1340-
[ 1., 0., 0., 0.],
1341-
[ 0., 0., -1., 0.],
1342-
[ 0., 0., 0., 1.]]))
13431341
13441342
:seealso: :func:`~spatialmath.base.transforms3d.oa2r`
13451343
"""
@@ -1519,6 +1517,7 @@ def Tx(cls, x):
15191517
15201518
.. runblock:: pycon
15211519
1520+
>>> from spatialmath import SE3
15221521
>>> SE3.Tx(2)
15231522
>>> SE3.Tx([2,3])
15241523
@@ -1545,6 +1544,7 @@ def Ty(cls, y):
15451544
15461545
.. runblock:: pycon
15471546
1547+
>>> from spatialmath import SE3
15481548
>>> SE3.Ty(2)
15491549
>>> SE3.Ty([2,3])
15501550
@@ -1570,6 +1570,7 @@ def Tz(cls, z):
15701570
15711571
.. runblock:: pycon
15721572
1573+
>>> from spatialmath import SE3
15731574
>>> SE3.Tz(2)
15741575
>>> SE3.Tz([2,3])
15751576
@@ -1638,7 +1639,7 @@ def angdist(self, other, metric=6):
16381639
16391640
.. runblock:: pycon
16401641
1641-
>>> from spatialmath import UnitQuaternion
1642+
>>> from spatialmath import SE3
16421643
>>> T1 = SE3.Rx(0.3)
16431644
>>> T2 = SE3.Ry(0.3)
16441645
>>> print(T1.angdist(T1))

‎spatialmath/spatialvector.py

Copy file name to clipboardExpand all lines: spatialmath/spatialvector.py
+19-2Lines changed: 19 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,11 +39,28 @@ class SpatialVector(BasePoseList):
3939
``+`` addition of spatial vectors of the same subclass
4040
``-`` subtraction of spatial vectors of the same subclass
4141
``-`` unary minus
42-
``*`` premultiplication by Twist3 is transformation to new frame
42+
``*`` see table below
4343
``^`` cross product x or x*
4444
======== ===========================================================
4545
4646
47+
Certain subtypes can be multiplied
48+
49+
=================== ==================== =================== =========================
50+
Multiplicands Product
51+
------------------------------------------ ----------------------------------------------
52+
left right type operation
53+
=================== ==================== =================== =========================
54+
SE3, Twist3 SpatialVelocity SpatialVelocity adjoint product
55+
SE3, Twist3 SpatialAcceleration SpatialAcceleration adjoint product
56+
SE3, Twist3 SpatialMomentum SpatialMomentum adjoint transpose product
57+
SE3, Twist3 SpatialForce SpatialForce adjoint transpose product
58+
SpatialAcceleration SpatialInertia SpatialForce matrix-vector product**
59+
SpatialVelocity SpatialInertia SpatialMomentum matrix-vector product**
60+
=================== ==================== =================== =========================
61+
62+
** indicates commutative operator.
63+
4764
.. inheritance-diagram:: spatialmath.spatialvector.SpatialVelocity spatialmath.spatialvector.SpatialAcceleration spatialmath.spatialvector.SpatialForce spatialmath.spatialvector.SpatialMomentum
4865
:top-classes: spatialmath.spatialvector.SpatialVector
4966
:parts: 1
@@ -442,7 +459,7 @@ def __init__(self, value=None):
442459
super().__init__(value)
443460
# n = SpatialForce(val);
444461

445-
def __rmul(right, left): # lgtm[py/not-named-self] pylint: disable=no-self-argument
462+
def __rmul__(right, left): # lgtm[py/not-named-self] pylint: disable=no-self-argument
446463
# Twist * SpatialForce -> SpatialForce
447464
return SpatialForce(left.Ad.T @ right.A)
448465

0 commit comments

Comments
0 (0)
Morty Proxy This is a proxified and sanitized view of the page, visit original site.