eigen.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR a PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  */
00035 
00036 #include <pcl/pcl_macros.h>
00037 
00038 void pcl::getTransFromUnitVectorsZY(const Eigen::Vector3f& z_axis, const Eigen::Vector3f& y_direction, Eigen::Affine3f& transformation)
00039 {
00040   Eigen::Vector3f tmp0 = (y_direction.cross(z_axis)).normalized();
00041   Eigen::Vector3f tmp1 = (z_axis.cross(tmp0)).normalized();
00042   Eigen::Vector3f tmp2 = z_axis.normalized();
00043   
00044   transformation(0,0)=tmp0[0]; transformation(0,1)=tmp0[1]; transformation(0,2)=tmp0[2]; transformation(0,3)=0.0f;
00045   transformation(1,0)=tmp1[0]; transformation(1,1)=tmp1[1]; transformation(1,2)=tmp1[2]; transformation(1,3)=0.0f;
00046   transformation(2,0)=tmp2[0]; transformation(2,1)=tmp2[1]; transformation(2,2)=tmp2[2]; transformation(2,3)=0.0f;
00047   transformation(3,0)=0.0f;    transformation(3,1)=0.0f;    transformation(3,2)=0.0f;    transformation(3,3)=1.0f;
00048 }
00049 
00050 Eigen::Affine3f pcl::getTransFromUnitVectorsZY(const Eigen::Vector3f& z_axis, const Eigen::Vector3f& y_direction)
00051 {
00052   Eigen::Affine3f transformation;
00053   getTransFromUnitVectorsZY(z_axis, y_direction, transformation);
00054   return transformation;
00055 }
00056 
00057 void pcl::getTransFromUnitVectorsXY(const Eigen::Vector3f& x_axis, const Eigen::Vector3f& y_direction, Eigen::Affine3f& transformation)
00058 {
00059   Eigen::Vector3f tmp2 = (x_axis.cross(y_direction)).normalized();
00060   Eigen::Vector3f tmp1 = (tmp2.cross(x_axis)).normalized();
00061   Eigen::Vector3f tmp0 = x_axis.normalized();
00062   
00063   transformation(0,0)=tmp0[0]; transformation(0,1)=tmp0[1]; transformation(0,2)=tmp0[2]; transformation(0,3)=0.0f;
00064   transformation(1,0)=tmp1[0]; transformation(1,1)=tmp1[1]; transformation(1,2)=tmp1[2]; transformation(1,3)=0.0f;
00065   transformation(2,0)=tmp2[0]; transformation(2,1)=tmp2[1]; transformation(2,2)=tmp2[2]; transformation(2,3)=0.0f;
00066   transformation(3,0)=0.0f;    transformation(3,1)=0.0f;    transformation(3,2)=0.0f;    transformation(3,3)=1.0f;
00067 }
00068 
00069 Eigen::Affine3f pcl::getTransFromUnitVectorsXY(const Eigen::Vector3f& x_axis, const Eigen::Vector3f& y_direction)
00070 {
00071   Eigen::Affine3f transformation;
00072   getTransFromUnitVectorsXY(x_axis, y_direction, transformation);
00073   return transformation;
00074 }
00075 
00076 void pcl::getTransformationFromTwoUnitVectors(const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis, Eigen::Affine3f& transformation)
00077 {
00078   getTransFromUnitVectorsZY(z_axis, y_direction, transformation);
00079 }
00080 
00081 Eigen::Affine3f pcl::getTransformationFromTwoUnitVectors(const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis)
00082 {
00083   Eigen::Affine3f transformation;
00084   getTransformationFromTwoUnitVectors(y_direction, z_axis, transformation);
00085   return transformation;
00086 }
00087 
00088 void pcl::getTransformationFromTwoUnitVectorsAndOrigin(const Eigen::Vector3f& y_direction, const Eigen::Vector3f& z_axis,
00089                                                   const Eigen::Vector3f& origin, Eigen::Affine3f& transformation)
00090 {
00091   getTransformationFromTwoUnitVectors(y_direction, z_axis, transformation);
00092   Eigen::Vector3f translation = transformation*origin;
00093   transformation(0,3)=-translation[0];  transformation(1,3)=-translation[1];  transformation(2,3)=-translation[2];
00094 }
00095 
00096 void pcl::getEulerAngles(const Eigen::Affine3f& t, float& roll, float& pitch, float& yaw)
00097 {
00098   roll  = atan2f(t(2,1), t(2,2));
00099   pitch = asinf(-t(2,0));
00100   yaw   = atan2f(t(1,0), t(0,0));
00101 }
00102 
00103 void pcl::getTranslationAndEulerAngles(const Eigen::Affine3f& t, float& x, float& y, float& z, float& roll, float& pitch, float& yaw)
00104 {
00105   x = t(0,3);
00106   y = t(1,3);
00107   z = t(2,3);
00108   roll  = atan2f(t(2,1), t(2,2));
00109   pitch = asinf(-t(2,0));
00110   yaw   = atan2f(t(1,0), t(0,0));
00111 }
00112 
00113 void pcl::getTransformation(float x, float y, float z, float roll, float pitch, float yaw, Eigen::Affine3f& t)
00114 {
00115   float A=cosf(yaw),  B=sinf(yaw),  C=cosf(pitch), D=sinf(pitch),
00116         E=cosf(roll), F=sinf(roll), DE=D*E,        DF=D*F;
00117   t(0,0) = A*C;  t(0,1) = A*DF - B*E;  t(0,2) = B*F + A*DE;  t(0,3) = x;
00118   t(1,0) = B*C;  t(1,1) = A*E + B*DF;  t(1,2) = B*DE - A*F;  t(1,3) = y;
00119   t(2,0) = -D;   t(2,1) = C*F;         t(2,2) = C*E;         t(2,3) = z;
00120   t(3,0) = 0;    t(3,1) = 0;           t(3,2) = 0;           t(3,3) = 1;
00121 }
00122 
00123 Eigen::Affine3f pcl::getTransformation(float x, float y, float z, float roll, float pitch, float yaw)
00124 {
00125   Eigen::Affine3f t;
00126   getTransformation(x, y, z, roll, pitch, yaw, t);
00127   return t;
00128 }
00129 
00130 template <typename Derived> void 
00131 pcl::saveBinary (const Eigen::MatrixBase<Derived>& matrix, std::ostream& file)
00132 {
00133   uint32_t rows = static_cast<uint32_t> (matrix.rows ()), cols = static_cast<uint32_t> (matrix.cols ());
00134   file.write (reinterpret_cast<char*> (&rows), sizeof (rows));
00135   file.write (reinterpret_cast<char*> (&cols), sizeof (cols));
00136   for (uint32_t i = 0; i < rows; ++i)
00137     for (uint32_t j = 0; j < cols; ++j)
00138     {
00139       typename Derived::Scalar tmp = matrix(i,j);
00140       file.write (reinterpret_cast<const char*> (&tmp), sizeof (tmp));
00141     }
00142 }
00143 
00144 template <typename Derived> void 
00145 pcl::loadBinary (Eigen::MatrixBase<Derived> const & matrix_, std::istream& file)
00146 {
00147   Eigen::MatrixBase<Derived> &matrix = const_cast<Eigen::MatrixBase<Derived> &> (matrix_);
00148 
00149   uint32_t rows, cols;
00150   file.read (reinterpret_cast<char*> (&rows), sizeof (rows));
00151   file.read (reinterpret_cast<char*> (&cols), sizeof (cols));
00152   if (matrix.rows () != static_cast<int>(rows) || matrix.cols () != static_cast<int>(cols))
00153     matrix.derived().resize(rows, cols);
00154   
00155   for (uint32_t i = 0; i < rows; ++i)
00156     for (uint32_t j = 0; j < cols; ++j)
00157     {
00158       typename Derived::Scalar tmp;
00159       file.read (reinterpret_cast<char*> (&tmp), sizeof (tmp));
00160       matrix (i, j) = tmp;
00161     }
00162 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:49