Skip to content

Commit 21eb29f

Browse files
committed
optional arg for printline, value of orientation can be specified without keyword
doco update
1 parent adf34ea commit 21eb29f

File tree

1 file changed

+25
-3
lines changed

1 file changed

+25
-3
lines changed

spatialmath/baseposematrix.py

+25-3
Original file line numberDiff line numberDiff line change
@@ -590,10 +590,12 @@ def stack(self):
590590

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

593-
def printline(self, **kwargs):
593+
def printline(self, arg=None, **kwargs):
594594
"""
595595
Print pose in compact single line format (superclass method)
596-
596+
597+
:param arg: value for orient option, optional
598+
:type arg: str
597599
:param label: text label to put at start of line
598600
:type label: str
599601
:param fmt: conversion format for each number as used by ``format()``
@@ -608,10 +610,23 @@ def printline(self, **kwargs):
608610
:param file: file to write formatted string to. [default, stdout]
609611
:type file: file object
610612
611-
612613
Print pose in a compact single line format. If ``X`` has multiple
613614
values, print one per line.
614615
616+
Orientation can be displayed in various formats:
617+
618+
============= =================================================
619+
``orient`` description
620+
============= =================================================
621+
622+
``'rpy/zyx'`` roll-pitch-yaw angles in ZYX axis order [default]
623+
``'rpy/yxz'`` roll-pitch-yaw angles in YXZ axis order
624+
``'rpy/zyx'`` roll-pitch-yaw angles in ZYX axis order
625+
``'eul'`` Euler angles in ZYZ axis order
626+
``'angvec'`` angle and axis
627+
============= =================================================
628+
629+
615630
Example:
616631
617632
.. runblock:: pycon
@@ -620,6 +635,8 @@ def printline(self, **kwargs):
620635
>>> x.printline()
621636
>>> x = SE3.Rx([0.2, 0.3], 'rpy/xyz')
622637
>>> x.printline()
638+
>>> x.printline('angvec')
639+
>>> x.printline(orient='angvec', fmt="{:.6f}")
623640
>>> x = SE2(1, 2, 0.3)
624641
>>> x.printline()
625642
>>> SE3.Rand(N=3).printline(fmt='{:8.3g}')
@@ -631,6 +648,11 @@ def printline(self, **kwargs):
631648
632649
:seealso: :func:`trprint`, :func:`trprint2`
633650
"""
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')
634656
if self.N == 2:
635657
for x in self.data:
636658
base.trprint2(x, **kwargs)

0 commit comments

Comments
 (0)