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 namespace labust
00042 {
00043         namespace tools
00044         {
00048                 template <class Point, class Iterator>
00049                 void pointToVector(const Point& point, Iterator& vec, int offset = 0)
00050                 {
00051                         vec[offset+0] = point.x;
00052                         vec[offset+1] = point.y;
00053                         vec[offset+2] = point.z;
00054                 }
00055 
00059                 template <class Point, class Iterator>
00060                 void vectorToPoint(const Iterator& vec, Point& point, int offset = 0)
00061                 {
00062                         point.x = vec[offset+0];
00063                         point.y = vec[offset+1];
00064                         point.z = vec[offset+2];
00065                 }
00066 
00070                 template <class Point, class Iterator>
00071                 void nedToVector(const Point& point, Iterator& vec, int offset = 0)
00072                 {
00073                         vec[offset+0] = point.north;
00074                         vec[offset+1] = point.east;
00075                         vec[offset+2] = point.depth;
00076                 }
00077 
00081                 template <class Point, class Iterator>
00082                 void vectorToNED(const Iterator& vec, Point& point, int offset = 0)
00083                 {
00084                         point.north = vec[offset+0];
00085                         point.east = vec[offset+1];
00086                         point.depth = vec[offset+2];
00087                 }
00088 
00092                 template <class Point, class Iterator>
00093                 void rpyToVector(const Point& point, Iterator& vec, int offset = 0)
00094                 {
00095                         vec[offset+0] = point.roll;
00096                         vec[offset+1] = point.pitch;
00097                         vec[offset+2] = point.yaw;
00098                 }
00099 
00103                 template <class Point, class Iterator>
00104                 void vectorToRPY(const Iterator& vec, Point& point, int offset = 0)
00105                 {
00106                         point.roll = vec[offset+0];
00107                         point.pitch = vec[offset+1];
00108                         point.yaw = vec[offset+2];
00109                 }
00110 
00114                 template <class Point, class Iterator>
00115                 void vectorToDisableAxis(const Iterator& vec, Point& point)
00116                 {
00117                         point.x = vec[0];
00118                         point.y = vec[1];
00119                         point.z = vec[2];
00120                         point.roll = vec[3];
00121                         point.pitch = vec[4];
00122                         point.yaw = vec[5];
00123                 }
00124 
00125                 template <class Point, class Iterator>
00126                 void disableAxisToVector(Point& point, const Iterator& vec)
00127                 {
00128                         vec[0] = point.x;
00129                         vec[1] = point.y;
00130                         vec[2] = point.z;
00131                         vec[3] = point.roll;
00132                         vec[4] = point.pitch;
00133                         vec[5] = point.yaw;
00134                 }
00135 
00136                 template <class T>
00137                 void quaternionFromEulerZYX(double roll, double pitch, double yaw, Eigen::Quaternion<T>& q)
00138                 {
00139                         using namespace Eigen;
00140                         Matrix<T,3,3> m;
00141                         typedef Matrix<T,3,1> Vector3;
00142                         m = AngleAxis<T>(yaw, Vector3::UnitZ())
00143                         * AngleAxis<T>(pitch, Vector3::UnitY())
00144                         * AngleAxis<T>(roll, Vector3::UnitX());
00145                         q = Quaternion<T>(m);
00146                 }
00147 
00148                 //\todo Test and document this method
00149                 template <class T>
00150                 void eulerZYXFromQuaternion(const T& q, double& roll, double& pitch, double& yaw)
00151                 {
00152                         using namespace Eigen;
00153                         yaw = atan2(2*(q.w()*q.z() + q.x()*q.y()),1-2*(q.z()*q.z() + q.y()*q.y()));
00154                         pitch = -asin(2*(q.x()*q.z()-q.y()*q.w()));
00155                         roll = atan2(2*(q.w()*q.x()+q.y()*q.z()),1-2*(q.y()*q.y()+q.x()*q.x()));
00156                 }
00157         }
00158 }
00159 
00160 /* CONVERSIONS_HPP_ */
00161 #endif


snippets
Author(s): Gyula Nagy
autogenerated on Mon Oct 6 2014 01:39:41