.. _program_listing_file__tmp_ws_src_octomap_octomap_include_octomap_math_Quaternion.h: Program Listing for File Quaternion.h ===================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/octomap/octomap/include/octomap/math/Quaternion.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees * https://octomap.github.io/ * * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg * All rights reserved. * License: New BSD * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the University of Freiburg nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef OCTOMATH_QUATERNION_H #define OCTOMATH_QUATERNION_H #include "Vector3.h" #include #include namespace octomath { class Quaternion { public: inline Quaternion() { u() = 1; x() = 0; y() = 0; z() = 0; } Quaternion(const Quaternion& other); Quaternion(float u, float x, float y, float z); Quaternion(const Vector3& other); Quaternion(double roll, double pitch, double yaw); Quaternion(const Vector3& axis, double angle); Vector3 toEuler() const; void toRotMatrix(std::vector & rot_matrix_3_3) const; inline const float& operator() (unsigned int i) const { return data[i]; } inline float& operator() (unsigned int i) { return data[i]; } float norm () const; Quaternion normalized () const; Quaternion& normalize (); void operator/= (float x); Quaternion& operator= (const Quaternion& other); bool operator== (const Quaternion& other) const; Quaternion operator* (const Quaternion& other) const; Quaternion operator* (const Vector3 &v) const; friend Quaternion operator* (const Vector3 &v, const Quaternion &q); inline Quaternion inv() const { return Quaternion(u(), -x(), -y(), -z()); } Quaternion& inv_IP(); Vector3 rotate(const Vector3 &v) const; inline float& u() { return data[0]; } inline float& x() { return data[1]; } inline float& y() { return data[2]; } inline float& z() { return data[3]; } inline const float& u() const { return data[0]; } inline const float& x() const { return data[1]; } inline const float& y() const { return data[2]; } inline const float& z() const { return data[3]; } std::istream& read(std::istream &s); std::ostream& write(std::ostream &s) const; std::istream& readBinary(std::istream &s); std::ostream& writeBinary(std::ostream &s) const; protected: float data[4]; }; std::ostream& operator<<(std::ostream& s, const Quaternion& q); } #endif