Transform.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef TRANSFORM_H_
29 #define TRANSFORM_H_
30 
32 #include <vector>
33 #include <string>
34 #include <map>
35 #include <Eigen/Core>
36 #include <Eigen/Geometry>
37 #include <opencv2/core/core.hpp>
38 
39 namespace rtabmap {
40 
42 {
43 public:
44 
45  // Zero by default
46  Transform();
47  // rotation matrix r## and origin o##
48  Transform(float r11, float r12, float r13, float o14,
49  float r21, float r22, float r23, float o24,
50  float r31, float r32, float r33, float o34);
51  // should have 3 rows, 4 cols and type CV_32FC1
52  Transform(const cv::Mat & transformationMatrix);
53  // x,y,z, roll,pitch,yaw
54  Transform(float x, float y, float z, float roll, float pitch, float yaw);
55  // x,y,z, qx,qy,qz,qw
56  Transform(float x, float y, float z, float qx, float qy, float qz, float qw);
57  // x,y, theta
58  Transform(float x, float y, float theta);
59 
60  Transform clone() const;
61 
62  float r11() const {return data()[0];}
63  float r12() const {return data()[1];}
64  float r13() const {return data()[2];}
65  float r21() const {return data()[4];}
66  float r22() const {return data()[5];}
67  float r23() const {return data()[6];}
68  float r31() const {return data()[8];}
69  float r32() const {return data()[9];}
70  float r33() const {return data()[10];}
71 
72  float o14() const {return data()[3];}
73  float o24() const {return data()[7];}
74  float o34() const {return data()[11];}
75 
76  float & operator[](int index) {return data()[index];}
77  const float & operator[](int index) const {return data()[index];}
78  float & operator()(int row, int col) {return data()[row*4 + col];}
79  const float & operator()(int row, int col) const {return data()[row*4 + col];}
80 
81  bool isNull() const;
82  bool isIdentity() const;
83 
84  void setNull();
85  void setIdentity();
86 
87  const cv::Mat & dataMatrix() const {return data_;}
88  const float * data() const {return (const float *)data_.data;}
89  float * data() {return (float *)data_.data;}
90  int size() const {return 12;}
91 
92  float & x() {return data()[3];}
93  float & y() {return data()[7];}
94  float & z() {return data()[11];}
95  const float & x() const {return data()[3];}
96  const float & y() const {return data()[7];}
97  const float & z() const {return data()[11];}
98 
99  float theta() const;
100 
101  bool isInvertible() const;
102  Transform inverse() const;
103  Transform rotation() const;
104  Transform translation() const;
105  Transform to3DoF() const;
106 
107  cv::Mat rotationMatrix() const;
108  cv::Mat translationMatrix() const;
109 
110  void getTranslationAndEulerAngles(float & x, float & y, float & z, float & roll, float & pitch, float & yaw) const;
111  void getEulerAngles(float & roll, float & pitch, float & yaw) const;
112  void getTranslation(float & x, float & y, float & z) const;
113  float getAngle(float x=1.0f, float y=0.0f, float z=0.0f) const;
114  float getNorm() const;
115  float getNormSquared() const;
116  float getDistance(const Transform & t) const;
117  float getDistanceSquared(const Transform & t) const;
118  Transform interpolate(float t, const Transform & other) const;
119  void normalizeRotation();
120  std::string prettyPrint() const;
121 
122  Transform operator*(const Transform & t) const;
123  Transform & operator*=(const Transform & t);
124  bool operator==(const Transform & t) const;
125  bool operator!=(const Transform & t) const;
126 
127  Eigen::Matrix4f toEigen4f() const;
128  Eigen::Matrix4d toEigen4d() const;
129  Eigen::Affine3f toEigen3f() const;
130  Eigen::Affine3d toEigen3d() const;
131 
132  Eigen::Quaternionf getQuaternionf() const;
133  Eigen::Quaterniond getQuaterniond() const;
134 
135 public:
136  static Transform getIdentity();
137  static Transform fromEigen4f(const Eigen::Matrix4f & matrix);
138  static Transform fromEigen4d(const Eigen::Matrix4d & matrix);
139  static Transform fromEigen3f(const Eigen::Affine3f & matrix);
140  static Transform fromEigen3d(const Eigen::Affine3d & matrix);
141  static Transform fromEigen3f(const Eigen::Isometry3f & matrix);
142  static Transform fromEigen3d(const Eigen::Isometry3d & matrix);
143 
145  0.0f, -1.0f, 0.0f, 0.0f,
146  0.0f, 0.0f, 1.0f, 0.0f,
147  -1.0f, 0.0f, 0.0f, 0.0f);}
149  0.0f, 0.0f,-1.0f, 0.0f,
150  -1.0f, 0.0f, 0.0f, 0.0f,
151  0.0f, 1.0f, 0.0f, 0.0f);}
152 
160  static Transform fromString(const std::string & string);
161  static bool canParseString(const std::string & string);
162 
163  static Transform getTransform(
164  const std::map<double, Transform> & tfBuffer,
165  const double & stamp);
166  RTABMAP_DEPRECATED(static Transform getClosestTransform(
167  const std::map<double, Transform> & tfBuffer,
168  const double & stamp,
169  double * stampDiff), "Use Transform::getTransform() instead to get always accurate transforms.");
170 
171 private:
172  cv::Mat data_;
173 };
174 
175 RTABMAP_EXP std::ostream& operator<<(std::ostream& os, const Transform& s);
176 
178 {
179 public:
180  TransformStamped(const Transform & transform, const double & stamp) :
181  transform_(transform),
182  stamp_(stamp)
183  {}
184  const Transform & transform() const {return transform_;}
185  const double & stamp() const {return stamp_;}
186 
187 private:
189  double stamp_;
190 };
191 
192 }
193 
194 #endif /* TRANSFORM_H_ */
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
const float * data() const
Definition: Transform.h:88
const float & operator()(int row, int col) const
Definition: Transform.h:79
float r13() const
Definition: Transform.h:64
float r23() const
Definition: Transform.h:67
const float & z() const
Definition: Transform.h:97
float o34() const
Definition: Transform.h:74
f
float & operator[](int index)
Definition: Transform.h:76
const float & x() const
Definition: Transform.h:95
float * data()
Definition: Transform.h:89
GLM_FUNC_DECL genType::row_type row(genType const &m, length_t const &index)
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
GLM_FUNC_DECL tmat2x2< T, P > operator*(tmat2x2< T, P > const &m, T const &s)
static Transform opengl_T_rtabmap()
Definition: Transform.h:144
GLM_FUNC_DECL bool isNull(detail::tmat2x2< T, P > const &m, T const &epsilon)
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
GLM_FUNC_DECL detail::tmat4x4< T, P > interpolate(detail::tmat4x4< T, P > const &m1, detail::tmat4x4< T, P > const &m2, T const delta)
float o14() const
Definition: Transform.h:72
GLM_FUNC_DECL bool operator==(tvec1< T, P > const &v1, tvec1< T, P > const &v2)
float r12() const
Definition: Transform.h:63
float r31() const
Definition: Transform.h:68
GLM_FUNC_DECL bool operator!=(tvec1< T, P > const &v1, tvec1< T, P > const &v2)
float r21() const
Definition: Transform.h:65
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
GLM_FUNC_DECL bool isIdentity(matType< T, P > const &m, T const &epsilon)
const float & operator[](int index) const
Definition: Transform.h:77
const double & stamp() const
Definition: Transform.h:185
const float & y() const
Definition: Transform.h:96
float r33() const
Definition: Transform.h:70
const Transform & transform() const
Definition: Transform.h:184
static Transform rtabmap_T_opengl()
Definition: Transform.h:148
float r22() const
Definition: Transform.h:66
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const CameraModel &model)
TransformStamped(const Transform &transform, const double &stamp)
Definition: Transform.h:180
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
const cv::Mat & dataMatrix() const
Definition: Transform.h:87
RTABMAP_DEPRECATED(typedef SensorData Image,"rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.")
float r11() const
Definition: Transform.h:62
int size() const
Definition: Transform.h:90
float o24() const
Definition: Transform.h:73
float & operator()(int row, int col)
Definition: Transform.h:78
float r32() const
Definition: Transform.h:69
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:06