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  bool invertible = false;
172  Eigen::Matrix4f inverse;
173  Eigen::Matrix4f::RealScalar det;
174  toEigen4f().computeInverseAndDetWithCheck(inverse, det, invertible);
175  return invertible;
176 }
177 
179 {
180  bool invertible = false;
181  Eigen::Matrix4f inverse;
182  Eigen::Matrix4f::RealScalar det;
183  toEigen4f().computeInverseAndDetWithCheck(inverse, det, invertible);
184  UASSERT_MSG(invertible, uFormat("This transform is not invertible! %s \n"
185  "[%f %f %f %f;\n"
186  " %f %f %f %f;\n"
187  " %f %f %f %f;\n"
188  " 0 0 0 1]", prettyPrint().c_str(),
189  r11(), r12(), r13(), o14(),
190  r21(), r22(), r23(), o24(),
191  r31(), r32(), r33(), o34()).c_str());
192  return fromEigen4f(inverse);
193 }
194 
196 {
197  return Transform(
198  data()[0], data()[1], data()[2], 0,
199  data()[4], data()[5], data()[6], 0,
200  data()[8], data()[9], data()[10], 0);
201 }
202 
204 {
205  return Transform(1,0,0, data()[3],
206  0,1,0, data()[7],
207  0,0,1, data()[11]);
208 }
209 
211 {
212  float x,y,z,roll,pitch,yaw;
213  this->getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
214  return Transform(x,y,0, 0,0,yaw);
215 }
216 
218 {
219  float x,y,z,roll,pitch,yaw;
220  this->getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
221  return Transform(x,y,z, 0,0,yaw);
222 }
223 
224 bool Transform::is3DoF() const
225 {
226  return is4DoF() && z() == 0.0;
227 }
228 
229 bool Transform::is4DoF() const
230 {
231  return r13() == 0.0 &&
232  r23() == 0.0 &&
233  r31() == 0.0 &&
234  r32() == 0.0 &&
235  r33() == 0.0;
236 }
237 
239 {
240  return data_.colRange(0, 3).clone();
241 }
242 
244 {
245  return data_.col(3).clone();
246 }
247 
248 void Transform::getTranslationAndEulerAngles(float & x, float & y, float & z, float & roll, float & pitch, float & yaw) const
249 {
250  pcl::getTranslationAndEulerAngles(toEigen3f(), x, y, z, roll, pitch, yaw);
251 }
252 
253 void Transform::getEulerAngles(float & roll, float & pitch, float & yaw) const
254 {
255  float x,y,z;
256  pcl::getTranslationAndEulerAngles(toEigen3f(), x, y, z, roll, pitch, yaw);
257 }
258 
259 void Transform::getTranslation(float & x, float & y, float & z) const
260 {
261  x = this->x();
262  y = this->y();
263  z = this->z();
264 }
265 
266 float Transform::getAngle(float x, float y, float z) const
267 {
268  Eigen::Vector3f vA(x,y,z);
269  Eigen::Vector3f vB = this->toEigen3f().linear()*Eigen::Vector3f(1,0,0);
270  return pcl::getAngle3D(Eigen::Vector4f(vA[0], vA[1], vA[2], 0), Eigen::Vector4f(vB[0], vB[1], vB[2], 0));
271 }
272 
273 float Transform::getNorm() const
274 {
275  return uNorm(this->x(), this->y(), this->z());
276 }
277 
279 {
280  return uNormSquared(this->x(), this->y(), this->z());
281 }
282 
283 float Transform::getDistance(const Transform & t) const
284 {
285  return uNorm(this->x()-t.x(), this->y()-t.y(), this->z()-t.z());
286 }
287 
289 {
290  return uNormSquared(this->x()-t.x(), this->y()-t.y(), this->z()-t.z());
291 }
292 
293 Transform Transform::interpolate(float t, const Transform & other) const
294 {
295  Eigen::Quaternionf qa=this->getQuaternionf();
296  Eigen::Quaternionf qb=other.getQuaternionf();
297  Eigen::Quaternionf qres = qa.slerp(t, qb);
298 
299  float x = this->x() + t*(other.x() - this->x());
300  float y = this->y() + t*(other.y() - this->y());
301  float z = this->z() + t*(other.z() - this->z());
302 
303  return Transform(x,y,z, qres.x(), qres.y(), qres.z(), qres.w());
304 }
305 
307 {
308  if(!this->isNull())
309  {
310  Eigen::Affine3f m = toEigen3f();
311  m.linear() = Eigen::Quaternionf(m.linear()).normalized().toRotationMatrix();
312  *this = fromEigen3f(m);
313  }
314 }
315 
316 std::string Transform::prettyPrint() const
317 {
318  if(this->isNull())
319  {
320  return uFormat("xyz=[null] rpy=[null]");
321  }
322  else
323  {
324  float x,y,z,roll,pitch,yaw;
325  getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
326  return uFormat("xyz=%f,%f,%f rpy=%f,%f,%f", x,y,z, roll,pitch,yaw);
327  }
328 }
329 
331 {
332  Eigen::Affine3f m = Eigen::Affine3f(toEigen4f()*t.toEigen4f());
333  // make sure rotation is always normalized!
334  m.linear() = Eigen::Quaternionf(m.linear()).normalized().toRotationMatrix();
335  return fromEigen3f(m);
336 }
337 
339 {
340  *this = *this * t;
341  return *this;
342 }
343 
344 bool Transform::operator==(const Transform & t) const
345 {
346  return memcmp(data_.data, t.data_.data, data_.total() * sizeof(float)) == 0;
347 }
348 
349 bool Transform::operator!=(const Transform & t) const
350 {
351  return !(*this == t);
352 }
353 
354 std::ostream& operator<<(std::ostream& os, const Transform& s)
355 {
356  os << "[" << s.data()[0] << ", " << s.data()[1] << ", " << s.data()[2] << ", " << s.data()[3] << ";" << std::endl
357  << " " << s.data()[4] << ", " << s.data()[5] << ", " << s.data()[6] << ", " << s.data()[7] << ";" << std::endl
358  << " " << s.data()[8] << ", " << s.data()[9] << ", " << s.data()[10]<< ", " << s.data()[11] << "]";
359  return os;
360 }
361 
362 Eigen::Matrix4f Transform::toEigen4f() const
363 {
364  Eigen::Matrix4f m;
365  m << data()[0], data()[1], data()[2], data()[3],
366  data()[4], data()[5], data()[6], data()[7],
367  data()[8], data()[9], data()[10], data()[11],
368  0,0,0,1;
369  return m;
370 }
371 Eigen::Matrix4d Transform::toEigen4d() const
372 {
373  Eigen::Matrix4d m;
374  m << data()[0], data()[1], data()[2], data()[3],
375  data()[4], data()[5], data()[6], data()[7],
376  data()[8], data()[9], data()[10], data()[11],
377  0,0,0,1;
378  return m;
379 }
380 
381 Eigen::Affine3f Transform::toEigen3f() const
382 {
383  return Eigen::Affine3f(toEigen4f());
384 }
385 
386 Eigen::Affine3d Transform::toEigen3d() const
387 {
388  return Eigen::Affine3d(toEigen4d());
389 }
390 
391 Eigen::Quaternionf Transform::getQuaternionf() const
392 {
393  return Eigen::Quaternionf(this->toEigen3f().linear()).normalized();
394 }
395 
396 Eigen::Quaterniond Transform::getQuaterniond() const
397 {
398  return Eigen::Quaterniond(this->toEigen3d().linear()).normalized();
399 }
400 
402 {
403  return Transform(1,0,0,0, 0,1,0,0, 0,0,1,0);
404 }
405 
406 Transform Transform::fromEigen4f(const Eigen::Matrix4f & matrix)
407 {
408  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
409  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
410  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
411 }
412 Transform Transform::fromEigen4d(const Eigen::Matrix4d & matrix)
413 {
414  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
415  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
416  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
417 }
418 
419 Transform Transform::fromEigen3f(const Eigen::Affine3f & matrix)
420 {
421  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
422  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
423  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
424 }
425 Transform Transform::fromEigen3d(const Eigen::Affine3d & matrix)
426 {
427  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
428  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
429  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
430 }
431 
432 Transform Transform::fromEigen3f(const Eigen::Isometry3f & matrix)
433 {
434  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
435  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
436  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
437 }
438 Transform Transform::fromEigen3d(const Eigen::Isometry3d & matrix)
439 {
440  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
441  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
442  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
443 }
444 
445 Transform Transform::fromEigen3f(const Eigen::Matrix<float, 3, 4> & matrix)
446 {
447  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
448  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
449  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
450 }
451 Transform Transform::fromEigen3d(const Eigen::Matrix<double, 3, 4> & matrix)
452 {
453  return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
454  matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
455  matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
456 }
457 
465 Transform Transform::fromString(const std::string & string)
466 {
467  std::list<std::string> list = uSplit(string, ' ');
468  UASSERT_MSG(list.empty() || list.size() == 3 || list.size() == 6 || list.size() == 7 || list.size() == 9 || list.size() == 12,
469  uFormat("Cannot parse \"%s\"", string.c_str()).c_str());
470 
471  std::vector<float> numbers(list.size());
472  int i = 0;
473  for(std::list<std::string>::iterator iter=list.begin(); iter!=list.end(); ++iter)
474  {
475  numbers[i++] = uStr2Float(*iter);
476  }
477 
478  Transform t;
479  if(numbers.size() == 3)
480  {
481  t = Transform(numbers[0], numbers[1], numbers[2]);
482  }
483  else if(numbers.size() == 6)
484  {
485  t = Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5]);
486  }
487  else if(numbers.size() == 7)
488  {
489 
490  t = Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5], numbers[6]);
491  }
492  else if(numbers.size() == 9)
493  {
494  t = Transform(numbers[0], numbers[1], numbers[2], 0,
495  numbers[3], numbers[4], numbers[5], 0,
496  numbers[6], numbers[7], numbers[8], 0);
497  }
498  else if(numbers.size() == 12)
499  {
500  t = Transform(numbers[0], numbers[1], numbers[2], numbers[3],
501  numbers[4], numbers[5], numbers[6], numbers[7],
502  numbers[8], numbers[9], numbers[10], numbers[11]);
503  }
504  return t;
505 }
506 
514 bool Transform::canParseString(const std::string & string)
515 {
516  std::list<std::string> list = uSplit(string, ' ');
517  return list.size() == 0 || list.size() == 3 || list.size() == 6 || list.size() == 7 || list.size() == 9 || list.size() == 12;
518 }
519 
521  const std::map<double, Transform> & tfBuffer,
522  const double & stamp)
523 {
524  UASSERT(!tfBuffer.empty());
525  std::map<double, Transform>::const_iterator imuIterB = tfBuffer.lower_bound(stamp);
526  std::map<double, Transform>::const_iterator imuIterA = imuIterB;
527  if(imuIterA != tfBuffer.begin())
528  {
529  imuIterA = --imuIterA;
530  }
531  if(imuIterB == tfBuffer.end())
532  {
533  imuIterB = --imuIterB;
534  }
535  Transform imuT;
536  if(imuIterB->first == stamp)
537  {
538  imuT = imuIterB->second;
539  }
540  else if(imuIterA != imuIterB)
541  {
542  //interpolate:
543  imuT = imuIterA->second.interpolate((stamp-imuIterA->first) / (imuIterB->first-imuIterA->first), imuIterB->second);
544  }
545  else if(stamp > imuIterB->first)
546  {
547  UWARN("No transform found for stamp %f! Latest is %f", stamp, imuIterB->first);
548  }
549  else
550  {
551  UWARN("No transform found for stamp %f! Earliest is %f", stamp, imuIterA->first);
552  }
553  return imuT;
554 }
555 
556 Transform Transform::getClosestTransform(
557  const std::map<double, Transform> & tfBuffer,
558  const double & stamp,
559  double * stampDiff)
560 {
561  UASSERT(!tfBuffer.empty());
562  std::map<double, Transform>::const_iterator imuIterB = tfBuffer.lower_bound(stamp);
563  std::map<double, Transform>::const_iterator imuIterA = imuIterB;
564  if(imuIterA != tfBuffer.begin())
565  {
566  imuIterA = --imuIterA;
567  }
568  if(imuIterB == tfBuffer.end())
569  {
570  imuIterB = --imuIterB;
571  }
572  Transform imuT;
573  if(imuIterB->first == stamp || imuIterA == imuIterB)
574  {
575  imuT = imuIterB->second;
576  if(stampDiff)
577  {
578  *stampDiff = fabs(imuIterB->first - stamp);
579  }
580  }
581  else if(imuIterA != imuIterB)
582  {
583  //interpolate:
584  imuT = imuIterA->second.interpolate((stamp-imuIterA->first) / (imuIterB->first-imuIterA->first), imuIterB->second);
585  if(stampDiff)
586  {
587  *stampDiff = 0.0;
588  }
589  }
590  return imuT;
591 }
592 
593 
594 }
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
void getEulerAngles(float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:253
float getAngle(float x=1.0f, float y=0.0f, float z=0.0f) const
Definition: Transform.cpp:266
bool isInvertible() const
Definition: Transform.cpp:169
float r11() const
Definition: Transform.h:62
T uNorm(const std::vector< T > &v)
Definition: UMath.h:575
float r33() const
Definition: Transform.h:70
static Transform fromEigen4f(const Eigen::Matrix4f &matrix)
Definition: Transform.cpp:406
float r23() const
Definition: Transform.h:67
Transform to4DoF() const
Definition: Transform.cpp:217
float r13() const
Definition: Transform.h:64
static Transform getIdentity()
Definition: Transform.cpp:401
cv::Mat rotationMatrix() const
Definition: Transform.cpp:238
float UTILITE_EXP uStr2Float(const std::string &str)
Transform interpolate(float t, const Transform &other) const
Definition: Transform.cpp:293
float r32() const
Definition: Transform.h:69
Basic mathematics functions.
const float * data() const
Definition: Transform.h:88
float getNorm() const
Definition: Transform.cpp:273
Some conversion functions.
Definition: Features2d.h:41
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
float o34() const
Definition: Transform.h:74
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:248
float r22() const
Definition: Transform.h:66
#define UASSERT(condition)
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:566
bool operator!=(const Transform &t) const
Definition: Transform.cpp:349
static Transform fromEigen3f(const Eigen::Affine3f &matrix)
Definition: Transform.cpp:419
Transform operator*(const Transform &t) const
Definition: Transform.cpp:330
float o24() const
Definition: Transform.h:73
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
std::string prettyPrint() const
Definition: Transform.cpp:316
static Transform getTransform(const std::map< double, Transform > &tfBuffer, const double &stamp)
Definition: Transform.cpp:520
Eigen::Matrix4d toEigen4d() const
Definition: Transform.cpp:371
float o14() const
Definition: Transform.h:72
Eigen::Affine3f toEigen3f() const
Definition: Transform.cpp:381
void normalizeRotation()
Definition: Transform.cpp:306
float getNormSquared() const
Definition: Transform.cpp:278
Transform rotation() const
Definition: Transform.cpp:195
float getDistance(const Transform &t) const
Definition: Transform.cpp:283
bool isNull() const
Definition: Transform.cpp:107
static Transform fromEigen3d(const Eigen::Affine3d &matrix)
Definition: Transform.cpp:425
cv::Mat translationMatrix() const
Definition: Transform.cpp:243
Eigen::Quaternionf getQuaternionf() const
Definition: Transform.cpp:391
float r21() const
Definition: Transform.h:65
float getDistanceSquared(const Transform &t) const
Definition: Transform.cpp:288
static Transform fromEigen4d(const Eigen::Matrix4d &matrix)
Definition: Transform.cpp:412
float r12() const
Definition: Transform.h:63
static bool canParseString(const std::string &string)
Definition: Transform.cpp:514
T uNormSquared(const std::vector< T > &v)
Definition: UMath.h:560
Transform & operator*=(const Transform &t)
Definition: Transform.cpp:338
void getTranslation(float &x, float &y, float &z) const
Definition: Transform.cpp:259
bool is4DoF() const
Definition: Transform.cpp:229
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const CameraModel &model)
ULogger class and convenient macros.
Eigen::Matrix4f toEigen4f() const
Definition: Transform.cpp:362
#define UWARN(...)
bool operator==(const Transform &t) const
Definition: Transform.cpp:344
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
float r31() const
Definition: Transform.h:68
bool uIsNan(const T &value)
Definition: UMath.h:42
Transform to3DoF() const
Definition: Transform.cpp:210
float theta() const
Definition: Transform.cpp:162
static Transform fromString(const std::string &string)
Definition: Transform.cpp:465
std::string UTILITE_EXP uFormat(const char *fmt,...)
Eigen::Quaterniond getQuaterniond() const
Definition: Transform.cpp:396
Transform clone() const
Definition: Transform.cpp:102
Transform translation() const
Definition: Transform.cpp:203
bool isIdentity() const
Definition: Transform.cpp:136
bool is3DoF() const
Definition: Transform.cpp:224
Transform inverse() const
Definition: Transform.cpp:178
Eigen::Affine3d toEigen3d() const
Definition: Transform.cpp:386


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:38:58