30 #include <pcl/common/eigen.h> 31 #include <pcl/common/common.h> 51 data_ = (cv::Mat_<float>(3,4) <<
59 UASSERT(transformationMatrix.cols == 4 &&
60 transformationMatrix.rows == 3 &&
61 (transformationMatrix.type() == CV_32FC1 || transformationMatrix.type() == CV_64FC1));
62 if(transformationMatrix.type() == CV_32FC1)
64 data_ = transformationMatrix;
68 transformationMatrix.convertTo(
data_, CV_32F);
74 Eigen::Affine3f t = pcl::getTransformation (x, y, z, roll, pitch, yaw);
79 data_(
cv::Mat::zeros(3,4,CV_32FC1))
81 Eigen::Matrix3f
rotation = Eigen::Quaternionf(qw, qx, qy, qz).normalized().toRotationMatrix();
98 Eigen::Affine3f t = pcl::getTransformation (x, y, 0, 0, 0, theta);
109 return (
data_.empty() ||
110 (
data()[0] == 0.0f &&
120 data()[10] == 0.0f &&
121 data()[11] == 0.0f) ||
138 return data()[0] == 1.0f &&
148 data()[10] == 1.0f &&
171 bool invertible =
false;
173 Eigen::Matrix4f::RealScalar det;
174 toEigen4f().computeInverseAndDetWithCheck(inverse, det, invertible);
180 bool invertible =
false;
182 Eigen::Matrix4f::RealScalar det;
183 toEigen4f().computeInverseAndDetWithCheck(inverse, det, invertible);
231 return r13() == 0.0 &&
240 return data_.colRange(0, 3).clone();
245 return data_.col(3).clone();
250 pcl::getTranslationAndEulerAngles(
toEigen3f(), x, y, z, roll, pitch, yaw);
256 pcl::getTranslationAndEulerAngles(
toEigen3f(), x, y, z, roll, pitch, yaw);
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));
275 return uNorm(this->
x(), this->
y(), this->
z());
285 return uNorm(this->
x()-t.
x(), this->
y()-t.
y(), this->
z()-t.
z());
297 Eigen::Quaternionf qres = qa.slerp(t, qb);
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());
303 return Transform(x,y,z, qres.x(), qres.y(), qres.z(), qres.w());
311 m.linear() = Eigen::Quaternionf(m.linear()).normalized().toRotationMatrix();
320 return uFormat(
"xyz=[null] rpy=[null]");
326 return uFormat(
"xyz=%f,%f,%f rpy=%f,%f,%f", x,y,z, roll,pitch,yaw);
334 m.linear() = Eigen::Quaternionf(m.linear()).normalized().toRotationMatrix();
346 return memcmp(
data_.data, t.
data_.data,
data_.total() *
sizeof(float)) == 0;
351 return !(*
this == t);
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] <<
"]";
393 return Eigen::Quaternionf(this->
toEigen3f().linear()).normalized();
398 return Eigen::Quaterniond(this->
toEigen3d().linear()).normalized();
403 return Transform(1,0,0,0, 0,1,0,0, 0,0,1,0);
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));
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));
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));
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));
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));
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));
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));
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));
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());
471 std::vector<float> numbers(list.size());
473 for(std::list<std::string>::iterator iter=list.begin(); iter!=list.end(); ++iter)
479 if(numbers.size() == 3)
481 t =
Transform(numbers[0], numbers[1], numbers[2]);
483 else if(numbers.size() == 6)
485 t =
Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5]);
487 else if(numbers.size() == 7)
490 t =
Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5], numbers[6]);
492 else if(numbers.size() == 9)
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);
498 else if(numbers.size() == 12)
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]);
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;
521 const std::map<double, Transform> & tfBuffer,
522 const double & stamp)
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())
529 imuIterA = --imuIterA;
531 if(imuIterB == tfBuffer.end())
533 imuIterB = --imuIterB;
536 if(imuIterB->first == stamp)
538 imuT = imuIterB->second;
540 else if(imuIterA != imuIterB)
543 imuT = imuIterA->second.
interpolate((stamp-imuIterA->first) / (imuIterB->first-imuIterA->first), imuIterB->second);
545 else if(stamp > imuIterB->first)
547 UWARN(
"No transform found for stamp %f! Latest is %f", stamp, imuIterB->first);
551 UWARN(
"No transform found for stamp %f! Earliest is %f", stamp, imuIterA->first);
556 Transform Transform::getClosestTransform(
557 const std::map<double, Transform> & tfBuffer,
558 const double & stamp,
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())
566 imuIterA = --imuIterA;
568 if(imuIterB == tfBuffer.end())
570 imuIterB = --imuIterB;
573 if(imuIterB->first == stamp || imuIterA == imuIterB)
575 imuT = imuIterB->second;
578 *stampDiff = fabs(imuIterB->first - stamp);
581 else if(imuIterA != imuIterB)
584 imuT = imuIterA->second.
interpolate((stamp-imuIterA->first) / (imuIterB->first-imuIterA->first), imuIterB->second);
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
T uNorm(const std::vector< T > &v)
float UTILITE_EXP uStr2Float(const std::string &str)
Basic mathematics functions.
Some conversion functions.
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
#define UASSERT_MSG(condition, msg_str)
T uNormSquared(const std::vector< T > &v)
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const CameraModel &model)
ULogger class and convenient macros.
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
bool uIsNan(const T &value)
std::string UTILITE_EXP uFormat(const char *fmt,...)