/usr/include/octomap/math/Quaternion.h is in liboctomap-dev 1.6.8+dfsg-2.1.
This file is owned by root:root, with mode 0o644.
The actual contents of the file can be viewed below.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 | /*
* OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
* http://octomap.github.com/
*
* 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 <iostream>
#include <vector>
namespace octomath {
/*!
* \brief This class represents a Quaternion.
*
* The Unit Quaternion is one possible representation of the
* attitude of an object in tree-dimensional space.
*
* This Quaternion class is implemented according to Diebel,
* James. Representing Attitude: Euler Angle, Unit Quaternions, and
* Rotation Vectors. Stanford University. 2006. - Technical Report.
*/
class Quaternion {
public:
/*!
* \brief Default constructor
*
* Constructs the (1,0,0,0) Unit Quaternion
* representing the identity rotation.
*/
inline Quaternion() { u() = 1; x() = 0; y() = 0; z() = 0; }
/*!
* \brief Copy constructor
*/
Quaternion(const Quaternion& other);
/*!
* \brief Constructor
*
* Constructs a Quaternion from four single
* values
*/
Quaternion(float u, float x, float y, float z);
/*!
* \brief Constructor
*
* @param other a vector containing euler angles
*/
Quaternion(const Vector3& other);
/*!
* \brief Constructor from Euler angles
*
* Constructs a Unit Quaternion from Euler angles / Tait Bryan
* angles (in radians) according to the 1-2-3 convention.
* @param roll phi/roll angle (rotation about x-axis)
* @param pitch theta/pitch angle (rotation about y-axis)
* @param yaw psi/yaw angle (rotation about z-axis)
*/
Quaternion(double roll, double pitch, double yaw);
//! Constructs a Unit Quaternion from a rotation angle and axis.
Quaternion(const Vector3& axis, double angle);
/*!
* \brief Conversion to Euler angles
*
* Converts the attitude represented by this to
* Euler angles (roll, pitch, yaw).
*/
Vector3 toEuler() const;
void toRotMatrix(std::vector <double>& 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;
/*!
* \brief Quaternion multiplication
*
* Standard Quaternion multiplication which is not
* commutative.
* @return this * other
*/
Quaternion operator* (const Quaternion& other) const;
/*!
* \brief Quaternion multiplication with extended vector
*
* @return q * (0, v)
*/
Quaternion operator* (const Vector3 &v) const;
/*!
* \brief Quaternion multiplication with extended vector
*
* @return (0, v) * q
*/
friend Quaternion operator* (const Vector3 &v, const Quaternion &q);
/*!
* \brief Inversion
*
* @return A copy of this Quaterion inverted
*/
inline Quaternion inv() const { return Quaternion(u(), -x(), -y(), -z()); }
/*!
* \brief Inversion
*
* Inverts this Quaternion
* @return a reference to this Quaternion
*/
Quaternion& inv_IP();
/*!
* \brief Rotate a vector
*
* Rotates a vector to the body fixed coordinate
* system according to the attitude represented by
* this Quaternion.
* @param v a vector represented in world coordinates
* @return v represented in body-fixed coordinates
*/
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];
};
//! user friendly output in format (u x y z)
std::ostream& operator<<(std::ostream& s, const Quaternion& q);
}
#endif
|