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 4251e79

Browse filesBrowse files
committed
add strline, like printline but returns string, doesn't print
1 parent 6ea1e00 commit 4251e79
Copy full SHA for 4251e79

File tree

Expand file treeCollapse file tree

1 file changed

+52
-8
lines changed
Filter options
Expand file treeCollapse file tree

1 file changed

+52
-8
lines changed

‎spatialmath/baseposematrix.py

Copy file name to clipboardExpand all lines: spatialmath/baseposematrix.py
+52-8Lines changed: 52 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
# MIT Licence, see details in top-level file: LICENCE
44

55
import numpy as np
6+
from sympy.core.singleton import S
67
from spatialmath.base import base
78
from spatialmath.baseposelist import BasePoseList
89
from spatialmath.base import symbolic as sym
@@ -592,14 +593,55 @@ def printline(self, *args, **kwargs):
592593
:type unit: str
593594
:param file: file to write formatted string to. [default, stdout]
594595
:type file: file object
595-
:return: the formatted value as a string
596-
:rtype: str
597596
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
601642
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.
603645
604646
Example:
605647
@@ -620,12 +662,14 @@ def printline(self, *args, **kwargs):
620662
621663
:seealso: :func:`trprint`, :func:`trprint2`
622664
"""
665+
s = ''
623666
if self.N == 2:
624667
for x in self.data:
625-
return base.trprint2(x, *args, **kwargs)
668+
s += base.trprint2(x, *args, file=False, **kwargs)
626669
else:
627670
for x in self.data:
628-
return base.trprint(x, *args, **kwargs)
671+
s += base.trprint(x, *args, file=False, **kwargs)
672+
return s
629673

630674
def __repr__(self):
631675
"""

0 commit comments

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