Pose6D.cpp
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 #include <octomap/math/Pose6D.h>
35 #include <math.h>
36 
37 namespace octomath {
38 
40  }
41 
42 
43  Pose6D::Pose6D(const Vector3 &trans, const Quaternion &rot) :
44  translation(trans),
45  rotation(rot)
46  { }
47 
48 
49 
50  Pose6D::Pose6D(float x, float y, float z, double roll, double pitch, double yaw) :
51  translation(x, y, z),
52  rotation(roll, pitch, yaw)
53  { }
54 
56  }
57 
58  Pose6D::Pose6D(const Pose6D& other) :
59  translation(other.trans()),
60  rotation(other.rot())
61  { }
62 
63  Pose6D& Pose6D::operator= (const Pose6D& other) {
64  translation = other.trans();
65  rotation = other.rot();
66  return *this;
67  }
68 
69 
70  Pose6D Pose6D::inv() const {
71  Pose6D result(*this);
72  result.rot() = rot().inv().normalized();
73  result.trans() = result.rot().rotate(-trans());
74  return result;
75  }
76 
77 
79  rot() = rot().inv().normalized();
80  trans() = rot().rotate(-trans());
81  return *this;
82  }
83 
84 
85  Vector3 Pose6D::transform (const Vector3 &v) const {
86  Vector3 res = this->rot().rotate(v);
87  res = res + this->trans();
88  return res;
89  }
90 
91  Pose6D Pose6D::operator* (const Pose6D& other) const {
92  Quaternion rot_new = rotation * other.rot();
93  Vector3 trans_new = rotation.rotate(other.trans()) + trans();
94  return Pose6D(trans_new, rot_new.normalized());
95  }
96 
97  const Pose6D& Pose6D::operator*= (const Pose6D& other) {
98  trans() += rotation.rotate(other.trans());
99  rot() = rot() * other.rot();
100  return *this;
101  }
102 
103  double Pose6D::distance (const Pose6D &other) const {
104  double dist_x = x() - other.x();
105  double dist_y = y() - other.y();
106  double dist_z = z() - other.z();
107  return sqrt(dist_x*dist_x + dist_y*dist_y + dist_z*dist_z);
108  }
109 
110  double Pose6D::transLength() const {
111  return sqrt(x()*x() + y()*y() + z()*z());
112  }
113 
114 
115  bool Pose6D::operator==(const Pose6D& other) const {
116  return translation == other.translation
117  && rotation == other.rotation;
118  }
119 
120  bool Pose6D::operator!=(const Pose6D& other) const {
121  return !(*this == other);
122  }
123 
124  std::istream& Pose6D::read(std::istream &s) {
125  translation.read(s);
126  rotation.read(s);
127  return s;
128  }
129 
130 
131  std::ostream& Pose6D::write(std::ostream &s) const {
132  translation.write(s);
133  s << " ";
134  rotation.write(s);
135  return s;
136  }
137 
138 
139  std::istream& Pose6D::readBinary(std::istream &s) {
141  rotation.readBinary(s);
142  return s;
143  }
144 
145 
146  std::ostream& Pose6D::writeBinary(std::ostream &s) const {
149  return s;
150  }
151 
152  std::ostream& operator<<(std::ostream& s, const Pose6D& p) {
153  s << "(" << p.x() << " " << p.y() << " " << p.z()
154  << ", " << p.rot().u() << " " << p.rot().x() << " " << p.rot().y() << " " << p.rot().z() << ")";
155  return s;
156  }
157 
158 }
octomath::Pose6D::x
float & x()
Definition: Pose6D.h:102
octomath::Pose6D::~Pose6D
~Pose6D()
Definition: Pose6D.cpp:55
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::Vector3::writeBinary
std::ostream & writeBinary(std::ostream &s) const
Definition: Vector3.cpp:99
octomath::Quaternion::x
float & x()
Definition: Quaternion.h:179
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::Pose6D::z
float & z()
Definition: Pose6D.h:104
octomath::Pose6D::operator*
Pose6D operator*(const Pose6D &p) const
Concatenation.
Definition: Pose6D.cpp:91
octomath::Quaternion::read
std::istream & read(std::istream &s)
Definition: Quaternion.cpp:261
octomath::Quaternion::writeBinary
std::ostream & writeBinary(std::ostream &s) const
Definition: Quaternion.cpp:291
octomath::Quaternion::write
std::ostream & write(std::ostream &s) const
Definition: Quaternion.cpp:270
octomath::Quaternion::normalized
Quaternion normalized() const
Definition: Quaternion.cpp:241
octomath::Pose6D::y
float & y()
Definition: Pose6D.h:103
octomath::Vector3
This class represents a three-dimensional vector.
Definition: Vector3.h:50
octomath::Quaternion::rotate
Vector3 rotate(const Vector3 &v) const
Rotate a vector.
Definition: Quaternion.cpp:255
octomath::Vector3::read
std::istream & read(std::istream &s)
Definition: Vector3.cpp:69
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
Pose6D.h
octomath
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::Quaternion::y
float & y()
Definition: Quaternion.h:180
octomath::Quaternion::inv
Quaternion inv() const
Inversion.
Definition: Quaternion.h:156
octomath::Pose6D::Pose6D
Pose6D()
Definition: Pose6D.cpp:39
octomath::Vector3::readBinary
std::istream & readBinary(std::istream &s)
Definition: Vector3.cpp:87
octomath::Vector3::write
std::ostream & write(std::ostream &s) const
Definition: Vector3.cpp:78
octomath::Pose6D::write
std::ostream & write(std::ostream &s) const
Output operator.
Definition: Pose6D.cpp:131
octomath::Quaternion::u
float & u()
Definition: Quaternion.h:178
octomath::Pose6D::rot
Quaternion & rot()
Rotational component.
Definition: Pose6D.h:88
octomath::Pose6D::inv_IP
Pose6D & inv_IP()
Inversion.
Definition: Pose6D.cpp:78
octomath::Pose6D::operator!=
bool operator!=(const Pose6D &other) const
Definition: Pose6D.cpp:120
octomath::Quaternion::readBinary
std::istream & readBinary(std::istream &s)
Definition: Quaternion.cpp:279
octomath::Pose6D
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
octomath::Quaternion::z
float & z()
Definition: Quaternion.h:181
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