3
3
# MIT Licence, see details in top-level file: LICENCE
4
4
5
5
import numpy as np
6
+ from sympy .core .singleton import S
6
7
from spatialmath .base import base
7
8
from spatialmath .baseposelist import BasePoseList
8
9
from spatialmath .base import symbolic as sym
@@ -592,14 +593,55 @@ def printline(self, *args, **kwargs):
592
593
:type unit: str
593
594
:param file: file to write formatted string to. [default, stdout]
594
595
:type file: file object
595
- :return: the formatted value as a string
596
- :rtype: str
597
596
598
- - ``X.printline()`` print ``X`` in single-line format
599
- - ``X.printline(file=None)`` is a string representing the pose ``X`` in
600
- single-line format
597
+ Print pose in a compact single line format. If ``X`` has multiple
598
+ values, print one per line.
599
+
600
+ Example:
601
+
602
+ .. runblock:: pycon
603
+
604
+ >>> x = SE3.Rx(0.3)
605
+ >>> x.printline()
606
+ >>> x = SE3.Rx([0.2, 0.3], 'rpy/xyz')
607
+ >>> x.printline()
608
+ >>> x = SE2(1, 2, 0.3)
609
+ >>> x.printline()
610
+ >>> SE3.Rand(N=3).printline(fmt='{:8.3g}')
611
+
612
+ .. note::
613
+ - Default formatting is for compact display of data
614
+ - For tabular data set ``fmt`` to a fixed width format such as
615
+ ``fmt='{:.3g}'``
616
+
617
+ :seealso: :func:`trprint`, :func:`trprint2`
618
+ """
619
+ if self .N == 2 :
620
+ for x in self .data :
621
+ base .trprint2 (x , * args , ** kwargs )
622
+ else :
623
+ for x in self .data :
624
+ base .trprint (x , * args , ** kwargs )
625
+
626
+
627
+ def strline (self , * args , ** kwargs ):
628
+ """
629
+ Print pose in compact single line format (superclass method)
630
+
631
+ :param label: text label to put at start of line
632
+ :type label: str
633
+ :param fmt: conversion format for each number as used by ``format()``
634
+ :type fmt: str
635
+ :param label: text label to put at start of line
636
+ :type label: str
637
+ :param orient: 3-angle convention to use, optional, ``SO3`` and ``SE3``
638
+ only
639
+ :type orient: str
640
+ :param unit: angular units: 'rad' [default], or 'deg'
641
+ :type unit: str
601
642
602
- If ``X`` has multiple values, print one per line.
643
+ Print pose in a compact single line format. If ``X`` has multiple
644
+ values, print one per line.
603
645
604
646
Example:
605
647
@@ -620,12 +662,14 @@ def printline(self, *args, **kwargs):
620
662
621
663
:seealso: :func:`trprint`, :func:`trprint2`
622
664
"""
665
+ s = ''
623
666
if self .N == 2 :
624
667
for x in self .data :
625
- return base .trprint2 (x , * args , ** kwargs )
668
+ s += base .trprint2 (x , * args , file = False , ** kwargs )
626
669
else :
627
670
for x in self .data :
628
- return base .trprint (x , * args , ** kwargs )
671
+ s += base .trprint (x , * args , file = False , ** kwargs )
672
+ return s
629
673
630
674
def __repr__ (self ):
631
675
"""
0 commit comments