Transform.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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 <rtabmap/utilite/ULogger.h>
00035 #include <rtabmap/utilite/UStl.h>
00036 #include <iomanip>
00037 
00038 namespace rtabmap {
00039 
00040 Transform::Transform() : data_(cv::Mat::zeros(3,4,CV_32FC1))
00041 {
00042 }
00043 
00044 // rotation matrix r## and origin o##
00045 Transform::Transform(
00046                 float r11, float r12, float r13, float o14,
00047                 float r21, float r22, float r23, float o24,
00048                 float r31, float r32, float r33, float o34)
00049 {
00050         data_ = (cv::Mat_<float>(3,4) <<
00051                         r11, r12, r13, o14,
00052                         r21, r22, r23, o24,
00053                         r31, r32, r33, o34);
00054 }
00055 
00056 Transform::Transform(const cv::Mat & transformationMatrix)
00057 {
00058         UASSERT(transformationMatrix.cols == 4 &&
00059                         transformationMatrix.rows == 3 &&
00060                         transformationMatrix.type() == CV_32FC1);
00061         data_ = transformationMatrix;
00062 }
00063 
00064 Transform::Transform(float x, float y, float z, float roll, float pitch, float yaw)
00065 {
00066         Eigen::Affine3f t = pcl::getTransformation (x, y, z, roll, pitch, yaw);
00067         *this = fromEigen3f(t);
00068 }
00069 
00070 Transform::Transform(float x, float y, float z, float qx, float qy, float qz, float qw) :
00071                 data_(cv::Mat::zeros(3,4,CV_32FC1))
00072 {
00073         Eigen::Matrix3f rotation = Eigen::Quaternionf(qw, qx, qy, qz).toRotationMatrix();
00074         data()[0] = rotation(0,0);
00075         data()[1] = rotation(0,1);
00076         data()[2] = rotation(0,2);
00077         data()[3] = x;
00078         data()[4] = rotation(1,0);
00079         data()[5] = rotation(1,1);
00080         data()[6] = rotation(1,2);
00081         data()[7] = y;
00082         data()[8] = rotation(2,0);
00083         data()[9] = rotation(2,1);
00084         data()[10] = rotation(2,2);
00085         data()[11] = z;
00086 }
00087 
00088 Transform::Transform(float x, float y, float theta)
00089 {
00090         Eigen::Affine3f t = pcl::getTransformation (x, y, 0, 0, 0, theta);
00091         *this = fromEigen3f(t);
00092 }
00093 
00094 bool Transform::isNull() const
00095 {
00096         return (data_.empty() ||
00097                         (data()[0] == 0.0f &&
00098                         data()[1] == 0.0f &&
00099                         data()[2] == 0.0f &&
00100                         data()[3] == 0.0f &&
00101                         data()[4] == 0.0f &&
00102                         data()[5] == 0.0f &&
00103                         data()[6] == 0.0f &&
00104                         data()[7] == 0.0f &&
00105                         data()[8] == 0.0f &&
00106                         data()[9] == 0.0f &&
00107                         data()[10] == 0.0f &&
00108                         data()[11] == 0.0f) ||
00109                         uIsNan(data()[0]) ||
00110                         uIsNan(data()[1]) ||
00111                         uIsNan(data()[2]) ||
00112                         uIsNan(data()[3]) ||
00113                         uIsNan(data()[4]) ||
00114                         uIsNan(data()[5]) ||
00115                         uIsNan(data()[6]) ||
00116                         uIsNan(data()[7]) ||
00117                         uIsNan(data()[8]) ||
00118                         uIsNan(data()[9]) ||
00119                         uIsNan(data()[10]) ||
00120                         uIsNan(data()[11]));
00121 }
00122 
00123 bool Transform::isIdentity() const
00124 {
00125         return data()[0] == 1.0f &&
00126                         data()[1] == 0.0f &&
00127                         data()[2] == 0.0f &&
00128                         data()[3] == 0.0f &&
00129                         data()[4] == 0.0f &&
00130                         data()[5] == 1.0f &&
00131                         data()[6] == 0.0f &&
00132                         data()[7] == 0.0f &&
00133                         data()[8] == 0.0f &&
00134                         data()[9] == 0.0f &&
00135                         data()[10] == 1.0f &&
00136                         data()[11] == 0.0f;
00137 }
00138 
00139 void Transform::setNull()
00140 {
00141         *this = Transform();
00142 }
00143 
00144 void Transform::setIdentity()
00145 {
00146         *this = getIdentity();
00147 }
00148 
00149 float Transform::theta() const
00150 {
00151         float roll, pitch, yaw;
00152         this->getEulerAngles(roll, pitch, yaw);
00153         return yaw;
00154 }
00155 
00156 Transform Transform::inverse() const
00157 {
00158         return fromEigen4f(toEigen4f().inverse());
00159 }
00160 
00161 Transform Transform::rotation() const
00162 {
00163         return Transform(
00164                         data()[0], data()[1], data()[2], 0,
00165                         data()[4], data()[5], data()[6], 0,
00166                         data()[8], data()[9], data()[10], 0);
00167 }
00168 
00169 Transform Transform::translation() const
00170 {
00171         return Transform(1,0,0, data()[3],
00172                                          0,1,0, data()[7],
00173                                          0,0,1, data()[11]);
00174 }
00175 
00176 Transform Transform::to3DoF() const
00177 {
00178         float x,y,z,roll,pitch,yaw;
00179         this->getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
00180         return Transform(x,y,0, 0,0,yaw);
00181 }
00182 
00183 cv::Mat Transform::rotationMatrix() const
00184 {
00185         return data_.colRange(0, 3).clone();
00186 }
00187 
00188 cv::Mat Transform::translationMatrix() const
00189 {
00190         return data_.col(3).clone();
00191 }
00192 
00193 void Transform::getTranslationAndEulerAngles(float & x, float & y, float & z, float & roll, float & pitch, float & yaw) const
00194 {
00195         pcl::getTranslationAndEulerAngles(toEigen3f(), x, y, z, roll, pitch, yaw);
00196 }
00197 
00198 void Transform::getEulerAngles(float & roll, float & pitch, float & yaw) const
00199 {
00200         float x,y,z;
00201         pcl::getTranslationAndEulerAngles(toEigen3f(), x, y, z, roll, pitch, yaw);
00202 }
00203 
00204 void Transform::getTranslation(float & x, float & y, float & z) const
00205 {
00206         x = this->x();
00207         y = this->y();
00208         z = this->z();
00209 }
00210 
00211 float Transform::getNorm() const
00212 {
00213         return uNorm(this->x(), this->y(), this->z());
00214 }
00215 
00216 float Transform::getNormSquared() const
00217 {
00218         return uNormSquared(this->x(), this->y(), this->z());
00219 }
00220 
00221 float Transform::getDistance(const Transform & t) const
00222 {
00223         return uNorm(this->x()-t.x(), this->y()-t.y(), this->z()-t.z());
00224 }
00225 
00226 float Transform::getDistanceSquared(const Transform & t) const
00227 {
00228         return uNormSquared(this->x()-t.x(), this->y()-t.y(), this->z()-t.z());
00229 }
00230 
00231 Transform Transform::interpolate(float t, const Transform & other) const
00232 {
00233         Eigen::Quaternionf qa=this->getQuaternionf();
00234         Eigen::Quaternionf qb=other.getQuaternionf();
00235         Eigen::Quaternionf qres = qa.slerp(t, qb);
00236 
00237         float x = this->x() + t*(other.x() - this->x());
00238         float y = this->y() + t*(other.y() - this->y());
00239         float z = this->z() + t*(other.z() - this->z());
00240 
00241         return Transform(x,y,z, qres.x(), qres.y(), qres.z(), qres.w());
00242 }
00243 
00244 std::string Transform::prettyPrint() const
00245 {
00246         if(this->isNull())
00247         {
00248                 return uFormat("xyz=[null] rpy=[null]");
00249         }
00250         else
00251         {
00252                 float x,y,z,roll,pitch,yaw;
00253                 getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
00254                 return uFormat("xyz=%f,%f,%f rpy=%f,%f,%f", x,y,z, roll,pitch,yaw);
00255         }
00256 }
00257 
00258 Transform Transform::operator*(const Transform & t) const
00259 {
00260         return fromEigen4f(toEigen4f()*t.toEigen4f());
00261 }
00262 
00263 Transform & Transform::operator*=(const Transform & t)
00264 {
00265         *this = *this * t;
00266         return *this;
00267 }
00268 
00269 bool Transform::operator==(const Transform & t) const
00270 {
00271         return memcmp(data_.data, t.data_.data, data_.total() * sizeof(float)) == 0;
00272 }
00273 
00274 bool Transform::operator!=(const Transform & t) const
00275 {
00276         return !(*this == t);
00277 }
00278 
00279 std::ostream& operator<<(std::ostream& os, const Transform& s)
00280 {
00281         for(int i = 0; i < 3; ++i)
00282         {
00283                 for(int j = 0; j < 4; ++j)
00284                 {
00285                         std::cout << std::left << std::setw(12) << s.data()[i*4 + j];
00286                 }
00287                 std::cout << std::endl;
00288         }
00289         return os;
00290 }
00291 
00292 Eigen::Matrix4f Transform::toEigen4f() const
00293 {
00294         Eigen::Matrix4f m;
00295         m << data()[0], data()[1], data()[2], data()[3],
00296                  data()[4], data()[5], data()[6], data()[7],
00297                  data()[8], data()[9], data()[10], data()[11],
00298                  0,0,0,1;
00299         return m;
00300 }
00301 Eigen::Matrix4d Transform::toEigen4d() const
00302 {
00303         Eigen::Matrix4d m;
00304         m << data()[0], data()[1], data()[2], data()[3],
00305                  data()[4], data()[5], data()[6], data()[7],
00306                  data()[8], data()[9], data()[10], data()[11],
00307                  0,0,0,1;
00308         return m;
00309 }
00310 
00311 Eigen::Affine3f Transform::toEigen3f() const
00312 {
00313         return Eigen::Affine3f(toEigen4f());
00314 }
00315 
00316 Eigen::Affine3d Transform::toEigen3d() const
00317 {
00318         return Eigen::Affine3d(toEigen4d());
00319 }
00320 
00321 Eigen::Quaternionf Transform::getQuaternionf() const
00322 {
00323         return Eigen::Quaternionf(this->toEigen3f().rotation()).normalized();
00324 }
00325 
00326 Eigen::Quaterniond Transform::getQuaterniond() const
00327 {
00328         return Eigen::Quaterniond(this->toEigen3d().rotation()).normalized();
00329 }
00330 
00331 Transform Transform::getIdentity()
00332 {
00333         return Transform(1,0,0,0, 0,1,0,0, 0,0,1,0);
00334 }
00335 
00336 Transform Transform::fromEigen4f(const Eigen::Matrix4f & matrix)
00337 {
00338         return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00339                                          matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00340                                          matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00341 }
00342 Transform Transform::fromEigen4d(const Eigen::Matrix4d & matrix)
00343 {
00344         return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00345                                          matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00346                                          matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00347 }
00348 
00349 Transform Transform::fromEigen3f(const Eigen::Affine3f & matrix)
00350 {
00351         return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00352                                          matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00353                                          matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00354 }
00355 Transform Transform::fromEigen3d(const Eigen::Affine3d & matrix)
00356 {
00357         return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00358                                          matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00359                                          matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00360 }
00361 
00362 Transform Transform::fromEigen3f(const Eigen::Isometry3f & matrix)
00363 {
00364         return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00365                                          matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00366                                          matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00367 }
00368 Transform Transform::fromEigen3d(const Eigen::Isometry3d & matrix)
00369 {
00370         return Transform(matrix(0,0), matrix(0,1), matrix(0,2), matrix(0,3),
00371                                          matrix(1,0), matrix(1,1), matrix(1,2), matrix(1,3),
00372                                          matrix(2,0), matrix(2,1), matrix(2,2), matrix(2,3));
00373 }
00374 
00382 Transform Transform::fromString(const std::string & string)
00383 {
00384         std::list<std::string> list = uSplit(string, ' ');
00385         UASSERT_MSG(list.empty() || list.size() == 3 || list.size() == 6 || list.size() == 7 || list.size() == 9 || list.size() == 12,
00386                         uFormat("Cannot parse \"%s\"", string.c_str()).c_str());
00387 
00388         std::vector<float> numbers(list.size());
00389         int i = 0;
00390         for(std::list<std::string>::iterator iter=list.begin(); iter!=list.end(); ++iter)
00391         {
00392                 numbers[i++] = uStr2Float(*iter);
00393         }
00394 
00395         Transform t;
00396         if(numbers.size() == 3)
00397         {
00398                 t = Transform(numbers[0], numbers[1], numbers[2]);
00399         }
00400         else if(numbers.size() == 6)
00401         {
00402                 t = Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5]);
00403         }
00404         else if(numbers.size() == 7)
00405         {
00406 
00407                 t = Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5], numbers[6]);
00408         }
00409         else if(numbers.size() == 9)
00410         {
00411                 t = Transform(numbers[0], numbers[1], numbers[2], 0,
00412                                           numbers[3], numbers[4], numbers[5], 0,
00413                                           numbers[6], numbers[7], numbers[8], 0);
00414         }
00415         else if(numbers.size() == 12)
00416         {
00417                 t = Transform(numbers[0], numbers[1], numbers[2], numbers[3],
00418                                           numbers[4], numbers[5], numbers[6], numbers[7],
00419                                           numbers[8], numbers[9], numbers[10], numbers[11]);
00420         }
00421         return t;
00422 }
00423 
00431 bool Transform::canParseString(const std::string & string)
00432 {
00433         std::list<std::string> list = uSplit(string, ' ');
00434         return list.size() == 0 || list.size() == 3 || list.size() == 6 || list.size() == 7 || list.size() == 9 || list.size() == 12;
00435 }
00436 
00437 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:27