Transform.cpp
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 #include <rtabmap/core/Transform.h>
29 
30 #include <pcl/common/eigen.h>
31 #include <pcl/common/common.h>
32 #include <rtabmap/core/util3d.h>
34 #include <rtabmap/utilite/UMath.h>
36 #include <rtabmap/utilite/UStl.h>
37 #include <iomanip>
38 
39 namespace rtabmap {
40 
41 Transform::Transform() : data_(cv::Mat::zeros(3,4,CV_32FC1))
42 {
43 }
44 
45 // rotation matrix r## and origin o##
47  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 {
51  data_ = (cv::Mat_<float>(3,4) <<
52  r11, r12, r13, o14,
53  r21, r22, r23, o24,
54  r31, r32, r33, o34);
55 }
56 
57 Transform::Transform(const cv::Mat & transformationMatrix)
58 {
59  UASSERT(transformationMatrix.cols == 4 &&
60  transformationMatrix.rows == 3 &&
61  (transformationMatrix.type() == CV_32FC1 || transformationMatrix.type() == CV_64FC1));
62  if(transformationMatrix.type() == CV_32FC1)
63  {
64  data_ = transformationMatrix;
65  }
66  else
67  {
68  transformationMatrix.convertTo(data_, CV_32F);
69  }
70 }
71 
72 Transform::Transform(float x, float y, float z, float roll, float pitch, float yaw)
73 {
74  Eigen::Affine3f t = pcl::getTransformation (x, y, z, roll, pitch, yaw);
75  *this = fromEigen3f(t);
76 }
77 
78 Transform::Transform(float x, float y, float z, float qx, float qy, float qz, float qw) :
79  data_(cv::Mat::zeros(3,4,CV_32FC1))
80 {
81  Eigen::Matrix3f rotation = Eigen::Quaternionf(qw, qx, qy, qz).normalized().toRotationMatrix();
82  data()[0] = rotation(0,0);
83  data()[1] = rotation(0,1);
84  data()[2] = rotation(0,2);
85  data()[3] = x;
86  data()[4] = rotation(1,0);
87  data()[5] = rotation(1,1);
88  data()[6] = rotation(1,2);
89  data()[7] = y;
90  data()[8] = rotation(2,0);
91  data()[9] = rotation(2,1);
92  data()[10] = rotation(2,2);
93  data()[11] = z;
94 }
95 
96 Transform::Transform(float x, float y, float theta)
97 {
98  Eigen::Affine3f t = pcl::getTransformation (x, y, 0, 0, 0, theta);
99  *this = fromEigen3f(t);
100 }
101 
103 {
104  return Transform(data_.clone());
105 }
106 
107 bool Transform::isNull() const
108 {
109  return (data_.empty() ||
110  (data()[0] == 0.0f &&
111  data()[1] == 0.0f &&
112  data()[2] == 0.0f &&
113  data()[3] == 0.0f &&
114  data()[4] == 0.0f &&
115  data()[5] == 0.0f &&
116  data()[6] == 0.0f &&
117  data()[7] == 0.0f &&
118  data()[8] == 0.0f &&
119  data()[9] == 0.0f &&
120  data()[10] == 0.0f &&
121  data()[11] == 0.0f) ||
122  uIsNan(data()[0]) ||
123  uIsNan(data()[1]) ||
124  uIsNan(data()[2]) ||
125  uIsNan(data()[3]) ||
126  uIsNan(data()[4]) ||
127  uIsNan(data()[5]) ||
128  uIsNan(data()[6]) ||
129  uIsNan(data()[7]) ||
130  uIsNan(data()[8]) ||
131  uIsNan(data()[9]) ||
132  uIsNan(data()[10]) ||
133  uIsNan(data()[11]));
134 }
135 
137 {
138  return data()[0] == 1.0f &&
139  data()[1] == 0.0f &&
140  data()[2] == 0.0f &&
141  data()[3] == 0.0f &&
142  data()[4] == 0.0f &&
143  data()[5] == 1.0f &&
144  data()[6] == 0.0f &&
145  data()[7] == 0.0f &&
146  data()[8] == 0.0f &&
147  data()[9] == 0.0f &&
148  data()[10] == 1.0f &&
149  data()[11] == 0.0f;
150 }
151 
153 {
154  *this = Transform();
155 }
156 
158 {
159  *this = getIdentity();
160 }
161 
162 float Transform::theta() const
163 {
164  float roll, pitch, yaw;
165  this->getEulerAngles(roll, pitch, yaw);
166  return yaw;
167 }
168 
170 {
171  return fromEigen4f(toEigen4f().inverse());
172 }
173 
175 {
176  return Transform(
177  data()[0], data()[1], data()[2], 0,
178  data()[4], data()[5], data()[6], 0,
179  data()[8], data()[9], data()[10], 0);
180 }
181 
183 {
184  return Transform(1,0,0, data()[3],
185  0,1,0, data()[7],
186  0,0,1, data()[11]);
187 }
188 
190 {
191  float x,y,z,roll,pitch,yaw;
192  this->getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
193  return Transform(x,y,0, 0,0,yaw);
194 }
195 
197 {
198  return data_.colRange(0, 3).clone();
199 }
200 
202 {
203  return data_.col(3).clone();
204 }
205 
206 void Transform::getTranslationAndEulerAngles(float & x, float & y, float & z, float & roll, float & pitch, float & yaw) const
207 {
208  pcl::getTranslationAndEulerAngles(toEigen3f(), x, y, z, roll, pitch, yaw);
209 }
210 
211 void Transform::getEulerAngles(float & roll, float & pitch, float & yaw) const
212 {
213  float x,y,z;
214  pcl::getTranslationAndEulerAngles(toEigen3f(), x, y, z, roll, pitch, yaw);
215 }
216 
217 void Transform::getTranslation(float & x, float & y, float & z) const
218 {
219  x = this->x();
220  y = this->y();
221  z = this->z();
222 }
223 
224 float Transform::getAngle(float x, float y, float z) const
225 {
226  Eigen::Vector3f vA(x,y,z);
227  Eigen::Vector3f vB = this->toEigen3f().linear()*Eigen::Vector3f(1,0,0);
228  return pcl::getAngle3D(Eigen::Vector4f(vA[0], vA[1], vA[2], 0), Eigen::Vector4f(vB[0], vB[1], vB[2], 0));
229 }
230 
231 float Transform::getNorm() const
232 {
233  return uNorm(this->x(), this->y(), this->z());
234 }
235 
237 {
238  return uNormSquared(this->x(), this->y(), this->z());
239 }
240 
241 float Transform::getDistance(const Transform & t) const
242 {
243  return uNorm(this->x()-t.x(), this->y()-t.y(), this->z()-t.z());
244 }
245 
247 {
248  return uNormSquared(this->x()-t.x(), this->y()-t.y(), this->z()-t.z());
249 }
250 
251 Transform Transform::interpolate(float t, const Transform & other) const
252 {
253  Eigen::Quaternionf qa=this->getQuaternionf();
254  Eigen::Quaternionf qb=other.getQuaternionf();
255  Eigen::Quaternionf qres = qa.slerp(t, qb);
256 
257  float x = this->x() + t*(other.x() - this->x());
258  float y = this->y() + t*(other.y() - this->y());
259  float z = this->z() + t*(other.z() - this->z());
260 
261  return Transform(x,y,z, qres.x(), qres.y(), qres.z(), qres.w());
262 }
263 
265 {
266  if(!this->isNull())
267  {
268  Eigen::Affine3f m = toEigen3f();
269  m.linear() = Eigen::Quaternionf(m.linear()).normalized().toRotationMatrix();
270  *this = fromEigen3f(m);
271  }
272 }
273 
274 std::string Transform::prettyPrint() const
275 {
276  if(this->isNull())
277  {
278  return uFormat("xyz=[null] rpy=[null]");
279  }
280  else
281  {
282  float x,y,z,roll,pitch,yaw;
283  getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
284  return uFormat("xyz=%f,%f,%f rpy=%f,%f,%f", x,y,z, roll,pitch,yaw);
285  }
286 }
287 
289 {
290  Eigen::Affine3f m = Eigen::Affine3f(toEigen4f()*t.toEigen4f());
291  // make sure rotation is always normalized!
292  m.linear() = Eigen::Quaternionf(m.linear()).normalized().toRotationMatrix();
293  return fromEigen3f(m);
294 }
295 
297 {
298  *this = *this * t;
299  return *this;
300 }
301 
302 bool Transform::operator==(const Transform & t) const
303 {
304  return memcmp(data_.data, t.data_.data, data_.total() * sizeof(float)) == 0;
305 }
306 
307 bool Transform::operator!=(const Transform & t) const
308 {
309  return !(*this == t);
310 }
311 
312 std::ostream& operator<<(std::ostream& os, const Transform& s)
313 {
314  for(int i = 0; i < 3; ++i)
315  {
316  for(int j = 0; j < 4; ++j)
317  {
318  os << std::left << std::setw(12) << s.data()[i*4 + j] << " ";
319  }
320  os << std::endl;
321  }
322  return os;
323 }
324 
325 Eigen::Matrix4f Transform::toEigen4f() const
326 {
327  Eigen::Matrix4f m;
328  m << data()[0], data()[1], data()[2], data()[3],
329  data()[4], data()[5], data()[6], data()[7],
330  data()[8], data()[9], data()[10], data()[11],
331  0,0,0,1;
332  return m;
333 }
334 Eigen::Matrix4d Transform::toEigen4d() const
335 {
336  Eigen::Matrix4d m;
337  m << data()[0], data()[1], data()[2], data()[3],
338  data()[4], data()[5], data()[6], data()[7],
339  data()[8], data()[9], data()[10], data()[11],
340  0,0,0,1;
341  return m;
342 }
343 
344 Eigen::Affine3f Transform::toEigen3f() const
345 {
346  return Eigen::Affine3f(toEigen4f());
347 }
348 
349 Eigen::Affine3d Transform::toEigen3d() const
350 {
351  return Eigen::Affine3d(toEigen4d());
352 }
353 
354 Eigen::Quaternionf Transform::getQuaternionf() const
355 {
356  return Eigen::Quaternionf(this->toEigen3f().linear()).normalized();
357 }
358 
359 Eigen::Quaterniond Transform::getQuaterniond() const
360 {
361  return Eigen::Quaterniond(this->toEigen3d().linear()).normalized();
362 }
363 
365 {
366  return Transform(1,0,0,0, 0,1,0,0, 0,0,1,0);
367 }
368 
369 Transform Transform::fromEigen4f(const Eigen::Matrix4f & matrix)
370 {
371  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
372  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
373  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
374 }
375 Transform Transform::fromEigen4d(const Eigen::Matrix4d & matrix)
376 {
377  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
378  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
379  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
380 }
381 
382 Transform Transform::fromEigen3f(const Eigen::Affine3f & matrix)
383 {
384  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
385  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
386  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
387 }
388 Transform Transform::fromEigen3d(const Eigen::Affine3d & matrix)
389 {
390  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
391  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
392  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
393 }
394 
395 Transform Transform::fromEigen3f(const Eigen::Isometry3f & matrix)
396 {
397  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
398  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
399  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
400 }
401 Transform Transform::fromEigen3d(const Eigen::Isometry3d & matrix)
402 {
403  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
404  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
405  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
406 }
407 
415 Transform Transform::fromString(const std::string & string)
416 {
417  std::list<std::string> list = uSplit(string, ' ');
418  UASSERT_MSG(list.empty() || list.size() == 3 || list.size() == 6 || list.size() == 7 || list.size() == 9 || list.size() == 12,
419  uFormat("Cannot parse \"%s\"", string.c_str()).c_str());
420 
421  std::vector<float> numbers(list.size());
422  int i = 0;
423  for(std::list<std::string>::iterator iter=list.begin(); iter!=list.end(); ++iter)
424  {
425  numbers[i++] = uStr2Float(*iter);
426  }
427 
428  Transform t;
429  if(numbers.size() == 3)
430  {
431  t = Transform(numbers[0], numbers[1], numbers[2]);
432  }
433  else if(numbers.size() == 6)
434  {
435  t = Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5]);
436  }
437  else if(numbers.size() == 7)
438  {
439 
440  t = Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5], numbers[6]);
441  }
442  else if(numbers.size() == 9)
443  {
444  t = Transform(numbers[0], numbers[1], numbers[2], 0,
445  numbers[3], numbers[4], numbers[5], 0,
446  numbers[6], numbers[7], numbers[8], 0);
447  }
448  else if(numbers.size() == 12)
449  {
450  t = Transform(numbers[0], numbers[1], numbers[2], numbers[3],
451  numbers[4], numbers[5], numbers[6], numbers[7],
452  numbers[8], numbers[9], numbers[10], numbers[11]);
453  }
454  return t;
455 }
456 
464 bool Transform::canParseString(const std::string & string)
465 {
466  std::list<std::string> list = uSplit(string, ' ');
467  return list.size() == 0 || list.size() == 3 || list.size() == 6 || list.size() == 7 || list.size() == 9 || list.size() == 12;
468 }
469 
470 }
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
const float * data() const
Definition: Transform.h:87
float r13() const
Definition: Transform.h:63
float r23() const
Definition: Transform.h:66
T uNorm(const std::vector< T > &v)
Definition: UMath.h:575
static Transform fromEigen4f(const Eigen::Matrix4f &matrix)
Definition: Transform.cpp:369
std::string prettyPrint() const
Definition: Transform.cpp:274
void getTranslation(float &x, float &y, float &z) const
Definition: Transform.cpp:217
float o34() const
Definition: Transform.h:73
float getDistanceSquared(const Transform &t) const
Definition: Transform.cpp:246
cv::Mat rotationMatrix() const
Definition: Transform.cpp:196
Transform rotation() const
Definition: Transform.cpp:174
cv::Mat translationMatrix() const
Definition: Transform.cpp:201
static Transform getIdentity()
Definition: Transform.cpp:364
Transform translation() const
Definition: Transform.cpp:182
Eigen::Matrix4d toEigen4d() const
Definition: Transform.cpp:334
bool operator==(const Transform &t) const
Definition: Transform.cpp:302
float getNorm() const
Definition: Transform.cpp:231
float UTILITE_EXP uStr2Float(const std::string &str)
Basic mathematics functions.
Some conversion functions.
Definition: Features2d.h:41
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
bool isIdentity() const
Definition: Transform.cpp:136
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
Definition: UStl.h:566
#define UASSERT(condition)
Wrappers of STL for convenient functions.
float theta() const
Definition: Transform.cpp:162
static Transform fromEigen3f(const Eigen::Affine3f &matrix)
Definition: Transform.cpp:382
bool isNull() const
Definition: Transform.cpp:107
float o14() const
Definition: Transform.h:71
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
void getEulerAngles(float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:211
float r12() const
Definition: Transform.h:62
float r31() const
Definition: Transform.h:67
Transform operator*(const Transform &t) const
Definition: Transform.cpp:288
bool operator!=(const Transform &t) const
Definition: Transform.cpp:307
float r21() const
Definition: Transform.h:64
void normalizeRotation()
Definition: Transform.cpp:264
static Transform fromEigen3d(const Eigen::Affine3d &matrix)
Definition: Transform.cpp:388
float r33() const
Definition: Transform.h:69
Eigen::Quaternionf getQuaternionf() const
Definition: Transform.cpp:354
float getDistance(const Transform &t) const
Definition: Transform.cpp:241
Transform to3DoF() const
Definition: Transform.cpp:189
static Transform fromEigen4d(const Eigen::Matrix4d &matrix)
Definition: Transform.cpp:375
static bool canParseString(const std::string &string)
Definition: Transform.cpp:464
Eigen::Matrix4f toEigen4f() const
Definition: Transform.cpp:325
T uNormSquared(const std::vector< T > &v)
Definition: UMath.h:560
Transform & operator*=(const Transform &t)
Definition: Transform.cpp:296
float r22() const
Definition: Transform.h:65
float getNormSquared() const
Definition: Transform.cpp:236
ULogger class and convenient macros.
float getAngle(float x=1.0f, float y=0.0f, float z=0.0f) const
Definition: Transform.cpp:224
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
Eigen::Quaterniond getQuaterniond() const
Definition: Transform.cpp:359
bool uIsNan(const T &value)
Definition: UMath.h:42
Transform inverse() const
Definition: Transform.cpp:169
Eigen::Affine3f toEigen3f() const
Definition: Transform.cpp:344
Transform clone() const
Definition: Transform.cpp:102
static Transform fromString(const std::string &string)
Definition: Transform.cpp:415
float r11() const
Definition: Transform.h:61
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:206
std::string UTILITE_EXP uFormat(const char *fmt,...)
float o24() const
Definition: Transform.h:72
Eigen::Affine3d toEigen3d() const
Definition: Transform.cpp:349
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const Transform &s)
Definition: Transform.cpp:312
float r32() const
Definition: Transform.h:68
Transform interpolate(float t, const Transform &other) const
Definition: Transform.cpp:251


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