Class SE3fFormatter

Class Documentation

class SE3fFormatter

Formats the se3 in easily readable translation/quaternion syntax.

If you are working with frames, what you usually want to read is the pose of the frame, i.e. the inverse of the transform.

e.g. if you have T_cam_rel_map, to get the pose of the cam frame relative to the map frame, pass T_cam_rel_map.inverse() to this formatter.

Public Functions

inline SE3fFormatter(const int &w = -1, const unsigned int &p = 2)

Default constructor.

Initialises the format tags for width, and precision.

Parameters:
  • w – : width (default - no width constraints)

  • p – : the number of decimal places of precision (default - 4)

inline virtual ~SE3fFormatter()
inline SE3fFormatter &precision(const unsigned int &p)

Sets the precision format parameter.

Parameters:

p – : the number of decimal places of precision.

Returns:

SE3fFormatter& : this formatter readied for use with a stream.

inline SE3fFormatter &width(const int &w)

Sets the width format parameter.

Sets the width format parameter.

Parameters:

w – : the width to use for inserted floats (-1 is no width constraint).

Returns:

FloatMatrixFormatter& : this formatter readied for use with a stream.

inline unsigned int precision()

Returns the current precision setting.

Returns:

unsigned int : the precision value.

inline int width()

Returns the current width setting.

Returns:

int : the witdh value (-1 for no width constraint).

inline SE3fFormatter &operator()(const Sophus::SE3f &s)

Format a sophus transform with permanently stored precision/width.

This function directly formats the specified input value with the stored settings.

cout << format(Sophus::SE3f()) << endl;

Parameters:

matrix – : the matrix to be formatted (gets temporarily stored as a pointer).

Returns:

FloatMatrixFormatter& : this formatter readied for use with a stream.

inline SE3fFormatter &operator()(const Sophus::SE3f &s, const int &w, const unsigned int &p)

Format a matrix with temporarily specified precision/width.

This function directly formats the specified input value and temporary settings.

Sophus::SE3f s;
cout << format(s,3,-1) << endl; // precision of 3 and no width constraint
Parameters:
  • matrix – : the matrix to be formatted (gets temporarily stored as a pointer).

  • w – : the width to use for inserted floats (-1 is no width constraint).

  • p – : the number of decimal places of precision.

Returns:

FloatMatrixFormatter& : this formatter readied for use with a stream.

Friends

template<typename OutputStream>
friend OutputStream &operator<<(OutputStream &ostream, SE3fFormatter &formatter)

Stream the formatter.

Insertion operator for sending the formatter to an output stream.

Parameters:
  • ostream – : the output stream.

  • formatter – : the formatter to be inserted.

Template Parameters:
  • OutputStream – : the type of the output stream to be inserted into.

  • Derived – : matrix type.

Throws:

StandardException – : throws if the formatter has un-specified _matrix [debug mode only]

Returns:

OutputStream : continue streaming with the updated output stream.