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 &&
198 return data_.colRange(0, 3).clone();
203 return data_.col(3).clone();
208 pcl::getTranslationAndEulerAngles(
toEigen3f(), x, y, z, roll, pitch, yaw);
214 pcl::getTranslationAndEulerAngles(
toEigen3f(), x, y, z, roll, pitch, yaw);
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));
233 return uNorm(this->
x(), this->
y(), this->
z());
243 return uNorm(this->
x()-t.
x(), this->
y()-t.
y(), this->
z()-t.
z());
255 Eigen::Quaternionf qres = qa.slerp(t, qb);
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());
261 return Transform(x,y,z, qres.x(), qres.y(), qres.z(), qres.w());
269 m.linear() = Eigen::Quaternionf(m.linear()).normalized().toRotationMatrix();
278 return uFormat(
"xyz=[null] rpy=[null]");
284 return uFormat(
"xyz=%f,%f,%f rpy=%f,%f,%f", x,y,z, roll,pitch,yaw);
292 m.linear() = Eigen::Quaternionf(m.linear()).normalized().toRotationMatrix();
304 return memcmp(
data_.data, t.
data_.data,
data_.total() *
sizeof(float)) == 0;
309 return !(*
this == t);
314 for(
int i = 0; i < 3; ++i)
316 for(
int j = 0; j < 4; ++j)
318 os << std::left << std::setw(12) << s.
data()[i*4 + j] <<
" ";
356 return Eigen::Quaternionf(this->
toEigen3f().linear()).normalized();
361 return Eigen::Quaterniond(this->
toEigen3d().linear()).normalized();
366 return Transform(1,0,0,0, 0,1,0,0, 0,0,1,0);
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));
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));
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));
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));
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));
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));
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());
421 std::vector<float> numbers(list.size());
423 for(std::list<std::string>::iterator iter=list.begin(); iter!=list.end(); ++iter)
429 if(numbers.size() == 3)
431 t =
Transform(numbers[0], numbers[1], numbers[2]);
433 else if(numbers.size() == 6)
435 t =
Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5]);
437 else if(numbers.size() == 7)
440 t =
Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5], numbers[6]);
442 else if(numbers.size() == 9)
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);
448 else if(numbers.size() == 12)
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]);
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;
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)
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
#define UASSERT(condition)
Wrappers of STL for convenient functions.
#define UASSERT_MSG(condition, msg_str)
T uNormSquared(const std::vector< T > &v)
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,...)
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const Transform &s)