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


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