00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <rtabmap/core/Transform.h>
00029
00030 #include <pcl/common/eigen.h>
00031 #include <rtabmap/core/util3d.h>
00032 #include <rtabmap/utilite/UConversion.h>
00033 #include <rtabmap/utilite/UMath.h>
00034 #include <iomanip>
00035
00036 namespace rtabmap {
00037
00038 Transform::Transform() : data_(12)
00039 {
00040 data_[0] = 0.0f;
00041 data_[1] = 0.0f;
00042 data_[2] = 0.0f;
00043 data_[3] = 0.0f;
00044 data_[4] = 0.0f;
00045 data_[5] = 0.0f;
00046 data_[6] = 0.0f;
00047 data_[7] = 0.0f;
00048 data_[8] = 0.0f;
00049 data_[9] = 0.0f;
00050 data_[10] = 0.0f;
00051 data_[11] = 0.0f;
00052 }
00053
00054
00055 Transform::Transform(float r11, float r12, float r13, float o14,
00056 float r21, float r22, float r23, float o24,
00057 float r31, float r32, float r33, float o34) :
00058 data_(12)
00059 {
00060 data_[0] = r11;
00061 data_[1] = r12;
00062 data_[2] = r13;
00063 data_[3] = o14;
00064 data_[4] = r21;
00065 data_[5] = r22;
00066 data_[6] = r23;
00067 data_[7] = o24;
00068 data_[8] = r31;
00069 data_[9] = r32;
00070 data_[10] = r33;
00071 data_[11] = o34;
00072 }
00073
00074 Transform::Transform(float x, float y, float z, float roll, float pitch, float yaw)
00075 {
00076 Eigen::Affine3f t = pcl::getTransformation (x, y, z, roll, pitch, yaw);
00077 *this = fromEigen3f(t);
00078 }
00079
00080 bool Transform::isNull() const
00081 {
00082 return (data_[0] == 0.0f &&
00083 data_[1] == 0.0f &&
00084 data_[2] == 0.0f &&
00085 data_[3] == 0.0f &&
00086 data_[4] == 0.0f &&
00087 data_[5] == 0.0f &&
00088 data_[6] == 0.0f &&
00089 data_[7] == 0.0f &&
00090 data_[8] == 0.0f &&
00091 data_[9] == 0.0f &&
00092 data_[10] == 0.0f &&
00093 data_[11] == 0.0f) ||
00094 uIsNan(data_[0]) ||
00095 uIsNan(data_[1]) ||
00096 uIsNan(data_[2]) ||
00097 uIsNan(data_[3]) ||
00098 uIsNan(data_[4]) ||
00099 uIsNan(data_[5]) ||
00100 uIsNan(data_[6]) ||
00101 uIsNan(data_[7]) ||
00102 uIsNan(data_[8]) ||
00103 uIsNan(data_[9]) ||
00104 uIsNan(data_[10]) ||
00105 uIsNan(data_[11]);
00106 }
00107
00108 bool Transform::isIdentity() const
00109 {
00110 return data_[0] == 1.0f &&
00111 data_[1] == 0.0f &&
00112 data_[2] == 0.0f &&
00113 data_[3] == 0.0f &&
00114 data_[4] == 0.0f &&
00115 data_[5] == 1.0f &&
00116 data_[6] == 0.0f &&
00117 data_[7] == 0.0f &&
00118 data_[8] == 0.0f &&
00119 data_[9] == 0.0f &&
00120 data_[10] == 1.0f &&
00121 data_[11] == 0.0f;
00122 }
00123
00124 void Transform::setNull()
00125 {
00126 *this = Transform();
00127 }
00128
00129 void Transform::setIdentity()
00130 {
00131 *this = getIdentity();
00132 }
00133
00134 float Transform::theta() const
00135 {
00136 float roll, pitch, yaw;
00137 this->getEulerAngles(roll, pitch, yaw);
00138 return yaw;
00139 }
00140
00141 Transform Transform::inverse() const
00142 {
00143 return fromEigen4f(toEigen4f().inverse());
00144 }
00145
00146 Transform Transform::rotation() const
00147 {
00148 return Transform(data_[0], data_[1], data_[2], 0,
00149 data_[4], data_[5], data_[6], 0,
00150 data_[8], data_[9], data_[10], 0);
00151 }
00152
00153 Transform Transform::translation() const
00154 {
00155 return Transform(1,0,0, data_[3],
00156 0,1,0, data_[7],
00157 0,0,1, data_[11]);
00158 }
00159
00160 void Transform::getTranslationAndEulerAngles(float & x, float & y, float & z, float & roll, float & pitch, float & yaw) const
00161 {
00162 pcl::getTranslationAndEulerAngles(toEigen3f(), x, y, z, roll, pitch, yaw);
00163 }
00164
00165 void Transform::getEulerAngles(float & roll, float & pitch, float & yaw) const
00166 {
00167 float x,y,z;
00168 pcl::getTranslationAndEulerAngles(toEigen3f(), x, y, z, roll, pitch, yaw);
00169 }
00170
00171 void Transform::getTranslation(float & x, float & y, float & z) const
00172 {
00173 x = this->x();
00174 y = this->y();
00175 z = this->z();
00176 }
00177
00178 float Transform::getNorm() const
00179 {
00180 return uNorm(this->x(), this->y(), this->z());
00181 }
00182
00183 float Transform::getNormSquared() const
00184 {
00185 return uNormSquared(this->x(), this->y(), this->z());
00186 }
00187
00188 float Transform::getDistance(const Transform & t) const
00189 {
00190 return uNorm(this->x()-t.x(), this->y()-t.y(), this->z()-t.z());
00191 }
00192
00193 float Transform::getDistanceSquared(const Transform & t) const
00194 {
00195 return uNormSquared(this->x()-t.x(), this->y()-t.y(), this->z()-t.z());
00196 }
00197
00198 std::string Transform::prettyPrint() const
00199 {
00200 float x,y,z,roll,pitch,yaw;
00201 getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
00202 return uFormat("xyz=%f,%f,%f rpy=%f,%f,%f", x,y,z, roll,pitch,yaw);
00203 }
00204
00205 Transform Transform::operator*(const Transform & t) const
00206 {
00207 return fromEigen4f(toEigen4f()*t.toEigen4f());
00208 }
00209
00210 Transform & Transform::operator*=(const Transform & t)
00211 {
00212 *this = *this * t;
00213 return *this;
00214 }
00215
00216 bool Transform::operator==(const Transform & t) const
00217 {
00218 return memcmp(data_.data(), t.data_.data(), data_.size() * sizeof(float)) == 0;
00219 }
00220
00221 bool Transform::operator!=(const Transform & t) const
00222 {
00223 return !(*this == t);
00224 }
00225
00226 std::ostream& operator<<(std::ostream& os, const Transform& s)
00227 {
00228 for(int i = 0; i < 3; ++i)
00229 {
00230 for(int j = 0; j < 4; ++j)
00231 {
00232 std::cout << std::left << std::setw(12) << s.data()[i*4 + j];
00233 }
00234 std::cout << std::endl;
00235 }
00236 return os;
00237 }
00238
00239 Eigen::Matrix4f Transform::toEigen4f() const
00240 {
00241 Eigen::Matrix4f m;
00242 m << data_[0], data_[1], data_[2], data_[3],
00243 data_[4], data_[5], data_[6], data_[7],
00244 data_[8], data_[9], data_[10], data_[11],
00245 0,0,0,1;
00246 return m;
00247 }
00248 Eigen::Matrix4d Transform::toEigen4d() const
00249 {
00250 Eigen::Matrix4d m;
00251 m << data_[0], data_[1], data_[2], data_[3],
00252 data_[4], data_[5], data_[6], data_[7],
00253 data_[8], data_[9], data_[10], data_[11],
00254 0,0,0,1;
00255 return m;
00256 }
00257
00258 Eigen::Affine3f Transform::toEigen3f() const
00259 {
00260 return Eigen::Affine3f(toEigen4f());
00261 }
00262
00263 Eigen::Affine3d Transform::toEigen3d() const
00264 {
00265 return Eigen::Affine3d(toEigen4d());
00266 }
00267
00268 Eigen::Quaternionf Transform::getQuaternionf() const
00269 {
00270 return Eigen::Quaternionf(this->toEigen3f().rotation()).normalized();
00271 }
00272
00273 Eigen::Quaterniond Transform::getQuaterniond() const
00274 {
00275 return Eigen::Quaterniond(this->toEigen3d().rotation()).normalized();
00276 }
00277
00278 Transform Transform::getIdentity()
00279 {
00280 return Transform(1,0,0,0, 0,1,0,0, 0,0,1,0);
00281 }
00282
00283 Transform Transform::fromEigen4f(const Eigen::Matrix4f & matrix)
00284 {
00285 return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00286 matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00287 matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00288 }
00289 Transform Transform::fromEigen4d(const Eigen::Matrix4d & matrix)
00290 {
00291 return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00292 matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00293 matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00294 }
00295
00296 Transform Transform::fromEigen3f(const Eigen::Affine3f & matrix)
00297 {
00298 return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00299 matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00300 matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00301 }
00302 Transform Transform::fromEigen3d(const Eigen::Affine3d & matrix)
00303 {
00304 return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00305 matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00306 matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00307 }
00308
00309 Transform Transform::fromEigen3f(const Eigen::Isometry3f & matrix)
00310 {
00311 return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00312 matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00313 matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00314 }
00315 Transform Transform::fromEigen3d(const Eigen::Isometry3d & matrix)
00316 {
00317 return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00318 matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00319 matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00320 }
00321
00322 }