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 <Eigen/Core>
35 #include <Eigen/Geometry>
36 #include <opencv2/core/core.hpp>
37 
38 namespace rtabmap {
39 
41 {
42 public:
43 
44  // Zero by default
45  Transform();
46  // rotation matrix r## and origin o##
47  Transform(float r11, float r12, float r13, float o14,
48  float r21, float r22, float r23, float o24,
49  float r31, float r32, float r33, float o34);
50  // should have 3 rows, 4 cols and type CV_32FC1
51  Transform(const cv::Mat & transformationMatrix);
52  // x,y,z, roll,pitch,yaw
53  Transform(float x, float y, float z, float roll, float pitch, float yaw);
54  // x,y,z, qx,qy,qz,qw
55  Transform(float x, float y, float z, float qx, float qy, float qz, float qw);
56  // x,y, theta
57  Transform(float x, float y, float theta);
58 
59  Transform clone() const;
60 
61  float r11() const {return data()[0];}
62  float r12() const {return data()[1];}
63  float r13() const {return data()[2];}
64  float r21() const {return data()[4];}
65  float r22() const {return data()[5];}
66  float r23() const {return data()[6];}
67  float r31() const {return data()[8];}
68  float r32() const {return data()[9];}
69  float r33() const {return data()[10];}
70 
71  float o14() const {return data()[3];}
72  float o24() const {return data()[7];}
73  float o34() const {return data()[11];}
74 
75  float & operator[](int index) {return data()[index];}
76  const float & operator[](int index) const {return data()[index];}
77  float & operator()(int row, int col) {return data()[row*4 + col];}
78  const float & operator()(int row, int col) const {return data()[row*4 + col];}
79 
80  bool isNull() const;
81  bool isIdentity() const;
82 
83  void setNull();
84  void setIdentity();
85 
86  const cv::Mat & dataMatrix() const {return data_;}
87  const float * data() const {return (const float *)data_.data;}
88  float * data() {return (float *)data_.data;}
89  int size() const {return 12;}
90 
91  float & x() {return data()[3];}
92  float & y() {return data()[7];}
93  float & z() {return data()[11];}
94  const float & x() const {return data()[3];}
95  const float & y() const {return data()[7];}
96  const float & z() const {return data()[11];}
97 
98  float theta() const;
99 
100  Transform inverse() const;
101  Transform rotation() const;
102  Transform translation() const;
103  Transform to3DoF() const;
104 
105  cv::Mat rotationMatrix() const;
106  cv::Mat translationMatrix() const;
107 
108  void getTranslationAndEulerAngles(float & x, float & y, float & z, float & roll, float & pitch, float & yaw) const;
109  void getEulerAngles(float & roll, float & pitch, float & yaw) const;
110  void getTranslation(float & x, float & y, float & z) const;
111  float getAngle(float x=1.0f, float y=0.0f, float z=0.0f) const;
112  float getNorm() const;
113  float getNormSquared() const;
114  float getDistance(const Transform & t) const;
115  float getDistanceSquared(const Transform & t) const;
116  Transform interpolate(float t, const Transform & other) const;
117  void normalizeRotation();
118  std::string prettyPrint() const;
119 
120  Transform operator*(const Transform & t) const;
121  Transform & operator*=(const Transform & t);
122  bool operator==(const Transform & t) const;
123  bool operator!=(const Transform & t) const;
124 
125  Eigen::Matrix4f toEigen4f() const;
126  Eigen::Matrix4d toEigen4d() const;
127  Eigen::Affine3f toEigen3f() const;
128  Eigen::Affine3d toEigen3d() const;
129 
130  Eigen::Quaternionf getQuaternionf() const;
131  Eigen::Quaterniond getQuaterniond() const;
132 
133 public:
134  static Transform getIdentity();
135  static Transform fromEigen4f(const Eigen::Matrix4f & matrix);
136  static Transform fromEigen4d(const Eigen::Matrix4d & matrix);
137  static Transform fromEigen3f(const Eigen::Affine3f & matrix);
138  static Transform fromEigen3d(const Eigen::Affine3d & matrix);
139  static Transform fromEigen3f(const Eigen::Isometry3f & matrix);
140  static Transform fromEigen3d(const Eigen::Isometry3d & matrix);
141 
149  static Transform fromString(const std::string & string);
150  static bool canParseString(const std::string & string);
151 
152 private:
153  cv::Mat data_;
154 };
155 
156 RTABMAP_EXP std::ostream& operator<<(std::ostream& os, const Transform& s);
157 
158 }
159 
160 #endif /* TRANSFORM_H_ */
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
const float * data() const
Definition: Transform.h:87
const float & operator()(int row, int col) const
Definition: Transform.h:78
float r13() const
Definition: Transform.h:63
float r23() const
Definition: Transform.h:66
const float & z() const
Definition: Transform.h:96
float o34() const
Definition: Transform.h:73
f
float & operator[](int index)
Definition: Transform.h:75
const float & x() const
Definition: Transform.h:94
float * data()
Definition: Transform.h:88
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)
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:71
GLM_FUNC_DECL bool operator==(tvec1< T, P > const &v1, tvec1< T, P > const &v2)
float r12() const
Definition: Transform.h:62
float r31() const
Definition: Transform.h:67
GLM_FUNC_DECL bool operator!=(tvec1< T, P > const &v1, tvec1< T, P > const &v2)
float r21() const
Definition: Transform.h:64
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:76
const float & y() const
Definition: Transform.h:95
float r33() const
Definition: Transform.h:69
float r22() const
Definition: Transform.h:65
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
const cv::Mat & dataMatrix() const
Definition: Transform.h:86
float r11() const
Definition: Transform.h:61
int size() const
Definition: Transform.h:89
float o24() const
Definition: Transform.h:72
float & operator()(int row, int col)
Definition: Transform.h:77
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const Transform &s)
Definition: Transform.cpp:312
float r32() const
Definition: Transform.h:68
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:40