|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
9 #ifndef YARP_QUATERNION
10 #define YARP_QUATERNION
28 double internal_data[4];
32 Quaternion(
double x,
double y,
double z,
double w);
34 const double*
data()
const;
44 std::string
toString(
int precision = -1,
int width = -1)
const;
108 #ifndef YARP_NO_DEPRECATED // Since YARP 3.0.0
This is a base class for objects that can be both read from and be written to the YARP network.
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
contains the definition of a Vector type
std::string toString(int precision=-1, int width=-1) const
yarp::sig::Matrix toRotationMatrix4x4() const
Converts a quaternion to a rotation matrix.
contains the definition of a Matrix type
void normalize()
Normalizes the quaternion elements.
yarp::os::Type getType() const override
double abs()
Computes the modulus of the quaternion.
yarp::sig::Matrix toRotationMatrix3x3() const
Converts a quaternion to a rotation matrix.
static Type byName(const char *name)
void fromAxisAngle(const yarp::sig::Vector &v)
Computes the quaternion from an axis-angle representation.
An interface for writing to a network connection.
double arg()
Computes the argument or phase of the quaternion in radians.
Quaternion inverse() const
Computes the inverse of the quaternion.
An interface for reading from a network connection.
#define YARP_DEPRECATED_MSG(MSG)
Expands to either the standard [[deprecated]] attribute or a compiler-specific decorator such as __at...
yarp::sig::Vector toAxisAngle()
The main, catch-all namespace for YARP.
yarp::rosmsg::geometry_msgs::Quaternion Quaternion
yarp::sig::Vector toVector() const
Converts the quaternion to a vector of length 4.
bool write(yarp::os::ConnectionWriter &connection) const override
Write vector to a connection.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.