YARP
Yet Another Robot Platform
Quaternion.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 #ifndef YARP_QUATERNION
10 #define YARP_QUATERNION
11 
12 #include <yarp/math/api.h>
13 #include <yarp/sig/Vector.h>
14 #include <yarp/sig/Matrix.h>
15 #include <yarp/os/Portable.h>
16 
17 // network stuff
18 #include <yarp/os/NetInt32.h>
19 
20 namespace yarp {
21  namespace math {
22  class Quaternion;
23  }
24 }
25 
27 {
28  double internal_data[4]; // stored as [w x y z]
29 
30 public:
31  Quaternion();
32  Quaternion(double x, double y, double z, double w);
33  double* data();
34  const double* data() const;
35  double x() const;
36  double y() const;
37  double z() const;
38  double w() const;
39  double& x() ;
40  double& y() ;
41  double& z() ;
42  double& w() ;
43 
44  std::string toString(int precision = -1, int width = -1) const;
45 
49  double abs();
50 
54  void normalize();
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 
106  void fromRotationMatrix(const yarp::sig::Matrix &R);
107 
108 #ifndef YARP_NO_DEPRECATED // Since YARP 3.0.0
109 
114  YARP_DEPRECATED_MSG("Use toRotationMatrix4x4 instead")
115  yarp::sig::Matrix toRotationMatrix() const { return toRotationMatrix4x4(); }
116 #endif
117 
144 
151 
155  yarp::sig::Vector toVector() const;
156 
158  /*
159  * Read vector from a connection.
160  * return true iff a vector was read correctly
161  */
162  bool read(yarp::os::ConnectionReader& connection) override;
163 
168  bool write(yarp::os::ConnectionWriter& connection) const override;
169 
170  yarp::os::Type getType() const override
171  {
172  return yarp::os::Type::byName("yarp/quaternion");
173  }
174 
175 
176 };
177 
178 #endif
yarp::os::Portable
This is a base class for objects that can be both read from and be written to the YARP network.
Definition: Portable.h:29
yarp::math::Quaternion::fromRotationMatrix
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
Definition: Quaternion.cpp:154
Vector.h
contains the definition of a Vector type
yarp::math::Quaternion::y
double y() const
Definition: Quaternion.cpp:80
yarp::os::Type
Definition: Type.h:24
NetInt32.h
yarp::math::Quaternion::z
double z() const
Definition: Quaternion.cpp:85
Portable.h
yarp::math::Quaternion::toString
std::string toString(int precision=-1, int width=-1) const
Definition: Quaternion.cpp:249
yarp::math::Quaternion::toRotationMatrix4x4
yarp::sig::Matrix toRotationMatrix4x4() const
Converts a quaternion to a rotation matrix.
Definition: Quaternion.cpp:211
Matrix.h
contains the definition of a Matrix type
yarp::math::Quaternion::data
double * data()
Definition: Quaternion.cpp:55
yarp::math::Quaternion::normalize
void normalize()
Normalizes the quaternion elements.
Definition: Quaternion.cpp:310
yarp::math::Quaternion::Quaternion
Quaternion()
Definition: Quaternion.cpp:34
yarp::math::Quaternion::getType
yarp::os::Type getType() const override
Definition: Quaternion.h:170
yarp::math::Quaternion::abs
double abs()
Computes the modulus of the quaternion.
Definition: Quaternion.cpp:302
yarp::math::Quaternion::toRotationMatrix3x3
yarp::sig::Matrix toRotationMatrix3x3() const
Converts a quaternion to a rotation matrix.
Definition: Quaternion.cpp:230
yarp::math::Quaternion::x
double x() const
Definition: Quaternion.cpp:75
yarp::sig::VectorOf< double >
yarp::os::Type::byName
static Type byName(const char *name)
Definition: Type.cpp:174
yarp::math::Quaternion::fromAxisAngle
void fromAxisAngle(const yarp::sig::Vector &v)
Computes the quaternion from an axis-angle representation.
Definition: Quaternion.cpp:271
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::math::Quaternion::arg
double arg()
Computes the argument or phase of the quaternion in radians.
Definition: Quaternion.cpp:320
yarp::math::Quaternion::inverse
Quaternion inverse() const
Computes the inverse of the quaternion.
Definition: Quaternion.cpp:328
yarp::math::Quaternion
Definition: Quaternion.h:27
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
yarp::math::Quaternion::w
double w() const
Definition: Quaternion.cpp:70
YARP_DEPRECATED_MSG
#define YARP_DEPRECATED_MSG(MSG)
Expands to either the standard [[deprecated]] attribute or a compiler-specific decorator such as __at...
Definition: compiler.h:2883
yarp::math::Quaternion::toAxisAngle
yarp::sig::Vector toAxisAngle()
Definition: Quaternion.cpp:295
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
geometry_msgs::Quaternion
yarp::rosmsg::geometry_msgs::Quaternion Quaternion
Definition: Quaternion.h:24
YARP_math_API
#define YARP_math_API
Definition: api.h:18
yarp::math::Quaternion::toVector
yarp::sig::Vector toVector() const
Converts the quaternion to a vector of length 4.
Definition: Quaternion.cpp:60
yarp::math::Quaternion::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write vector to a connection.
Definition: Quaternion.cpp:133
yarp::math::Quaternion::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Quaternion.cpp:110
api.h
yarp::sig::Matrix
A class for a Matrix.
Definition: Matrix.h:46