#include <yarp/math/Quaternion.h>
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... | |
Definition at line 26 of file Quaternion.h.
Quaternion::Quaternion | ( | ) |
Definition at line 34 of file Quaternion.cpp.
Quaternion::Quaternion | ( | double | x, |
double | y, | ||
double | z, | ||
double | w | ||
) |
Definition at line 42 of file Quaternion.cpp.
double Quaternion::abs | ( | ) |
Computes the modulus of the quaternion.
Definition at line 302 of file Quaternion.cpp.
double Quaternion::arg | ( | ) |
Computes the argument or phase of the quaternion in radians.
Definition at line 320 of file Quaternion.cpp.
double * Quaternion::data | ( | ) |
Definition at line 55 of file Quaternion.cpp.
const double * Quaternion::data | ( | ) | const |
Definition at line 50 of file Quaternion.cpp.
void Quaternion::fromAxisAngle | ( | const yarp::sig::Vector & | axis, |
const double & | angle | ||
) |
Computes the quaternion from an axis-angle representation.
axis | a 3D vector representing the axis. @angle the rotation angle (in radians) |
Definition at line 282 of file Quaternion.cpp.
void Quaternion::fromAxisAngle | ( | const yarp::sig::Vector & | v | ) |
Computes the quaternion from an axis-angle representation.
v | a 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.
void Quaternion::fromRotationMatrix | ( | const yarp::sig::Matrix & | R | ) |
Converts a rotation matrix to a quaternion.
The returned quaternion is ordered in the following way:
The input rotation matrix and the output quaternion are related by the following formula:
where is the skew-symmetric matrix such that:
R | the input rotation matrix. |
Definition at line 154 of file Quaternion.cpp.
|
inlineoverridevirtual |
Reimplemented from yarp::os::Portable.
Definition at line 170 of file Quaternion.h.
Quaternion Quaternion::inverse | ( | ) | const |
Computes the inverse of the quaternion.
Definition at line 328 of file Quaternion.cpp.
void Quaternion::normalize | ( | ) |
Normalizes the quaternion elements.
Definition at line 310 of file Quaternion.cpp.
|
overridevirtual |
Read this object from a network connection.
Override this for your particular class.
reader | an interface to the network connection for reading |
Implements yarp::os::Portable.
Definition at line 110 of file Quaternion.cpp.
yarp::sig::Vector Quaternion::toAxisAngle | ( | ) |
Definition at line 295 of file Quaternion.cpp.
|
inline |
Converts a quaternion to a rotation matrix.
Definition at line 115 of file Quaternion.h.
yarp::sig::Matrix Quaternion::toRotationMatrix3x3 | ( | ) | const |
Converts a quaternion to a rotation matrix.
q | the quaternion |
Definition at line 230 of file Quaternion.cpp.
yarp::sig::Matrix Quaternion::toRotationMatrix4x4 | ( | ) | const |
Converts a quaternion to a rotation matrix.
The quaternion is expected to be ordered in the following way:
The returned rotation matrix is given by the following formula:
where is the skew-symmetric matrix such that:
q | the 4 by 1 input quaternion in the form
|
Definition at line 211 of file Quaternion.cpp.
std::string Quaternion::toString | ( | int | precision = -1 , |
int | width = -1 |
||
) | const |
Definition at line 249 of file Quaternion.cpp.
yarp::sig::Vector Quaternion::toVector | ( | ) | const |
Converts the quaternion to a vector of length 4.
Definition at line 60 of file Quaternion.cpp.
double & Quaternion::w | ( | ) |
Definition at line 90 of file Quaternion.cpp.
double Quaternion::w | ( | ) | const |
Definition at line 70 of file Quaternion.cpp.
|
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.
double & Quaternion::x | ( | ) |
Definition at line 95 of file Quaternion.cpp.
double Quaternion::x | ( | ) | const |
Definition at line 75 of file Quaternion.cpp.
double & Quaternion::y | ( | ) |
Definition at line 100 of file Quaternion.cpp.
double Quaternion::y | ( | ) | const |
Definition at line 80 of file Quaternion.cpp.
double & Quaternion::z | ( | ) |
Definition at line 105 of file Quaternion.cpp.
double Quaternion::z | ( | ) | const |
Definition at line 85 of file Quaternion.cpp.