conversions.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
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 the LABUST 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  *  Created: 20.05.2013.
00035  *  Author: Đula Nađ
00036  *********************************************************************/
00037 #ifndef CONVERSIONS_HPP_
00038 #define CONVERSIONS_HPP_
00039 #include <Eigen/Dense>
00040 
00041 #include <geometry_msgs/Quaternion.h>
00042 
00043 namespace labust
00044 {
00045         namespace tools
00046         {
00050                 template <class Point, class Iterator>
00051                 void pointToVector(const Point& point, Iterator& vec, int offset = 0)
00052                 {
00053                         vec[offset+0] = point.x;
00054                         vec[offset+1] = point.y;
00055                         vec[offset+2] = point.z;
00056                 }
00057 
00061                 template <class Point, class Iterator>
00062                 void vectorToPoint(const Iterator& vec, Point& point, int offset = 0)
00063                 {
00064                         point.x = vec[offset+0];
00065                         point.y = vec[offset+1];
00066                         point.z = vec[offset+2];
00067                 }
00068 
00072                 template <class Point, class Iterator>
00073                 void nedToVector(const Point& point, Iterator& vec, int offset = 0)
00074                 {
00075                         vec[offset+0] = point.north;
00076                         vec[offset+1] = point.east;
00077                         vec[offset+2] = point.depth;
00078                 }
00079 
00083                 template <class Point, class Iterator>
00084                 void vectorToNED(const Iterator& vec, Point& point, int offset = 0)
00085                 {
00086                         point.north = vec[offset+0];
00087                         point.east = vec[offset+1];
00088                         point.depth = vec[offset+2];
00089                 }
00090 
00094                 template <class Point, class Iterator>
00095                 void rpyToVector(const Point& point, Iterator& vec, int offset = 0)
00096                 {
00097                         vec[offset+0] = point.roll;
00098                         vec[offset+1] = point.pitch;
00099                         vec[offset+2] = point.yaw;
00100                 }
00101 
00105                 template <class Point, class Iterator>
00106                 void vectorToRPY(const Iterator& vec, Point& point, int offset = 0)
00107                 {
00108                         point.roll = vec[offset+0];
00109                         point.pitch = vec[offset+1];
00110                         point.yaw = vec[offset+2];
00111                 }
00112 
00116                 template <class Point, class Iterator>
00117                 void vectorToDisableAxis(const Iterator& vec, Point& point)
00118                 {
00119                         point.x = vec[0];
00120                         point.y = vec[1];
00121                         point.z = vec[2];
00122                         point.roll = vec[3];
00123                         point.pitch = vec[4];
00124                         point.yaw = vec[5];
00125                 }
00126 
00127                 template <class Point, class Iterator>
00128                 void disableAxisToVector(Point& point, const Iterator& vec)
00129                 {
00130                         vec[0] = point.x;
00131                         vec[1] = point.y;
00132                         vec[2] = point.z;
00133                         vec[3] = point.roll;
00134                         vec[4] = point.pitch;
00135                         vec[5] = point.yaw;
00136                 }
00137 
00138                 template <class T>
00139                 void quaternionFromEulerZYX(double roll, double pitch, double yaw, Eigen::Quaternion<T>& q)
00140                 {
00141                         using namespace Eigen;
00142                         Matrix<T,3,3> Cx,Cy,Cz,m;
00143                         typedef Matrix<T,3,1> Vector3;
00144                         Cx = AngleAxis<T>(roll, Vector3::UnitX());
00145                         Cy = AngleAxis<T>(pitch, Vector3::UnitY());
00146                         Cz = AngleAxis<T>(yaw, Vector3::UnitZ());
00147                         //ZYX convention
00148                         m = (Cz*Cy*Cx); //From child to parent
00149                         //m = (Cz*Cy*Cx).transpose(); //From parent to child
00150                         q = Quaternion<T>(m);
00151                 }
00152 
00153                 template <class T>
00154                 void quaternionFromEulerZYX(double roll, double pitch, double yaw, T& q)
00155                 {
00156                         Eigen::Quaternion<double> t;
00157                         quaternionFromEulerZYX(roll, pitch, yaw, t);
00158                         q.x = t.x();
00159                         q.y = t.y();
00160                         q.z = t.z();
00161                         q.w = t.w();
00162                 }
00163 
00164                 //\todo Test and document this method
00165                 template <class T>
00166                 void eulerZYXFromQuaternion(const T& q, double& roll, double& pitch, double& yaw)
00167                 {
00168                         using namespace Eigen;
00169                         //From child to parent
00170                         roll = atan2(2*(q.y()*q.z() + q.x()*q.w()),1-2*(q.x()*q.x() + q.y()*q.y()));
00171                         pitch = -asin(2*(q.x()*q.z()-q.y()*q.w()));
00172                         yaw = atan2(2*(q.y()*q.x()+q.w()*q.z()),1-2*(q.y()*q.y()+q.z()*q.z()));
00173                         //From parent to child
00174                         //roll = atan2(2*(q.y()*q.z() - q.x()*q.w()),1-2*(q.x()*q.x() + q.y()*q.y()));
00175                         //pitch = -asin(2*(q.x()*q.z() + q.y()*q.w()));
00176                         //yaw = atan2(2*(q.x()*q.y()-q.w()*q.z()),1-2*(q.y()*q.y()+q.z()*q.z()));
00177                 }
00178 
00179                 //\todo Test and document this method
00180                 template <class T, class V>
00181                 void eulerZYXFromQuaternion(const T& q, V& vect)
00182                 {
00183                         using namespace Eigen;
00184                         //From child to parent
00185                         enum {roll=0, pitch, yaw};
00186                         vect(roll) = atan2(2*(q.y()*q.z() + q.x()*q.w()),1-2*(q.x()*q.x() + q.y()*q.y()));
00187                         vect(pitch) = -asin(2*(q.x()*q.z()-q.y()*q.w()));
00188                         vect(yaw) = atan2(2*(q.y()*q.x()+q.w()*q.z()),1-2*(q.y()*q.y()+q.z()*q.z()));
00189                         //From parent to child
00190                         //roll = atan2(2*(q.y()*q.z() - q.x()*q.w()),1-2*(q.x()*q.x() + q.y()*q.y()));
00191                         //pitch = -asin(2*(q.x()*q.z() + q.y()*q.w()));
00192                         //yaw = atan2(2*(q.x()*q.y()-q.w()*q.z()),1-2*(q.y()*q.y()+q.z()*q.z()));
00193                 }
00194 
00195                 //\todo Test and document this method
00196                 inline void eulerZYXFromQuaternion(const geometry_msgs::Quaternion& q,
00197                                 double& roll, double& pitch, double& yaw)
00198                 {
00199                         using namespace Eigen;
00200                         //From child to parent
00201                         roll = atan2(2*(q.y*q.z + q.x*q.w),1-2*(q.x*q.x + q.y*q.y));
00202                         pitch = -asin(2*(q.x*q.z-q.y*q.w));
00203                         yaw = atan2(2*(q.y*q.x+q.w*q.z),1-2*(q.y*q.y+q.z*q.z));
00204                         //From parent to child
00205                         //roll = atan2(2*(q.y*q.z - q.x*q.w),1-2*(q.x*q.x + q.y*q.y));
00206                         //pitch = -asin(2*(q.x*q.z + q.y*q.w));
00207                         //yaw = atan2(2*(q.x*q.y-q.w*q.z),1-2*(q.y*q.y+q.z*q.z));
00208                 }
00209         }
00210 }
00211 
00212 /* CONVERSIONS_HPP_ */
00213 #endif


snippets
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:33