Quaternion.h
Go to the documentation of this file.
00001 /*
00002  * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
00003  * http://octomap.github.com/
00004  *
00005  * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg
00006  * All rights reserved.
00007  * License: New BSD
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions are met:
00011  *
00012  *     * Redistributions of source code must retain the above copyright
00013  *       notice, this list of conditions and the following disclaimer.
00014  *     * Redistributions in binary form must reproduce the above copyright
00015  *       notice, this list of conditions and the following disclaimer in the
00016  *       documentation and/or other materials provided with the distribution.
00017  *     * Neither the name of the University of Freiburg nor the names of its
00018  *       contributors may be used to endorse or promote products derived from
00019  *       this software without specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00023  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00024  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00025  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00026  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00027  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00028  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00029  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00030  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  * POSSIBILITY OF SUCH DAMAGE.
00032  */
00033 
00034 #ifndef OCTOMATH_QUATERNION_H
00035 #define OCTOMATH_QUATERNION_H
00036 
00037 #include "Vector3.h"
00038 
00039 #include <iostream>
00040 #include <vector>
00041 
00042 
00043 namespace octomath {
00044 
00056   class Quaternion {
00057 
00058   public:
00059 
00066     inline Quaternion() { u() = 1;  x() = 0; y() = 0; z() = 0;  }
00067 
00071     Quaternion(const Quaternion& other);
00072 
00079     Quaternion(float u, float x, float y, float z);
00080 
00086     Quaternion(const Vector3& other);
00087 
00097     Quaternion(double roll, double pitch, double yaw);
00098 
00099 
00100      
00102     Quaternion(const Vector3& axis, double angle);
00103 
00104 
00111     Vector3 toEuler() const;
00112 
00113     void toRotMatrix(std::vector <double>& rot_matrix_3_3) const;
00114 
00115 
00116     inline const float& operator() (unsigned int i) const { return data[i]; }
00117     inline float& operator() (unsigned int i) { return data[i]; }
00118 
00119     float norm () const;
00120     Quaternion  normalized () const;
00121     Quaternion& normalize ();
00122 
00123 
00124     void operator/= (float x);
00125     Quaternion& operator= (const Quaternion& other);
00126     bool operator== (const Quaternion& other) const;
00127 
00135     Quaternion operator* (const Quaternion& other) const;
00136 
00142     Quaternion operator* (const Vector3 &v) const;
00143 
00149     friend Quaternion operator* (const Vector3 &v, const Quaternion &q);
00150 
00156     inline Quaternion inv() const {  return Quaternion(u(), -x(), -y(), -z()); }
00157 
00158 
00165     Quaternion& inv_IP();
00166 
00176     Vector3 rotate(const Vector3 &v) const;
00177 
00178     inline float& u() { return data[0]; }
00179     inline float& x() { return data[1]; }
00180     inline float& y() { return data[2]; }
00181     inline float& z() { return data[3]; }
00182 
00183     inline const float& u() const { return data[0]; }
00184     inline const float& x() const { return data[1]; }
00185     inline const float& y() const { return data[2]; }
00186     inline const float& z() const { return data[3]; }
00187 
00188     std::istream& read(std::istream &s);
00189     std::ostream& write(std::ostream &s) const;
00190     std::istream& readBinary(std::istream &s);
00191     std::ostream& writeBinary(std::ostream &s) const;
00192 
00193   protected:
00194     float data[4];
00195 
00196   };
00197 
00199   std::ostream& operator<<(std::ostream& s, const Quaternion& q);
00200 
00201 }
00202 
00203 #endif


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Aug 27 2015 14:13:14