Pose6D.h
Go to the documentation of this file.
1 /*
2  * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
3  * https://octomap.github.io/
4  *
5  * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg
6  * All rights reserved.
7  * License: New BSD
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above copyright
15  * notice, this list of conditions and the following disclaimer in the
16  * documentation and/or other materials provided with the distribution.
17  * * Neither the name of the University of Freiburg nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #ifndef OCTOMATH_POSE6D_H
35 #define OCTOMATH_POSE6D_H
36 
37 #include "Vector3.h"
38 #include "Quaternion.h"
39 
40 namespace octomath {
41 
49  class Pose6D {
50  public:
51 
52  Pose6D();
53  ~Pose6D();
54 
60  Pose6D(const Vector3& trans, const Quaternion& rot);
61 
69  Pose6D(float x, float y, float z, double roll, double pitch, double yaw);
70 
71  Pose6D(const Pose6D& other);
72  Pose6D& operator= (const Pose6D& other);
73 
74  bool operator==(const Pose6D& other) const;
75  bool operator!=(const Pose6D& other) const;
76 
82  inline Vector3& trans() { return translation; }
88  inline Quaternion& rot() { return rotation; }
94  const Vector3& trans() const { return translation; }
99  const Quaternion& rot() const { return rotation; }
100 
101 
102  inline float& x() { return translation(0); }
103  inline float& y() { return translation(1); }
104  inline float& z() { return translation(2); }
105  inline const float& x() const { return translation(0); }
106  inline const float& y() const { return translation(1); }
107  inline const float& z() const { return translation(2); }
108 
109  inline double roll() const {return (rotation.toEuler())(0); }
110  inline double pitch() const {return (rotation.toEuler())(1); }
111  inline double yaw() const {return (rotation.toEuler())(2); }
112 
121  Vector3 transform (const Vector3 &v) const;
122 
129  Pose6D inv() const;
130 
137  Pose6D& inv_IP();
138 
146  Pose6D operator* (const Pose6D &p) const;
154  const Pose6D& operator*= (const Pose6D &p);
155 
161  double distance(const Pose6D &other) const;
162 
169  double transLength() const;
170 
176  std::ostream& write(std::ostream &s) const;
182  std::istream& read(std::istream &s);
188  std::ostream& writeBinary(std::ostream &s) const;
194  std::istream& readBinary(std::istream &s);
195 
196  protected:
199  };
200 
202  std::ostream& operator<<(std::ostream& s, const Pose6D& p);
203 
204 }
205 
206 #endif
octomath::Pose6D::x
float & x()
Definition: Pose6D.h:102
octomath::Pose6D::~Pose6D
~Pose6D()
Definition: Pose6D.cpp:55
octomath::Pose6D::yaw
double yaw() const
Definition: Pose6D.h:111
octomath::Pose6D::x
const float & x() const
Definition: Pose6D.h:105
octomath::Pose6D::operator*=
const Pose6D & operator*=(const Pose6D &p)
In place concatenation.
Definition: Pose6D.cpp:97
octomath::Pose6D::translation
Vector3 translation
Definition: Pose6D.h:197
octomath::Pose6D::operator==
bool operator==(const Pose6D &other) const
Definition: Pose6D.cpp:115
octomath::operator<<
std::ostream & operator<<(std::ostream &s, const Pose6D &p)
user friendly output in format (x y z, u x y z) which is (translation, rotation)
Definition: Pose6D.cpp:152
octomath::Quaternion::toEuler
Vector3 toEuler() const
Conversion to Euler angles.
Definition: Quaternion.cpp:124
octomath::Pose6D::rot
const Quaternion & rot() const
Rotational component.
Definition: Pose6D.h:99
octomath::Pose6D::z
float & z()
Definition: Pose6D.h:104
octomath::Pose6D::y
const float & y() const
Definition: Pose6D.h:106
octomath::Pose6D::operator*
Pose6D operator*(const Pose6D &p) const
Concatenation.
Definition: Pose6D.cpp:91
octomath::Pose6D::y
float & y()
Definition: Pose6D.h:103
octomath::Vector3
This class represents a three-dimensional vector.
Definition: Vector3.h:50
octomath::Pose6D::trans
const Vector3 & trans() const
Translational component.
Definition: Pose6D.h:94
octomath::Pose6D::pitch
double pitch() const
Definition: Pose6D.h:110
octomath::Pose6D::transform
Vector3 transform(const Vector3 &v) const
Transformation of a vector.
Definition: Pose6D.cpp:85
octomath::Pose6D::rotation
Quaternion rotation
Definition: Pose6D.h:198
octomath
Quaternion.h
octomath::Pose6D::writeBinary
std::ostream & writeBinary(std::ostream &s) const
Binary output operator.
Definition: Pose6D.cpp:146
octomath::Pose6D::readBinary
std::istream & readBinary(std::istream &s)
Binary input operator.
Definition: Pose6D.cpp:139
octomath::Pose6D::z
const float & z() const
Definition: Pose6D.h:107
octomath::Pose6D::Pose6D
Pose6D()
Definition: Pose6D.cpp:39
octomath::Pose6D::write
std::ostream & write(std::ostream &s) const
Output operator.
Definition: Pose6D.cpp:131
octomath::Pose6D::rot
Quaternion & rot()
Rotational component.
Definition: Pose6D.h:88
Vector3.h
octomath::Pose6D::inv_IP
Pose6D & inv_IP()
Inversion.
Definition: Pose6D.cpp:78
octomath::Pose6D::roll
double roll() const
Definition: Pose6D.h:109
octomath::Pose6D::operator!=
bool operator!=(const Pose6D &other) const
Definition: Pose6D.cpp:120
octomath::Pose6D
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
octomath::Pose6D::operator=
Pose6D & operator=(const Pose6D &other)
Definition: Pose6D.cpp:63
octomath::Pose6D::distance
double distance(const Pose6D &other) const
Translational distance.
Definition: Pose6D.cpp:103
octomath::Pose6D::read
std::istream & read(std::istream &s)
Input operator.
Definition: Pose6D.cpp:124
octomath::Quaternion
This class represents a Quaternion.
Definition: Quaternion.h:56
octomath::Pose6D::inv
Pose6D inv() const
Inversion.
Definition: Pose6D.cpp:70
octomath::Pose6D::transLength
double transLength() const
Translational length.
Definition: Pose6D.cpp:110
octomath::Pose6D::trans
Vector3 & trans()
Translational component.
Definition: Pose6D.h:82


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Tue Dec 12 2023 03:39:40