YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Quaternion.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef YARP_QUATERNION
7#define YARP_QUATERNION
8
9#include <yarp/math/api.h>
10#include <yarp/sig/Vector.h>
11#include <yarp/sig/Matrix.h>
12#include <yarp/os/Portable.h>
13
14// network stuff
15#include <yarp/os/NetInt32.h>
16
17namespace yarp::math {
18class Quaternion;
19}
20
22{
23 double internal_data[4]; // stored as [w x y z]
24
25public:
26 Quaternion();
27 Quaternion(double x, double y, double z, double w);
28 double* data();
29 const double* data() const;
30 double x() const;
31 double y() const;
32 double z() const;
33 double w() const;
34 double& x() ;
35 double& y() ;
36 double& z() ;
37 double& w() ;
38
39 std::string toString(int precision = -1, int width = -1) const;
40
44 double abs();
45
49 void normalize();
50
54 bool isValid() const;
55
59 Quaternion inverse() const;
60
64 double arg();
65
70 void fromAxisAngle(const yarp::sig::Vector &v);
71
77 void fromAxisAngle(const yarp::sig::Vector& axis, const double& angle);
78
79
81
107
134
141
146
148 /*
149 * Read vector from a connection.
150 * return true iff a vector was read correctly
151 */
152 bool read(yarp::os::ConnectionReader& connection) override;
153
158 bool write(yarp::os::ConnectionWriter& connection) const override;
159
160 yarp::os::Type getType() const override
161 {
162 return yarp::os::Type::byName("yarp/quaternion");
163 }
164
165
166};
167
168#endif
contains the definition of a Matrix type
contains the definition of a Vector type
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
double abs()
Computes the modulus of the quaternion.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::sig::Vector toVector() const
Converts the quaternion to a vector of length 4.
yarp::sig::Matrix toRotationMatrix3x3() const
Converts a quaternion to a rotation matrix.
Quaternion inverse() const
Computes the inverse of the quaternion.
std::string toString(int precision=-1, int width=-1) const
void normalize()
Normalizes the quaternion elements.
void fromAxisAngle(const yarp::sig::Vector &v)
Computes the quaternion from an axis-angle representation.
double arg()
Computes the argument or phase of the quaternion in radians.
yarp::os::Type getType() const override
Definition Quaternion.h:160
yarp::sig::Matrix toRotationMatrix4x4() const
Converts a quaternion to a rotation matrix.
yarp::sig::Vector toAxisAngle()
bool isValid() const
Check if the quaternion is valid.
bool write(yarp::os::ConnectionWriter &connection) const override
Write vector to a connection.
An interface for reading from a network connection.
An interface for writing to a network connection.
This is a base class for objects that can be both read from and be written to the YARP network.
Definition Portable.h:25
static Type byName(const char *name)
Definition Type.cpp:171
A class for a Matrix.
Definition Matrix.h:39
The main, catch-all namespace for YARP.
Definition dirs.h:16
#define YARP_math_API
Definition api.h:17