YARP
Yet Another Robot Platform
yarp::math::Quaternion Class Reference

#include <yarp/math/Quaternion.h>

+ Inheritance diagram for yarp::math::Quaternion:

Public Member Functions

 Quaternion ()
 
 Quaternion (double x, double y, double z, double w)
 
double * data ()
 
const double * data () const
 
double x () const
 
double y () const
 
double z () const
 
double w () const
 
double & x ()
 
double & y ()
 
double & z ()
 
double & w ()
 
std::string toString (int precision=-1, int width=-1) const
 
double abs ()
 Computes the modulus of the quaternion. More...
 
void normalize ()
 Normalizes the quaternion elements. More...
 
Quaternion inverse () const
 Computes the inverse of the quaternion. More...
 
double arg ()
 Computes the argument or phase of the quaternion in radians. More...
 
void fromAxisAngle (const yarp::sig::Vector &v)
 Computes the quaternion from an axis-angle representation. More...
 
void fromAxisAngle (const yarp::sig::Vector &axis, const double &angle)
 Computes the quaternion from an axis-angle representation. More...
 
yarp::sig::Vector toAxisAngle ()
 
void fromRotationMatrix (const yarp::sig::Matrix &R)
 Converts a rotation matrix to a quaternion. More...
 
yarp::sig::Matrix toRotationMatrix () const
 Converts a quaternion to a rotation matrix. More...
 
yarp::sig::Matrix toRotationMatrix4x4 () const
 Converts a quaternion to a rotation matrix. More...
 
yarp::sig::Matrix toRotationMatrix3x3 () const
 Converts a quaternion to a rotation matrix. More...
 
yarp::sig::Vector toVector () const
 Converts the quaternion to a vector of length 4. More...
 
bool read (yarp::os::ConnectionReader &connection) override
 Read this object from a network connection. More...
 
bool write (yarp::os::ConnectionWriter &connection) const override
 Write vector to a connection. More...
 
yarp::os::Type getType () const override
 
- Public Member Functions inherited from yarp::os::PortReader
virtual ~PortReader ()
 Destructor. More...
 
virtual Type getReadType () const
 
- Public Member Functions inherited from yarp::os::PortWriter
virtual ~PortWriter ()
 Destructor. More...
 
virtual void onCompletion () const
 This is called when the port has finished all writing operations. More...
 
virtual void onCommencement () const
 This is called when the port is about to begin writing operations. More...
 
virtual yarp::os::Type getWriteType () const
 

Additional Inherited Members

- Static Public Member Functions inherited from yarp::os::Portable
static bool copyPortable (const PortWriter &writer, PortReader &reader)
 Copy one portable to another, via writing and reading. More...
 

Detailed Description

Definition at line 26 of file Quaternion.h.

Constructor & Destructor Documentation

◆ Quaternion() [1/2]

Quaternion::Quaternion ( )

Definition at line 34 of file Quaternion.cpp.

◆ Quaternion() [2/2]

Quaternion::Quaternion ( double  x,
double  y,
double  z,
double  w 
)

Definition at line 42 of file Quaternion.cpp.

Member Function Documentation

◆ abs()

double Quaternion::abs ( )

Computes the modulus of the quaternion.

Definition at line 302 of file Quaternion.cpp.

◆ arg()

double Quaternion::arg ( )

Computes the argument or phase of the quaternion in radians.

Definition at line 320 of file Quaternion.cpp.

◆ data() [1/2]

double * Quaternion::data ( )

Definition at line 55 of file Quaternion.cpp.

◆ data() [2/2]

const double * Quaternion::data ( ) const

Definition at line 50 of file Quaternion.cpp.

◆ fromAxisAngle() [1/2]

void Quaternion::fromAxisAngle ( const yarp::sig::Vector axis,
const double &  angle 
)

Computes the quaternion from an axis-angle representation.

Parameters
axisa 3D vector representing the axis. @angle the rotation angle (in radians)

Definition at line 282 of file Quaternion.cpp.

◆ fromAxisAngle() [2/2]

void Quaternion::fromAxisAngle ( const yarp::sig::Vector v)

Computes the quaternion from an axis-angle representation.

Parameters
va 4D vector, where the first three elements represent the axis, while the fourth element represents the angle (in radians)

Definition at line 271 of file Quaternion.cpp.

◆ fromRotationMatrix()

void Quaternion::fromRotationMatrix ( const yarp::sig::Matrix R)

Converts a rotation matrix to a quaternion.

The returned quaternion is ordered in the following way:

  • s = q_0 \in \mathbb{R} the real part of the quaternion
  • r = $ \begin{bmatrix} q_1 \\ q_2 \\ q_3 \end{bmatrix} \in \mathbb{R}^3 $ the imaginary part of the quaternion

The input rotation matrix and the output quaternion are related by the following formula:

\[ R(s,r) = I_{3\times3} + 2s r^{\wedge} + 2{r^\wedge}^2, \]

where $ r^{\wedge} $ is the skew-symmetric matrix such that:

\[ r \times v = r^\wedge v \]

Note
This method is compatible with the rotation-quaternion convention used in the ROS tf2 library.
Parameters
Rthe input rotation matrix.
Returns
4 by 1 vector for the quaternion representation in the form

\[ \mathbf{q}=q_0 + i \cdot q_1 + j \cdot q_2 + k \cdot q_3 \]

Definition at line 154 of file Quaternion.cpp.

◆ getType()

yarp::os::Type yarp::math::Quaternion::getType ( ) const
inlineoverridevirtual

Reimplemented from yarp::os::Portable.

Definition at line 170 of file Quaternion.h.

◆ inverse()

Quaternion Quaternion::inverse ( ) const

Computes the inverse of the quaternion.

Definition at line 328 of file Quaternion.cpp.

◆ normalize()

void Quaternion::normalize ( )

Normalizes the quaternion elements.

Definition at line 310 of file Quaternion.cpp.

◆ read()

bool Quaternion::read ( yarp::os::ConnectionReader reader)
overridevirtual

Read this object from a network connection.

Override this for your particular class.

Parameters
readeran interface to the network connection for reading
Returns
true iff the object is successfully read

Implements yarp::os::Portable.

Definition at line 110 of file Quaternion.cpp.

◆ toAxisAngle()

yarp::sig::Vector Quaternion::toAxisAngle ( )

Definition at line 295 of file Quaternion.cpp.

◆ toRotationMatrix()

yarp::sig::Matrix yarp::math::Quaternion::toRotationMatrix ( ) const
inline

Converts a quaternion to a rotation matrix.

Deprecated:
since YARP 3.0.0. Use toRotationMatrix4x4 instead.

Definition at line 115 of file Quaternion.h.

◆ toRotationMatrix3x3()

yarp::sig::Matrix Quaternion::toRotationMatrix3x3 ( ) const

Converts a quaternion to a rotation matrix.

Parameters
qthe quaternion
Returns
the corresponding 3 by 3 rotation matrix

Definition at line 230 of file Quaternion.cpp.

◆ toRotationMatrix4x4()

yarp::sig::Matrix Quaternion::toRotationMatrix4x4 ( ) const

Converts a quaternion to a rotation matrix.

The quaternion is expected to be ordered in the following way:

  • s = q_0 \in \mathbb{R} the real part of the quaternion
  • r = \begin{bmatrix} q_1 \ q_2 \ q_3 \end{bmatrix} \in \mathbb{R}^3 the imaginary part of the quaternion

The returned rotation matrix is given by the following formula:

\[ R(s,r) = I_{3\times3} + 2s r^{\wedge} + 2{r^\wedge}^2, \]

where $ r^{\wedge} $ is the skew-symmetric matrix such that:

\[ r \times v = r^\wedge v \]

Note
This method is compatible with the rotation-quaternion convention used in the ROS tf2 library.
Parameters
qthe 4 by 1 input quaternion in the form

\[ \mathbf{q}=q_0 + i \cdot q_1 + j \cdot q_2 + k \cdot q_3 \]

Returns
4 by 4 homogeneous matrix representing with the rotation components in the top left 3 by 3 submatrix.

Definition at line 211 of file Quaternion.cpp.

◆ toString()

std::string Quaternion::toString ( int  precision = -1,
int  width = -1 
) const

Definition at line 249 of file Quaternion.cpp.

◆ toVector()

yarp::sig::Vector Quaternion::toVector ( ) const

Converts the quaternion to a vector of length 4.

Definition at line 60 of file Quaternion.cpp.

◆ w() [1/2]

double & Quaternion::w ( )

Definition at line 90 of file Quaternion.cpp.

◆ w() [2/2]

double Quaternion::w ( ) const

Definition at line 70 of file Quaternion.cpp.

◆ write()

bool Quaternion::write ( yarp::os::ConnectionWriter connection) const
overridevirtual

Write vector to a connection.

return true iff a vector was written correctly

Implements yarp::os::Portable.

Definition at line 133 of file Quaternion.cpp.

◆ x() [1/2]

double & Quaternion::x ( )

Definition at line 95 of file Quaternion.cpp.

◆ x() [2/2]

double Quaternion::x ( ) const

Definition at line 75 of file Quaternion.cpp.

◆ y() [1/2]

double & Quaternion::y ( )

Definition at line 100 of file Quaternion.cpp.

◆ y() [2/2]

double Quaternion::y ( ) const

Definition at line 80 of file Quaternion.cpp.

◆ z() [1/2]

double & Quaternion::z ( )

Definition at line 105 of file Quaternion.cpp.

◆ z() [2/2]

double Quaternion::z ( ) const

Definition at line 85 of file Quaternion.cpp.


The documentation for this class was generated from the following files: