From 3a21ba23934e500dbe0a29741c88744a72233dfa Mon Sep 17 00:00:00 2001 From: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Date: Tue, 5 Nov 2024 20:40:32 -0500 Subject: [PATCH] Linter Matrix3x3.h Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Matrix3x3.hpp Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter MinMax.h Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter MinMax.hpp Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter QuadWord.h Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter QuadWord.hpp Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Quaternion.h Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Quaternion.hpp Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Scalar.h Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Scalar.hpp Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Transform.h Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Transform.hpp Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Vector3.h Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Linter Vector3.hpp Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> --- tf2/include/tf2/LinearMath/Matrix3x3.h | 4 +- tf2/include/tf2/LinearMath/Matrix3x3.hpp | 200 +++++++++++----------- tf2/include/tf2/LinearMath/MinMax.h | 4 +- tf2/include/tf2/LinearMath/MinMax.hpp | 34 ++-- tf2/include/tf2/LinearMath/QuadWord.h | 4 +- tf2/include/tf2/LinearMath/QuadWord.hpp | 32 ++-- tf2/include/tf2/LinearMath/Quaternion.h | 4 +- tf2/include/tf2/LinearMath/Quaternion.hpp | 132 +++++++------- tf2/include/tf2/LinearMath/Scalar.h | 4 +- tf2/include/tf2/LinearMath/Scalar.hpp | 50 +++--- tf2/include/tf2/LinearMath/Transform.h | 4 +- tf2/include/tf2/LinearMath/Transform.hpp | 62 +++---- tf2/include/tf2/LinearMath/Vector3.h | 4 +- tf2/include/tf2/LinearMath/Vector3.hpp | 168 +++++++++--------- 14 files changed, 353 insertions(+), 353 deletions(-) diff --git a/tf2/include/tf2/LinearMath/Matrix3x3.h b/tf2/include/tf2/LinearMath/Matrix3x3.h index ca97856f..4225988e 100644 --- a/tf2/include/tf2/LinearMath/Matrix3x3.h +++ b/tf2/include/tf2/LinearMath/Matrix3x3.h @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. diff --git a/tf2/include/tf2/LinearMath/Matrix3x3.hpp b/tf2/include/tf2/LinearMath/Matrix3x3.hpp index 33a0e4df..34de1055 100644 --- a/tf2/include/tf2/LinearMath/Matrix3x3.hpp +++ b/tf2/include/tf2/LinearMath/Matrix3x3.hpp @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -13,19 +13,19 @@ subject to the following restrictions: */ -#ifndef TF2_MATRIX3x3_HPP -#define TF2_MATRIX3x3_HPP +#ifndef TF2__LINEARMATH__MATRIX3x3_HPP +#define TF2__LINEARMATH__MATRIX3x3_HPP #include "Vector3.hpp" #include "Quaternion.hpp" -#include "tf2/visibility_control.hpp" +#include "tf2/visibility_control.h" namespace tf2 { -#define Matrix3x3Data Matrix3x3DoubleData +#define Matrix3x3Data Matrix3x3DoubleData /**@brief The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Quaternion, Transform and Vector3. @@ -48,7 +48,7 @@ class Matrix3x3 { /* template Matrix3x3(const tf2Scalar& yaw, const tf2Scalar& pitch, const tf2Scalar& roll) - { + { setEulerYPR(yaw, pitch, roll); } */ @@ -57,9 +57,9 @@ class Matrix3x3 { Matrix3x3(const tf2Scalar& xx, const tf2Scalar& xy, const tf2Scalar& xz, const tf2Scalar& yx, const tf2Scalar& yy, const tf2Scalar& yz, const tf2Scalar& zx, const tf2Scalar& zy, const tf2Scalar& zz) - { - setValue(xx, xy, xz, - yx, yy, yz, + { + setValue(xx, xy, xz, + yx, yy, yz, zx, zy, zz); } /** @brief Copy constructor */ @@ -81,7 +81,7 @@ class Matrix3x3 { } - /** @brief Get a column of the matrix as a vector + /** @brief Get a column of the matrix as a vector * @param i Column number 0 indexed */ TF2SIMD_FORCE_INLINE Vector3 getColumn(int i) const { @@ -89,7 +89,7 @@ class Matrix3x3 { } - /** @brief Get a row of the matrix as a vector + /** @brief Get a row of the matrix as a vector * @param i Row number 0 indexed */ TF2SIMD_FORCE_INLINE const Vector3& getRow(int i) const { @@ -97,29 +97,29 @@ class Matrix3x3 { return m_el[i]; } - /** @brief Get a mutable reference to a row of the matrix as a vector + /** @brief Get a mutable reference to a row of the matrix as a vector * @param i Row number 0 indexed */ TF2SIMD_FORCE_INLINE Vector3& operator[](int i) - { + { tf2FullAssert(0 <= i && i < 3); - return m_el[i]; + return m_el[i]; } - /** @brief Get a const reference to a row of the matrix as a vector + /** @brief Get a const reference to a row of the matrix as a vector * @param i Row number 0 indexed */ TF2SIMD_FORCE_INLINE const Vector3& operator[](int i) const { tf2FullAssert(0 <= i && i < 3); - return m_el[i]; + return m_el[i]; } /** @brief Multiply by the target matrix on the right - * @param m Rotation matrix to be applied + * @param m Rotation matrix to be applied * Equivilant to this = this * m */ TF2_PUBLIC - Matrix3x3& operator*=(const Matrix3x3& m); + Matrix3x3& operator*=(const Matrix3x3& m); - /** @brief Set from a carray of tf2Scalars + /** @brief Set from a carray of tf2Scalars * @param m A pointer to the beginning of an array of 9 tf2Scalars */ TF2_PUBLIC void setFromOpenGLSubMatrix(const tf2Scalar *m) @@ -140,8 +140,8 @@ class Matrix3x3 { * @param zy Bottom Middle * @param zz Bottom Right*/ TF2_PUBLIC - void setValue(const tf2Scalar& xx, const tf2Scalar& xy, const tf2Scalar& xz, - const tf2Scalar& yx, const tf2Scalar& yy, const tf2Scalar& yz, + void setValue(const tf2Scalar& xx, const tf2Scalar& xy, const tf2Scalar& xz, + const tf2Scalar& yx, const tf2Scalar& yy, const tf2Scalar& yz, const tf2Scalar& zx, const tf2Scalar& zy, const tf2Scalar& zz) { m_el[0].setValue(xx,xy,xz); @@ -150,9 +150,9 @@ class Matrix3x3 { } /** @brief Set the matrix from a quaternion - * @param q The Quaternion to match */ + * @param q The Quaternion to match */ TF2_PUBLIC - void setRotation(const Quaternion& q) + void setRotation(const Quaternion& q) { tf2Scalar d = q.length2(); tf2FullAssert(d != tf2Scalar(0.0)); @@ -170,26 +170,26 @@ class Matrix3x3 { * @param eulerZ Yaw aboud Z axis * @param eulerY Pitch around Y axis * @param eulerX Roll about X axis - * + * * These angles are used to produce a rotation matrix. The euler - * angles are applied in ZYX order. I.e a vector is first rotated + * angles are applied in ZYX order. I.e a vector is first rotated * about X then Y and then Z **/ TF2_PUBLIC - void setEulerYPR(tf2Scalar eulerZ, tf2Scalar eulerY,tf2Scalar eulerX) { - tf2Scalar ci ( tf2Cos(eulerX)); - tf2Scalar cj ( tf2Cos(eulerY)); - tf2Scalar ch ( tf2Cos(eulerZ)); - tf2Scalar si ( tf2Sin(eulerX)); - tf2Scalar sj ( tf2Sin(eulerY)); - tf2Scalar sh ( tf2Sin(eulerZ)); - tf2Scalar cc = ci * ch; - tf2Scalar cs = ci * sh; - tf2Scalar sc = si * ch; + void setEulerYPR(tf2Scalar eulerZ, tf2Scalar eulerY,tf2Scalar eulerX) { + tf2Scalar ci ( tf2Cos(eulerX)); + tf2Scalar cj ( tf2Cos(eulerY)); + tf2Scalar ch ( tf2Cos(eulerZ)); + tf2Scalar si ( tf2Sin(eulerX)); + tf2Scalar sj ( tf2Sin(eulerY)); + tf2Scalar sh ( tf2Sin(eulerZ)); + tf2Scalar cc = ci * ch; + tf2Scalar cs = ci * sh; + tf2Scalar sc = si * ch; tf2Scalar ss = si * sh; setValue(cj * ch, sj * sc - cs, sj * cc + ss, - cj * sh, sj * ss + cc, sj * cs - sc, + cj * sh, sj * ss + cc, sj * cs - sc, -sj, cj * si, cj * ci); } @@ -197,51 +197,51 @@ class Matrix3x3 { * @param roll Roll about X axis * @param pitch Pitch around Y axis * @param yaw Yaw aboud Z axis - * + * **/ TF2_PUBLIC - void setRPY(tf2Scalar roll, tf2Scalar pitch,tf2Scalar yaw) { + void setRPY(tf2Scalar roll, tf2Scalar pitch,tf2Scalar yaw) { setEulerYPR(yaw, pitch, roll); } /**@brief Set the matrix to the identity */ TF2_PUBLIC void setIdentity() - { - setValue(tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0), - tf2Scalar(0.0), tf2Scalar(1.0), tf2Scalar(0.0), - tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(1.0)); + { + setValue(tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0), + tf2Scalar(0.0), tf2Scalar(1.0), tf2Scalar(0.0), + tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(1.0)); } TF2_PUBLIC static const Matrix3x3& getIdentity() { - static const Matrix3x3 identityMatrix(tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0), - tf2Scalar(0.0), tf2Scalar(1.0), tf2Scalar(0.0), + static const Matrix3x3 identityMatrix(tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0), + tf2Scalar(0.0), tf2Scalar(1.0), tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(1.0)); return identityMatrix; } - /**@brief Fill the values of the matrix into a 9 element array + /**@brief Fill the values of the matrix into a 9 element array * @param m The array to be filled */ TF2_PUBLIC - void getOpenGLSubMatrix(tf2Scalar *m) const + void getOpenGLSubMatrix(tf2Scalar *m) const { - m[0] = tf2Scalar(m_el[0].x()); + m[0] = tf2Scalar(m_el[0].x()); m[1] = tf2Scalar(m_el[1].x()); m[2] = tf2Scalar(m_el[2].x()); - m[3] = tf2Scalar(0.0); + m[3] = tf2Scalar(0.0); m[4] = tf2Scalar(m_el[0].y()); m[5] = tf2Scalar(m_el[1].y()); m[6] = tf2Scalar(m_el[2].y()); - m[7] = tf2Scalar(0.0); - m[8] = tf2Scalar(m_el[0].z()); + m[7] = tf2Scalar(0.0); + m[8] = tf2Scalar(m_el[0].z()); m[9] = tf2Scalar(m_el[1].z()); m[10] = tf2Scalar(m_el[2].z()); - m[11] = tf2Scalar(0.0); + m[11] = tf2Scalar(0.0); } - /**@brief Get the matrix represented as a quaternion + /**@brief Get the matrix represented as a quaternion * @param q The quaternion which will be set */ TF2_PUBLIC void getRotation(Quaternion& q) const @@ -249,7 +249,7 @@ class Matrix3x3 { tf2Scalar trace = m_el[0].x() + m_el[1].y() + m_el[2].z(); tf2Scalar temp[4]; - if (trace > tf2Scalar(0.0)) + if (trace > tf2Scalar(0.0)) { tf2Scalar s = tf2Sqrt(trace + tf2Scalar(1.0)); temp[3]=(s * tf2Scalar(0.5)); @@ -258,13 +258,13 @@ class Matrix3x3 { temp[0]=((m_el[2].y() - m_el[1].z()) * s); temp[1]=((m_el[0].z() - m_el[2].x()) * s); temp[2]=((m_el[1].x() - m_el[0].y()) * s); - } - else + } + else { - int i = m_el[0].x() < m_el[1].y() ? + int i = m_el[0].x() < m_el[1].y() ? (m_el[1].y() < m_el[2].z() ? 2 : 1) : - (m_el[0].x() < m_el[2].z() ? 2 : 0); - int j = (i + 1) % 3; + (m_el[0].x() < m_el[2].z() ? 2 : 0); + int j = (i + 1) % 3; int k = (i + 2) % 3; tf2Scalar s = tf2Sqrt(m_el[i][i] - m_el[j][j] - m_el[k][k] + tf2Scalar(1.0)); @@ -281,7 +281,7 @@ class Matrix3x3 { /**@brief Get the matrix represented as euler angles around YXZ, roundtrip with setEulerYPR * @param yaw Yaw around Z axis * @param pitch Pitch around Y axis - * @param roll around X axis */ + * @param roll around X axis */ TF2_PUBLIC void getEulerYPR(tf2Scalar& yaw, tf2Scalar& pitch, tf2Scalar& roll, unsigned int solution_number = 1) const { @@ -302,7 +302,7 @@ class Matrix3x3 { { euler_out.yaw = 0; euler_out2.yaw = 0; - + // From difference of angles formula tf2Scalar delta = tf2Atan2(m_el[2].y(),m_el[2].z()); if (m_el[2].x() < 0) //gimbal locked down @@ -325,43 +325,43 @@ class Matrix3x3 { euler_out.pitch = - tf2Asin(m_el[2].x()); euler_out2.pitch = TF2SIMD_PI - euler_out.pitch; - euler_out.roll = tf2Atan2(m_el[2].y()/tf2Cos(euler_out.pitch), + euler_out.roll = tf2Atan2(m_el[2].y()/tf2Cos(euler_out.pitch), m_el[2].z()/tf2Cos(euler_out.pitch)); - euler_out2.roll = tf2Atan2(m_el[2].y()/tf2Cos(euler_out2.pitch), + euler_out2.roll = tf2Atan2(m_el[2].y()/tf2Cos(euler_out2.pitch), m_el[2].z()/tf2Cos(euler_out2.pitch)); - euler_out.yaw = tf2Atan2(m_el[1].x()/tf2Cos(euler_out.pitch), + euler_out.yaw = tf2Atan2(m_el[1].x()/tf2Cos(euler_out.pitch), m_el[0].x()/tf2Cos(euler_out.pitch)); - euler_out2.yaw = tf2Atan2(m_el[1].x()/tf2Cos(euler_out2.pitch), + euler_out2.yaw = tf2Atan2(m_el[1].x()/tf2Cos(euler_out2.pitch), m_el[0].x()/tf2Cos(euler_out2.pitch)); } if (solution_number == 1) - { - yaw = euler_out.yaw; + { + yaw = euler_out.yaw; pitch = euler_out.pitch; roll = euler_out.roll; } else - { - yaw = euler_out2.yaw; + { + yaw = euler_out2.yaw; pitch = euler_out2.pitch; roll = euler_out2.roll; } } /**@brief Get the matrix represented as roll pitch and yaw about fixed axes XYZ - * @param roll around X axis + * @param roll around X axis * @param pitch Pitch around Y axis * @param yaw Yaw around Z axis - * @param solution_number Which solution of two possible solutions ( 1 or 2) are possible values*/ + * @param solution_number Which solution of two possible solutions ( 1 or 2) are possible values*/ TF2_PUBLIC void getRPY(tf2Scalar& roll, tf2Scalar& pitch, tf2Scalar& yaw, unsigned int solution_number = 1) const { getEulerYPR(yaw, pitch, roll, solution_number); } - /**@brief Create a scaled copy of the matrix + /**@brief Create a scaled copy of the matrix * @param s Scaling vector The elements of the vector will scale each column */ TF2_PUBLIC @@ -386,22 +386,22 @@ class Matrix3x3 { Matrix3x3 transpose() const; /**@brief Return the inverse of the matrix */ TF2_PUBLIC - Matrix3x3 inverse() const; + Matrix3x3 inverse() const; TF2_PUBLIC Matrix3x3 transposeTimes(const Matrix3x3& m) const; TF2_PUBLIC Matrix3x3 timesTranspose(const Matrix3x3& m) const; - TF2SIMD_FORCE_INLINE tf2Scalar tdotx(const Vector3& v) const + TF2SIMD_FORCE_INLINE tf2Scalar tdotx(const Vector3& v) const { return m_el[0].x() * v.x() + m_el[1].x() * v.y() + m_el[2].x() * v.z(); } - TF2SIMD_FORCE_INLINE tf2Scalar tdoty(const Vector3& v) const + TF2SIMD_FORCE_INLINE tf2Scalar tdoty(const Vector3& v) const { return m_el[0].y() * v.x() + m_el[1].y() * v.y() + m_el[2].y() * v.z(); } - TF2SIMD_FORCE_INLINE tf2Scalar tdotz(const Vector3& v) const + TF2SIMD_FORCE_INLINE tf2Scalar tdotz(const Vector3& v) const { return m_el[0].z() * v.x() + m_el[1].z() * v.y() + m_el[2].z() * v.z(); } @@ -409,12 +409,12 @@ class Matrix3x3 { /**@brief diagonalizes this matrix by the Jacobi method. * @param rot stores the rotation from the coordinate system in which the matrix is diagonal to the original - * coordinate system, i.e., old_this = rot * new_this * rot^T. + * coordinate system, i.e., old_this = rot * new_this * rot^T. * @param threshold See iteration - * @param iteration The iteration stops when all off-diagonal elements are less than the threshold multiplied - * by the sum of the absolute values of the diagonal, or when maxSteps have been executed. - * - * Note that this matrix is assumed to be symmetric. + * @param iteration The iteration stops when all off-diagonal elements are less than the threshold multiplied + * by the sum of the absolute values of the diagonal, or when maxSteps have been executed. + * + * Note that this matrix is assumed to be symmetric. */ TF2_PUBLIC void diagonalize(Matrix3x3& rot, tf2Scalar threshold, int maxSteps) @@ -453,7 +453,7 @@ class Matrix3x3 { step = 1; } - // compute Jacobi rotation J which leads to a zero for element [p][q] + // compute Jacobi rotation J which leads to a zero for element [p][q] tf2Scalar mpq = m_el[p][q]; tf2Scalar theta = (m_el[q][q] - m_el[p][p]) / (2 * mpq); tf2Scalar theta2 = theta * theta; @@ -498,7 +498,7 @@ class Matrix3x3 { - /**@brief Calculate the matrix cofactor + /**@brief Calculate the matrix cofactor * @param r1 The first row to use for calculating the cofactor * @param c1 The first column to use for calculating the cofactor * @param r1 The second row to use for calculating the cofactor @@ -506,7 +506,7 @@ class Matrix3x3 { * See http://en.wikipedia.org/wiki/Cofactor_(linear_algebra) for more details */ TF2_PUBLIC - tf2Scalar cofac(int r1, int c1, int r2, int c2) const + tf2Scalar cofac(int r1, int c1, int r2, int c2) const { return m_el[r1][c1] * m_el[r2][c2] - m_el[r1][c2] * m_el[r2][c1]; } @@ -529,7 +529,7 @@ class Matrix3x3 { }; -TF2SIMD_FORCE_INLINE Matrix3x3& +TF2SIMD_FORCE_INLINE Matrix3x3& Matrix3x3::operator*=(const Matrix3x3& m) { setValue(m.tdotx(m_el[0]), m.tdoty(m_el[0]), m.tdotz(m_el[0]), @@ -538,14 +538,14 @@ Matrix3x3::operator*=(const Matrix3x3& m) return *this; } -TF2SIMD_FORCE_INLINE tf2Scalar +TF2SIMD_FORCE_INLINE tf2Scalar Matrix3x3::determinant() const -{ +{ return tf2Triple((*this)[0], (*this)[1], (*this)[2]); } -TF2SIMD_FORCE_INLINE Matrix3x3 +TF2SIMD_FORCE_INLINE Matrix3x3 Matrix3x3::absolute() const { return Matrix3x3( @@ -554,23 +554,23 @@ Matrix3x3::absolute() const tf2Fabs(m_el[2].x()), tf2Fabs(m_el[2].y()), tf2Fabs(m_el[2].z())); } -TF2SIMD_FORCE_INLINE Matrix3x3 -Matrix3x3::transpose() const +TF2SIMD_FORCE_INLINE Matrix3x3 +Matrix3x3::transpose() const { return Matrix3x3(m_el[0].x(), m_el[1].x(), m_el[2].x(), m_el[0].y(), m_el[1].y(), m_el[2].y(), m_el[0].z(), m_el[1].z(), m_el[2].z()); } -TF2SIMD_FORCE_INLINE Matrix3x3 -Matrix3x3::adjoint() const +TF2SIMD_FORCE_INLINE Matrix3x3 +Matrix3x3::adjoint() const { return Matrix3x3(cofac(1, 1, 2, 2), cofac(0, 2, 2, 1), cofac(0, 1, 1, 2), cofac(1, 2, 2, 0), cofac(0, 0, 2, 2), cofac(0, 2, 1, 0), cofac(1, 0, 2, 1), cofac(0, 1, 2, 0), cofac(0, 0, 1, 1)); } -TF2SIMD_FORCE_INLINE Matrix3x3 +TF2SIMD_FORCE_INLINE Matrix3x3 Matrix3x3::inverse() const { Vector3 co(cofac(1, 1, 2, 2), cofac(1, 2, 2, 0), cofac(1, 0, 2, 1)); @@ -582,7 +582,7 @@ Matrix3x3::inverse() const co.z() * s, cofac(0, 1, 2, 0) * s, cofac(0, 0, 1, 1) * s); } -TF2SIMD_FORCE_INLINE Matrix3x3 +TF2SIMD_FORCE_INLINE Matrix3x3 Matrix3x3::transposeTimes(const Matrix3x3& m) const { return Matrix3x3( @@ -597,7 +597,7 @@ Matrix3x3::transposeTimes(const Matrix3x3& m) const m_el[0].z() * m[0].z() + m_el[1].z() * m[1].z() + m_el[2].z() * m[2].z()); } -TF2SIMD_FORCE_INLINE Matrix3x3 +TF2SIMD_FORCE_INLINE Matrix3x3 Matrix3x3::timesTranspose(const Matrix3x3& m) const { return Matrix3x3( @@ -607,8 +607,8 @@ Matrix3x3::timesTranspose(const Matrix3x3& m) const } -TF2SIMD_FORCE_INLINE Vector3 -operator*(const Matrix3x3& m, const Vector3& v) +TF2SIMD_FORCE_INLINE Vector3 +operator*(const Matrix3x3& m, const Vector3& v) { return Vector3(m[0].dot(v), m[1].dot(v), m[2].dot(v)); } @@ -620,7 +620,7 @@ operator*(const Vector3& v, const Matrix3x3& m) return Vector3(m.tdotx(v), m.tdoty(v), m.tdotz(v)); } -TF2SIMD_FORCE_INLINE Matrix3x3 +TF2SIMD_FORCE_INLINE Matrix3x3 operator*(const Matrix3x3& m1, const Matrix3x3& m2) { return Matrix3x3( @@ -666,7 +666,7 @@ struct Matrix3x3DoubleData }; - + TF2SIMD_FORCE_INLINE void Matrix3x3::serialize(struct Matrix3x3Data& dataOut) const { @@ -700,4 +700,4 @@ TF2SIMD_FORCE_INLINE void Matrix3x3::deSerializeDouble(const struct Matrix3x3Dou } } -#endif //TF2_MATRIX3x3_HPP +#endif // TF2__LINEARMATH__MATRIX3x3_HPP diff --git a/tf2/include/tf2/LinearMath/MinMax.h b/tf2/include/tf2/LinearMath/MinMax.h index 0544b365..be6d3caa 100644 --- a/tf2/include/tf2/LinearMath/MinMax.h +++ b/tf2/include/tf2/LinearMath/MinMax.h @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. diff --git a/tf2/include/tf2/LinearMath/MinMax.hpp b/tf2/include/tf2/LinearMath/MinMax.hpp index d74de1fb..6c3746a8 100644 --- a/tf2/include/tf2/LinearMath/MinMax.hpp +++ b/tf2/include/tf2/LinearMath/MinMax.hpp @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -14,58 +14,58 @@ subject to the following restrictions: -#ifndef GEN_MINMAX_HPP -#define GEN_MINMAX_HPP +#ifndef TF2__LINEARMATH__MINMAX_HPP_ +#define TF2__LINEARMATH__MINMAX_HPP_ #include "Scalar.hpp" template -TF2SIMD_FORCE_INLINE const T& tf2Min(const T& a, const T& b) +TF2SIMD_FORCE_INLINE const T& tf2Min(const T& a, const T& b) { return a < b ? a : b ; } template -TF2SIMD_FORCE_INLINE const T& tf2Max(const T& a, const T& b) +TF2SIMD_FORCE_INLINE const T& tf2Max(const T& a, const T& b) { return a > b ? a : b; } template -TF2SIMD_FORCE_INLINE const T& GEN_clamped(const T& a, const T& lb, const T& ub) +TF2SIMD_FORCE_INLINE const T& GEN_clamped(const T& a, const T& lb, const T& ub) { - return a < lb ? lb : (ub < a ? ub : a); + return a < lb ? lb : (ub < a ? ub : a); } template -TF2SIMD_FORCE_INLINE void tf2SetMin(T& a, const T& b) +TF2SIMD_FORCE_INLINE void tf2SetMin(T& a, const T& b) { - if (b < a) + if (b < a) { a = b; } } template -TF2SIMD_FORCE_INLINE void tf2SetMax(T& a, const T& b) +TF2SIMD_FORCE_INLINE void tf2SetMax(T& a, const T& b) { - if (a < b) + if (a < b) { a = b; } } template -TF2SIMD_FORCE_INLINE void GEN_clamp(T& a, const T& lb, const T& ub) +TF2SIMD_FORCE_INLINE void GEN_clamp(T& a, const T& lb, const T& ub) { - if (a < lb) + if (a < lb) { - a = lb; + a = lb; } - else if (ub < a) + else if (ub < a) { a = ub; } } -#endif +#endif // TF2__LINEARMATH__MINMAX_HPP_ diff --git a/tf2/include/tf2/LinearMath/QuadWord.h b/tf2/include/tf2/LinearMath/QuadWord.h index 7b94f9f6..69d06627 100644 --- a/tf2/include/tf2/LinearMath/QuadWord.h +++ b/tf2/include/tf2/LinearMath/QuadWord.h @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. diff --git a/tf2/include/tf2/LinearMath/QuadWord.hpp b/tf2/include/tf2/LinearMath/QuadWord.hpp index 423f9d65..04153d4c 100644 --- a/tf2/include/tf2/LinearMath/QuadWord.hpp +++ b/tf2/include/tf2/LinearMath/QuadWord.hpp @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -13,8 +13,8 @@ subject to the following restrictions: */ -#ifndef TF2SIMD_QUADWORD_HPP -#define TF2SIMD_QUADWORD_HPP +#ifndef TF2__LINEARMATH__QUADWORD_HPP +#define TF2__LINEARMATH__QUADWORD_HPP #include "Scalar.hpp" #include "MinMax.hpp" @@ -27,7 +27,7 @@ subject to the following restrictions: namespace tf2 { -/**@brief The QuadWord class is base class for Vector3 and Quaternion. +/**@brief The QuadWord class is base class for Vector3 and Quaternion. * Some issues under PS3 Linux with IBM 2.1 SDK, gcc compiler prevent from using aligned quadword. */ #ifndef USE_LIBSPE2 @@ -55,7 +55,7 @@ class QuadWord #endif //__CELLOS_LV2__ __SPU__ public: - + /**@brief Return the x value */ TF2SIMD_FORCE_INLINE const tf2Scalar& getX() const { return m_floats[0]; } @@ -80,7 +80,7 @@ class QuadWord /**@brief Return the w value */ TF2SIMD_FORCE_INLINE const tf2Scalar& w() const { return m_floats[3]; } - //TF2SIMD_FORCE_INLINE tf2Scalar& operator[](int i) { return (&m_floats[0])[i]; } + //TF2SIMD_FORCE_INLINE tf2Scalar& operator[](int i) { return (&m_floats[0])[i]; } //TF2SIMD_FORCE_INLINE const tf2Scalar& operator[](int i) const { return (&m_floats[0])[i]; } ///operator tf2Scalar*() replaces operator[], using implicit conversion. We added operator != and operator == to avoid pointer comparisons. TF2SIMD_FORCE_INLINE operator tf2Scalar *() { return &m_floats[0]; } @@ -96,7 +96,7 @@ class QuadWord return !(*this == other); } - /**@brief Set x,y,z and zero w + /**@brief Set x,y,z and zero w * @param x Value of x * @param y Value of y * @param z Value of z @@ -109,14 +109,14 @@ class QuadWord m_floats[3] = 0.f; } -/* void getValue(tf2Scalar *m) const +/* void getValue(tf2Scalar *m) const { m[0] = m_floats[0]; m[1] = m_floats[1]; m[2] = m_floats[2]; } */ -/**@brief Set the values +/**@brief Set the values * @param x Value of x * @param y Value of y * @param z Value of z @@ -134,13 +134,13 @@ class QuadWord // :m_floats[0](tf2Scalar(0.)),m_floats[1](tf2Scalar(0.)),m_floats[2](tf2Scalar(0.)),m_floats[3](tf2Scalar(0.)) { } - + /**@brief Three argument constructor (zeros w) * @param x Value of x * @param y Value of y * @param z Value of z */ - TF2SIMD_FORCE_INLINE QuadWord(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z) + TF2SIMD_FORCE_INLINE QuadWord(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z) { m_floats[0] = x, m_floats[1] = y, m_floats[2] = z, m_floats[3] = 0.0f; } @@ -151,13 +151,13 @@ class QuadWord * @param z Value of z * @param w Value of w */ - TF2SIMD_FORCE_INLINE QuadWord(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w) + TF2SIMD_FORCE_INLINE QuadWord(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w) { m_floats[0] = x, m_floats[1] = y, m_floats[2] = z, m_floats[3] = w; } /**@brief Set each element to the max of the current values and the values of another QuadWord - * @param other The other QuadWord to compare with + * @param other The other QuadWord to compare with */ TF2SIMD_FORCE_INLINE void setMax(const QuadWord& other) { @@ -167,7 +167,7 @@ class QuadWord tf2SetMax(m_floats[3], other.m_floats[3]); } /**@brief Set each element to the min of the current values and the values of another QuadWord - * @param other The other QuadWord to compare with + * @param other The other QuadWord to compare with */ TF2SIMD_FORCE_INLINE void setMin(const QuadWord& other) { @@ -182,4 +182,4 @@ class QuadWord }; } -#endif //TF2SIMD_QUADWORD_HPP +#endif // TF2__LINEARMATH__QUADWORD_HPP diff --git a/tf2/include/tf2/LinearMath/Quaternion.h b/tf2/include/tf2/LinearMath/Quaternion.h index efa8bbd5..864cd335 100644 --- a/tf2/include/tf2/LinearMath/Quaternion.h +++ b/tf2/include/tf2/LinearMath/Quaternion.h @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. diff --git a/tf2/include/tf2/LinearMath/Quaternion.hpp b/tf2/include/tf2/LinearMath/Quaternion.hpp index 94e14538..12aaa469 100644 --- a/tf2/include/tf2/LinearMath/Quaternion.hpp +++ b/tf2/include/tf2/LinearMath/Quaternion.hpp @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -14,8 +14,8 @@ subject to the following restrictions: -#ifndef TF2_QUATERNION_HPP_ -#define TF2_QUATERNION_HPP_ +#ifndef TF2__LINEARMATH__QUATERNION_HPP_ +#define TF2__LINEARMATH__QUATERNION_HPP_ #include "Vector3.hpp" @@ -36,18 +36,18 @@ class Quaternion : public QuadWord { // explicit Quaternion(const tf2Scalar *v) : Tuple4(v) {} /**@brief Constructor from scalars */ TF2_PUBLIC - Quaternion(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z, const tf2Scalar& w) - : QuadWord(x, y, z, w) + Quaternion(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z, const tf2Scalar& w) + : QuadWord(x, y, z, w) {} /**@brief Axis angle Constructor * @param axis The axis which the rotation is around * @param angle The magnitude of the rotation around the angle (Radians) */ TF2_PUBLIC - Quaternion(const Vector3& axis, const tf2Scalar& angle) - { - setRotation(axis, angle); + Quaternion(const Vector3& axis, const tf2Scalar& angle) + { + setRotation(axis, angle); } - /**@brief Set the rotation using axis angle notation + /**@brief Set the rotation using axis angle notation * @param axis The axis around which to rotate * @param angle The magnitude of the rotation in Radians */ TF2_PUBLIC @@ -56,7 +56,7 @@ class Quaternion : public QuadWord { tf2Scalar d = axis.length(); tf2Assert(d != tf2Scalar(0.0)); tf2Scalar s = tf2Sin(angle * tf2Scalar(0.5)) / d; - setValue(axis.x() * s, axis.y() * s, axis.z() * s, + setValue(axis.x() * s, axis.y() * s, axis.z() * s, tf2Cos(angle * tf2Scalar(0.5))); } /**@brief Set the quaternion using Euler angles @@ -66,9 +66,9 @@ class Quaternion : public QuadWord { TF2_PUBLIC void setEuler(const tf2Scalar& yaw, const tf2Scalar& pitch, const tf2Scalar& roll) { - tf2Scalar halfYaw = tf2Scalar(yaw) * tf2Scalar(0.5); - tf2Scalar halfPitch = tf2Scalar(pitch) * tf2Scalar(0.5); - tf2Scalar halfRoll = tf2Scalar(roll) * tf2Scalar(0.5); + tf2Scalar halfYaw = tf2Scalar(yaw) * tf2Scalar(0.5); + tf2Scalar halfPitch = tf2Scalar(pitch) * tf2Scalar(0.5); + tf2Scalar halfRoll = tf2Scalar(roll) * tf2Scalar(0.5); tf2Scalar cosYaw = tf2Cos(halfYaw); tf2Scalar sinYaw = tf2Sin(halfYaw); tf2Scalar cosPitch = tf2Cos(halfPitch); @@ -81,15 +81,15 @@ class Quaternion : public QuadWord { cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw); } /**@brief Set the quaternion using fixed axis RPY - * @param roll Angle around X + * @param roll Angle around X * @param pitch Angle around Y * @param yaw Angle around Z*/ TF2_PUBLIC void setRPY(const tf2Scalar& roll, const tf2Scalar& pitch, const tf2Scalar& yaw) { - tf2Scalar halfYaw = tf2Scalar(yaw) * tf2Scalar(0.5); - tf2Scalar halfPitch = tf2Scalar(pitch) * tf2Scalar(0.5); - tf2Scalar halfRoll = tf2Scalar(roll) * tf2Scalar(0.5); + tf2Scalar halfYaw = tf2Scalar(yaw) * tf2Scalar(0.5); + tf2Scalar halfPitch = tf2Scalar(pitch) * tf2Scalar(0.5); + tf2Scalar halfRoll = tf2Scalar(roll) * tf2Scalar(0.5); tf2Scalar cosYaw = tf2Cos(halfYaw); tf2Scalar sinYaw = tf2Sin(halfYaw); tf2Scalar cosPitch = tf2Cos(halfPitch); @@ -112,7 +112,7 @@ class Quaternion : public QuadWord { /**@brief Sutf2ract out a quaternion * @param q The quaternion to sutf2ract from this one */ TF2_PUBLIC - Quaternion& operator-=(const Quaternion& q) + Quaternion& operator-=(const Quaternion& q) { m_floats[0] -= q.x(); m_floats[1] -= q.y(); m_floats[2] -= q.z(); m_floats[3] -= q.m_floats[3]; return *this; @@ -128,7 +128,7 @@ class Quaternion : public QuadWord { } /**@brief Multiply this quaternion by q on the right - * @param q The other quaternion + * @param q The other quaternion * Equivilant to this = this * q */ TF2_PUBLIC Quaternion& operator*=(const Quaternion& q) @@ -161,10 +161,10 @@ class Quaternion : public QuadWord { return tf2Sqrt(length2()); } - /**@brief Normalize the quaternion + /**@brief Normalize the quaternion * Such that x^2 + y^2 + z^2 +w^2 = 1 */ TF2_PUBLIC - Quaternion& normalize() + Quaternion& normalize() { return *this /= length(); } @@ -190,7 +190,7 @@ class Quaternion : public QuadWord { /**@brief Inversely scale this quaternion * @param s The scale factor */ TF2_PUBLIC - Quaternion& operator/=(const tf2Scalar& s) + Quaternion& operator/=(const tf2Scalar& s) { tf2Assert(s != tf2Scalar(0.0)); return *this *= tf2Scalar(1.0) / s; @@ -198,14 +198,14 @@ class Quaternion : public QuadWord { /**@brief Return a normalized version of this quaternion */ TF2_PUBLIC - Quaternion normalized() const + Quaternion normalized() const { return *this / length(); - } - /**@brief Return the ***half*** angle between this quaternion and the other + } + /**@brief Return the ***half*** angle between this quaternion and the other * @param q The other quaternion */ TF2_PUBLIC - tf2Scalar angle(const Quaternion& q) const + tf2Scalar angle(const Quaternion& q) const { tf2Scalar s = tf2Sqrt(length2() * q.length2()); tf2Assert(s != tf2Scalar(0.0)); @@ -214,18 +214,18 @@ class Quaternion : public QuadWord { /**@brief Return the angle between this quaternion and the other along the shortest path * @param q The other quaternion */ TF2_PUBLIC - tf2Scalar angleShortestPath(const Quaternion& q) const + tf2Scalar angleShortestPath(const Quaternion& q) const { tf2Scalar s = tf2Sqrt(length2() * q.length2()); tf2Assert(s != tf2Scalar(0.0)); if (dot(q) < 0) // Take care of long angle case see http://en.wikipedia.org/wiki/Slerp return tf2Acos(dot(-q) / s) * tf2Scalar(2.0); - else + else return tf2Acos(dot(q) / s) * tf2Scalar(2.0); } /**@brief Return the angle [0, 2Pi] of rotation represented by this quaternion */ TF2_PUBLIC - tf2Scalar getAngle() const + tf2Scalar getAngle() const { tf2Scalar s = tf2Scalar(2.) * tf2Acos(m_floats[3]); return s; @@ -233,7 +233,7 @@ class Quaternion : public QuadWord { /**@brief Return the angle [0, Pi] of rotation represented by this quaternion along the shortest path */ TF2_PUBLIC - tf2Scalar getAngleShortestPath() const + tf2Scalar getAngleShortestPath() const { tf2Scalar s; if (m_floats[3] >= 0) @@ -262,7 +262,7 @@ class Quaternion : public QuadWord { return Quaternion(-m_floats[0], -m_floats[1], -m_floats[2], m_floats[3]); } - /**@brief Return the sum of this quaternion and the other + /**@brief Return the sum of this quaternion and the other * @param q2 The other quaternion */ TF2SIMD_FORCE_INLINE Quaternion operator+(const Quaternion& q2) const @@ -271,7 +271,7 @@ class Quaternion : public QuadWord { return Quaternion(q1.x() + q2.x(), q1.y() + q2.y(), q1.z() + q2.z(), q1.m_floats[3] + q2.m_floats[3]); } - /**@brief Return the difference between this quaternion and the other + /**@brief Return the difference between this quaternion and the other * @param q2 The other quaternion */ TF2SIMD_FORCE_INLINE Quaternion operator-(const Quaternion& q2) const @@ -280,7 +280,7 @@ class Quaternion : public QuadWord { return Quaternion(q1.x() - q2.x(), q1.y() - q2.y(), q1.z() - q2.z(), q1.m_floats[3] - q2.m_floats[3]); } - /**@brief Return the negative of this quaternion + /**@brief Return the negative of this quaternion * This simply negates each element */ TF2SIMD_FORCE_INLINE Quaternion operator-() const { @@ -288,7 +288,7 @@ class Quaternion : public QuadWord { return Quaternion( - q2.x(), - q2.y(), - q2.z(), - q2.m_floats[3]); } /**@todo document this and it's use */ - TF2SIMD_FORCE_INLINE Quaternion farthest( const Quaternion& qd) const + TF2SIMD_FORCE_INLINE Quaternion farthest( const Quaternion& qd) const { Quaternion diff,sum; diff = *this - qd; @@ -299,7 +299,7 @@ class Quaternion : public QuadWord { } /**@todo document this and it's use */ - TF2SIMD_FORCE_INLINE Quaternion nearest( const Quaternion& qd) const + TF2SIMD_FORCE_INLINE Quaternion nearest( const Quaternion& qd) const { Quaternion diff,sum; diff = *this - qd; @@ -311,7 +311,7 @@ class Quaternion : public QuadWord { /**@brief Return the quaternion which is the result of Spherical Linear Interpolation between this and the other quaternion - * @param q The other quaternion to interpolate with + * @param q The other quaternion to interpolate with * @param t The ratio between this and q to interpolate. If t = 0 the result is this, if t=1 the result is q. * Slerp interpolates assuming constant velocity. */ TF2_PUBLIC @@ -322,7 +322,7 @@ class Quaternion : public QuadWord { { tf2Scalar d = tf2Scalar(1.0) / tf2Sin(theta); tf2Scalar s0 = tf2Sin((tf2Scalar(1.0) - t) * theta); - tf2Scalar s1 = tf2Sin(t * theta); + tf2Scalar s1 = tf2Sin(t * theta); if (dot(q) < 0) // Take care of long angle case see http://en.wikipedia.org/wiki/Slerp return Quaternion((m_floats[0] * s0 + -q.x() * s1) * d, (m_floats[1] * s0 + -q.y() * s1) * d, @@ -333,7 +333,7 @@ class Quaternion : public QuadWord { (m_floats[1] * s0 + q.y() * s1) * d, (m_floats[2] * s0 + q.z() * s1) * d, (m_floats[3] * s0 + q.m_floats[3] * s1) * d); - + } else { @@ -350,7 +350,7 @@ class Quaternion : public QuadWord { TF2SIMD_FORCE_INLINE const tf2Scalar& getW() const { return m_floats[3]; } - + }; @@ -369,7 +369,7 @@ operator*(const Quaternion& q1, const Quaternion& q2) { return Quaternion(q1.w() * q2.x() + q1.x() * q2.w() + q1.y() * q2.z() - q1.z() * q2.y(), q1.w() * q2.y() + q1.y() * q2.w() + q1.z() * q2.x() - q1.x() * q2.z(), q1.w() * q2.z() + q1.z() * q2.w() + q1.x() * q2.y() - q1.y() * q2.x(), - q1.w() * q2.w() - q1.x() * q2.x() - q1.y() * q2.y() - q1.z() * q2.z()); + q1.w() * q2.w() - q1.x() * q2.x() - q1.y() * q2.y() - q1.z() * q2.z()); } TF2SIMD_FORCE_INLINE Quaternion @@ -378,7 +378,7 @@ operator*(const Quaternion& q, const Vector3& w) return Quaternion( q.w() * w.x() + q.y() * w.z() - q.z() * w.y(), q.w() * w.y() + q.z() * w.x() - q.x() * w.z(), q.w() * w.z() + q.x() * w.y() - q.y() * w.x(), - -q.x() * w.x() - q.y() * w.y() - q.z() * w.z()); + -q.x() * w.x() - q.y() * w.y() - q.z() * w.z()); } TF2SIMD_FORCE_INLINE Quaternion @@ -387,65 +387,65 @@ operator*(const Vector3& w, const Quaternion& q) return Quaternion( w.x() * q.w() + w.y() * q.z() - w.z() * q.y(), w.y() * q.w() + w.z() * q.x() - w.x() * q.z(), w.z() * q.w() + w.x() * q.y() - w.y() * q.x(), - -w.x() * q.x() - w.y() * q.y() - w.z() * q.z()); + -w.x() * q.x() - w.y() * q.y() - w.z() * q.z()); } /**@brief Calculate the dot product between two quaternions */ -TF2SIMD_FORCE_INLINE tf2Scalar -dot(const Quaternion& q1, const Quaternion& q2) -{ - return q1.dot(q2); +TF2SIMD_FORCE_INLINE tf2Scalar +dot(const Quaternion& q1, const Quaternion& q2) +{ + return q1.dot(q2); } /**@brief Return the length of a quaternion */ TF2SIMD_FORCE_INLINE tf2Scalar -length(const Quaternion& q) -{ - return q.length(); +length(const Quaternion& q) +{ + return q.length(); } /**@brief Return the ***half*** angle between two quaternions*/ TF2SIMD_FORCE_INLINE tf2Scalar -angle(const Quaternion& q1, const Quaternion& q2) -{ - return q1.angle(q2); +angle(const Quaternion& q1, const Quaternion& q2) +{ + return q1.angle(q2); } /**@brief Return the shortest angle between two quaternions*/ TF2SIMD_FORCE_INLINE tf2Scalar -angleShortestPath(const Quaternion& q1, const Quaternion& q2) -{ - return q1.angleShortestPath(q2); +angleShortestPath(const Quaternion& q1, const Quaternion& q2) +{ + return q1.angleShortestPath(q2); } /**@brief Return the inverse of a quaternion*/ TF2SIMD_FORCE_INLINE Quaternion -inverse(const Quaternion& q) +inverse(const Quaternion& q) { return q.inverse(); } -/**@brief Return the result of spherical linear interpolation betwen two quaternions +/**@brief Return the result of spherical linear interpolation betwen two quaternions * @param q1 The first quaternion - * @param q2 The second quaternion - * @param t The ration between q1 and q2. t = 0 return q1, t=1 returns q2 + * @param q2 The second quaternion + * @param t The ration between q1 and q2. t = 0 return q1, t=1 returns q2 * Slerp assumes constant velocity between positions. */ TF2SIMD_FORCE_INLINE Quaternion -slerp(const Quaternion& q1, const Quaternion& q2, const tf2Scalar& t) +slerp(const Quaternion& q1, const Quaternion& q2, const tf2Scalar& t) { return q1.slerp(q2, t); } -TF2SIMD_FORCE_INLINE Vector3 -quatRotate(const Quaternion& rotation, const Vector3& v) +TF2SIMD_FORCE_INLINE Vector3 +quatRotate(const Quaternion& rotation, const Vector3& v) { Quaternion q = rotation * v; q *= rotation.inverse(); return Vector3(q.getX(),q.getY(),q.getZ()); } -TF2SIMD_FORCE_INLINE Quaternion +TF2SIMD_FORCE_INLINE Quaternion shortestArcQuat(const Vector3& v0, const Vector3& v1) // Game Programming Gems 2.10. make sure v0,v1 are normalized { Vector3 c = v0.cross(v1); @@ -464,7 +464,7 @@ shortestArcQuat(const Vector3& v0, const Vector3& v1) // Game Programming Gems 2 return Quaternion(c.getX()*rs,c.getY()*rs,c.getZ()*rs,s * 0.5f); } -TF2SIMD_FORCE_INLINE Quaternion +TF2SIMD_FORCE_INLINE Quaternion shortestArcQuatNormalize2(Vector3& v0,Vector3& v1) { v0.normalize(); @@ -473,4 +473,4 @@ shortestArcQuatNormalize2(Vector3& v0,Vector3& v1) } } -#endif +#endif // TF2__LINEARMATH__QUATERNION_HPP_ diff --git a/tf2/include/tf2/LinearMath/Scalar.h b/tf2/include/tf2/LinearMath/Scalar.h index af83a29e..ff6e7977 100644 --- a/tf2/include/tf2/LinearMath/Scalar.h +++ b/tf2/include/tf2/LinearMath/Scalar.h @@ -3,8 +3,8 @@ Copyright (c) 2003-2009 Erwin Coumans http://bullet.googlecode.com This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. diff --git a/tf2/include/tf2/LinearMath/Scalar.hpp b/tf2/include/tf2/LinearMath/Scalar.hpp index 9bbd3208..fdc2f9c4 100644 --- a/tf2/include/tf2/LinearMath/Scalar.hpp +++ b/tf2/include/tf2/LinearMath/Scalar.hpp @@ -3,8 +3,8 @@ Copyright (c) 2003-2009 Erwin Coumans http://bullet.googlecode.com This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -14,8 +14,8 @@ subject to the following restrictions: -#ifndef TF2_SCALAR_HPP -#define TF2_SCALAR_HPP +#ifndef TF2__LINEARMATH__SCALAR_HPP_ +#define TF2__LINEARMATH__SCALAR_HPP_ #ifdef TF2_MANAGED_CODE //Aligned data types not supported in managed code @@ -43,7 +43,7 @@ subject to the following restrictions: #define ATTRIBUTE_ALIGNED64(a) a #define ATTRIBUTE_ALIGNED128(a) a #else - //#define TF2_HPPAS_ALIGNED_ALLOCATOR + //#define TF2_HAS_ALIGNED_ALLOCATOR #pragma warning(disable : 4324) // disable padding warning // #pragma warning(disable:4530) // Disable the exception disable but used in MSCV Stl warning. // #pragma warning(disable:4996) //Turn off warnings about deprecated C routines @@ -57,7 +57,7 @@ subject to the following restrictions: #define TF2_USE_VMX128 #include - #define TF2_HPPAVE_NATIVE_FSEL + #define TF2_HAVE_NATIVE_FSEL #define tf2Fsel(a,b,c) __fsel((a),(b),(c)) #else @@ -79,7 +79,7 @@ subject to the following restrictions: #define tf2Unlikely(_c) _c #else - + #if defined (__CELLOS_LV2__) #define TF2SIMD_FORCE_INLINE inline #define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) @@ -121,7 +121,7 @@ subject to the following restrictions: #define tf2Likely(_c) __builtin_expect((_c), 1) #define tf2Unlikely(_c) __builtin_expect((_c), 0) - + #else //non-windows systems @@ -173,7 +173,7 @@ typedef double tf2Scalar; - + TF2SIMD_FORCE_INLINE tf2Scalar tf2Sqrt(tf2Scalar x) { return sqrt(x); } TF2SIMD_FORCE_INLINE tf2Scalar tf2Fabs(tf2Scalar x) { return fabs(x); } TF2SIMD_FORCE_INLINE tf2Scalar tf2Cos(tf2Scalar x) { return cos(x); } @@ -191,7 +191,7 @@ TF2SIMD_FORCE_INLINE tf2Scalar tf2Fmod(tf2Scalar x,tf2Scalar y) { return fmod(x, #define TF2SIMD_2_PI tf2Scalar(6.283185307179586232) #define TF2SIMD_PI (TF2SIMD_2_PI * tf2Scalar(0.5)) -#define TF2SIMD_HPPALF_PI (TF2SIMD_2_PI * tf2Scalar(0.25)) +#define TF2SIMD_HALF_PI (TF2SIMD_2_PI * tf2Scalar(0.25)) #define TF2SIMD_RADS_PER_DEG (TF2SIMD_2_PI / tf2Scalar(360.0)) #define TF2SIMD_DEGS_PER_RAD (tf2Scalar(360.0) / TF2SIMD_2_PI) #define TF2SIMDSQRT12 tf2Scalar(0.7071067811865475244008443621048490) @@ -202,7 +202,7 @@ TF2SIMD_FORCE_INLINE tf2Scalar tf2Fmod(tf2Scalar x,tf2Scalar y) { return fmod(x, #define TF2SIMD_EPSILON DBL_EPSILON #define TF2SIMD_INFINITY DBL_MAX -TF2SIMD_FORCE_INLINE tf2Scalar tf2Atan2Fast(tf2Scalar y, tf2Scalar x) +TF2SIMD_FORCE_INLINE tf2Scalar tf2Atan2Fast(tf2Scalar y, tf2Scalar x) { tf2Scalar coeff_1 = TF2SIMD_PI / 4.0f; tf2Scalar coeff_2 = 3.0f * coeff_1; @@ -235,7 +235,7 @@ TF2SIMD_FORCE_INLINE int tf2IsNegative(tf2Scalar x) { TF2SIMD_FORCE_INLINE tf2Scalar tf2Radians(tf2Scalar x) { return x * TF2SIMD_RADS_PER_DEG; } TF2SIMD_FORCE_INLINE tf2Scalar tf2Degrees(tf2Scalar x) { return x * TF2SIMD_DEGS_PER_RAD; } -#define TF2_DECLARE_HPPANDLE(name) typedef struct name##__ { int unused; } *name +#define TF2_DECLARE_HANDLE(name) typedef struct name##__ { int unused; } *name #ifndef tf2Fsel TF2SIMD_FORCE_INLINE tf2Scalar tf2Fsel(tf2Scalar a, tf2Scalar b, tf2Scalar c) @@ -260,28 +260,28 @@ TF2SIMD_FORCE_INLINE bool tf2MachineIsLittleEndian() ///tf2Select avoids branches, which makes performance much better for consoles like Playstation 3 and XBox 360 ///Thanks Phil Knight. See also http://www.cellperformance.com/articles/2006/04/more_techniques_for_eliminatin_1.html -TF2SIMD_FORCE_INLINE unsigned tf2Select(unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) +TF2SIMD_FORCE_INLINE unsigned tf2Select(unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) { // Set testNz to 0xFFFFFFFF if condition is nonzero, 0x00000000 if condition is zero // Rely on positive value or'ed with its negative having sign bit on - // and zero value or'ed with its negative (which is still zero) having sign bit off + // and zero value or'ed with its negative (which is still zero) having sign bit off // Use arithmetic shift right, shifting the sign bit through all 32 bits unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31); unsigned testEqz = ~testNz; - return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); + return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); } TF2SIMD_FORCE_INLINE int tf2Select(unsigned condition, int valueIfConditionNonZero, int valueIfConditionZero) { unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31); - unsigned testEqz = ~testNz; + unsigned testEqz = ~testNz; return static_cast((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); } TF2SIMD_FORCE_INLINE float tf2Select(unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero) { -#ifdef TF2_HPPAVE_NATIVE_FSEL +#ifdef TF2_HAVE_NATIVE_FSEL return (float)tf2Fsel((tf2Scalar)condition - tf2Scalar(1.0f), valueIfConditionNonZero, valueIfConditionZero); #else - return (condition != 0) ? valueIfConditionNonZero : valueIfConditionZero; + return (condition != 0) ? valueIfConditionNonZero : valueIfConditionZero; #endif } @@ -316,9 +316,9 @@ TF2SIMD_FORCE_INLINE unsigned short tf2SwapEndian(short val) ///tf2SwapFloat uses using char pointers to swap the endianness ////tf2SwapFloat/tf2SwapDouble will NOT return a float, because the machine might 'correct' invalid floating point values -///Not all values of sign/exponent/mantissa are valid floating point numbers according to IEEE 754. -///When a floating point unit is faced with an invalid value, it may actually change the value, or worse, throw an exception. -///In most systems, running user mode code, you wouldn't get an exception, but instead the hardware/os/runtime will 'fix' the number for you. +///Not all values of sign/exponent/mantissa are valid floating point numbers according to IEEE 754. +///When a floating point unit is faced with an invalid value, it may actually change the value, or worse, throw an exception. +///In most systems, running user mode code, you wouldn't get an exception, but instead the hardware/os/runtime will 'fix' the number for you. ///so instead of returning a float/double, we return integer/long long integer TF2SIMD_FORCE_INLINE unsigned int tf2SwapEndianFloat(float d) { @@ -334,7 +334,7 @@ TF2SIMD_FORCE_INLINE unsigned int tf2SwapEndianFloat(float d) } // unswap using char pointers -TF2SIMD_FORCE_INLINE float tf2UnswapEndianFloat(unsigned int a) +TF2SIMD_FORCE_INLINE float tf2UnswapEndianFloat(unsigned int a) { float d = 0.0f; unsigned char *src = (unsigned char *)&a; @@ -366,7 +366,7 @@ TF2SIMD_FORCE_INLINE void tf2SwapEndianDouble(double d, unsigned char* dst) } // unswap using char pointers -TF2SIMD_FORCE_INLINE double tf2UnswapEndianDouble(const unsigned char *src) +TF2SIMD_FORCE_INLINE double tf2UnswapEndianDouble(const unsigned char *src) { double d = 0.0; unsigned char *dst = (unsigned char *)&d; @@ -384,7 +384,7 @@ TF2SIMD_FORCE_INLINE double tf2UnswapEndianDouble(const unsigned char *src) } // returns normalized value in range [-TF2SIMD_PI, TF2SIMD_PI] -TF2SIMD_FORCE_INLINE tf2Scalar tf2NormalizeAngle(tf2Scalar angleInRadians) +TF2SIMD_FORCE_INLINE tf2Scalar tf2NormalizeAngle(tf2Scalar angleInRadians) { angleInRadians = tf2Fmod(angleInRadians, TF2SIMD_2_PI); if(angleInRadians < -TF2SIMD_PI) @@ -414,4 +414,4 @@ struct tf2TypedObject return m_objectType; } }; -#endif //TF2SIMD___SCALAR_HPP +#endif // TF2__LINEARMATH__SCALAR_HPP_ diff --git a/tf2/include/tf2/LinearMath/Transform.h b/tf2/include/tf2/LinearMath/Transform.h index d02f16c5..b8cfc958 100644 --- a/tf2/include/tf2/LinearMath/Transform.h +++ b/tf2/include/tf2/LinearMath/Transform.h @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. diff --git a/tf2/include/tf2/LinearMath/Transform.hpp b/tf2/include/tf2/LinearMath/Transform.hpp index 24caa04b..03f2aff9 100644 --- a/tf2/include/tf2/LinearMath/Transform.hpp +++ b/tf2/include/tf2/LinearMath/Transform.hpp @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -14,8 +14,8 @@ subject to the following restrictions: -#ifndef tf2_Transform_HPP -#define tf2_Transform_HPP +#ifndef TF2__LINEARMATH__TRANSFORM_HPP +#define TF2__LINEARMATH__TRANSFORM_HPP #include "Matrix3x3.hpp" @@ -31,30 +31,30 @@ namespace tf2 /**@brief The Transform class supports rigid transforms with only translation and rotation and no scaling/shear. *It can be used in combination with Vector3, Quaternion and Matrix3x3 linear algebra classes. */ class Transform { - + ///Storage for the rotation Matrix3x3 m_basis; ///Storage for the translation Vector3 m_origin; public: - + /**@brief No initialization constructor */ TF2_PUBLIC Transform() {} /**@brief Constructor from Quaternion (optional Vector3 ) - * @param q Rotation from quaternion + * @param q Rotation from quaternion * @param c Translation from Vector (default 0,0,0) */ - explicit TF2SIMD_FORCE_INLINE Transform(const Quaternion& q, - const Vector3& c = Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0))) + explicit TF2SIMD_FORCE_INLINE Transform(const Quaternion& q, + const Vector3& c = Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0))) : m_basis(q), m_origin(c) {} /**@brief Constructor from Matrix3x3 (optional Vector3) - * @param b Rotation from Matrix + * @param b Rotation from Matrix * @param c Translation from Vector default (0,0,0)*/ - explicit TF2SIMD_FORCE_INLINE Transform(const Matrix3x3& b, + explicit TF2SIMD_FORCE_INLINE Transform(const Matrix3x3& b, const Vector3& c = Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0))) : m_basis(b), m_origin(c) @@ -92,8 +92,8 @@ class Transform { /**@brief Return the transform of the vector */ TF2SIMD_FORCE_INLINE Vector3 operator()(const Vector3& x) const { - return Vector3(m_basis[0].dot(x) + m_origin.x(), - m_basis[1].dot(x) + m_origin.y(), + return Vector3(m_basis[0].dot(x) + m_origin.x(), + m_basis[1].dot(x) + m_origin.y(), m_basis[2].dot(x) + m_origin.z()); } @@ -121,14 +121,14 @@ class Transform { /**@brief Return a quaternion representing the rotation */ TF2_PUBLIC - Quaternion getRotation() const { + Quaternion getRotation() const { Quaternion q; m_basis.getRotation(q); return q; } - - - /**@brief Set from an array + + + /**@brief Set from an array * @param m A pointer to a 15 element array (12 rotation(row major padded on the right by 1), and 3 translation */ TF2_PUBLIC void setFromOpenGLMatrix(const tf2Scalar *m) @@ -140,7 +140,7 @@ class Transform { /**@brief Fill an array representation * @param m A pointer to a 15 element array (12 rotation(row major padded on the right by 1), and 3 translation */ TF2_PUBLIC - void getOpenGLMatrix(tf2Scalar *m) const + void getOpenGLMatrix(tf2Scalar *m) const { m_basis.getOpenGLSubMatrix(m); m[12] = m_origin.x(); @@ -151,8 +151,8 @@ class Transform { /**@brief Set the translational element * @param origin The vector to set the translation to */ - TF2SIMD_FORCE_INLINE void setOrigin(const Vector3& origin) - { + TF2SIMD_FORCE_INLINE void setOrigin(const Vector3& origin) + { m_origin = origin; } @@ -161,7 +161,7 @@ class Transform { /**@brief Set the rotational element by Matrix3x3 */ TF2SIMD_FORCE_INLINE void setBasis(const Matrix3x3& basis) - { + { m_basis = basis; } @@ -180,10 +180,10 @@ class Transform { m_origin.setValue(tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(0.0)); } - /**@brief Multiply this Transform by another(this = this * another) + /**@brief Multiply this Transform by another(this = this * another) * @param t The other transform */ TF2_PUBLIC - Transform& operator*=(const Transform& t) + Transform& operator*=(const Transform& t) { m_origin += m_basis * t.m_origin; m_basis *= t.m_basis; @@ -193,16 +193,16 @@ class Transform { /**@brief Return the inverse of this transform */ TF2_PUBLIC Transform inverse() const - { + { Matrix3x3 inv = m_basis.transpose(); return Transform(inv, inv * -m_origin); } /**@brief Return the inverse of this transform times the other transform - * @param t The other transform + * @param t The other transform * return this.inverse() * the other */ TF2_PUBLIC - Transform inverseTimes(const Transform& t) const; + Transform inverseTimes(const Transform& t) const; /**@brief Return the product of this transform and the other */ TF2_PUBLIC @@ -241,18 +241,18 @@ Transform::invXform(const Vector3& inVec) const return (m_basis.transpose() * v); } -TF2SIMD_FORCE_INLINE Transform -Transform::inverseTimes(const Transform& t) const +TF2SIMD_FORCE_INLINE Transform +Transform::inverseTimes(const Transform& t) const { Vector3 v = t.getOrigin() - m_origin; return Transform(m_basis.transposeTimes(t.m_basis), v * m_basis); } -TF2SIMD_FORCE_INLINE Transform +TF2SIMD_FORCE_INLINE Transform Transform::operator*(const Transform& t) const { - return Transform(m_basis * t.m_basis, + return Transform(m_basis * t.m_basis, (*this)(t.m_origin)); } @@ -312,4 +312,4 @@ TF2SIMD_FORCE_INLINE void Transform::deSerializeDouble(const TransformDoubleData } -#endif +#endif // TF2__LINEARMATH__TRANSFORM_HPP diff --git a/tf2/include/tf2/LinearMath/Vector3.h b/tf2/include/tf2/LinearMath/Vector3.h index f2924604..7bb0bc5a 100644 --- a/tf2/include/tf2/LinearMath/Vector3.h +++ b/tf2/include/tf2/LinearMath/Vector3.h @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. diff --git a/tf2/include/tf2/LinearMath/Vector3.hpp b/tf2/include/tf2/LinearMath/Vector3.hpp index dce58e6b..6e0e8295 100644 --- a/tf2/include/tf2/LinearMath/Vector3.hpp +++ b/tf2/include/tf2/LinearMath/Vector3.hpp @@ -3,8 +3,8 @@ Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousph This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -14,8 +14,8 @@ subject to the following restrictions: -#ifndef TF2_VECTOR3_HPP -#define TF2_VECTOR3_HPP +#ifndef TF2__LINEARMATH__VECTOR3_HPP_ +#define TF2__LINEARMATH__VECTOR3_HPP_ #include "Scalar.hpp" @@ -71,12 +71,12 @@ ATTRIBUTE_ALIGNED16(class) Vector3 /**@brief No initialization constructor */ TF2SIMD_FORCE_INLINE Vector3() {} - - - /**@brief Constructor from scalars + + + /**@brief Constructor from scalars * @param x X value - * @param y Y value - * @param z Z value + * @param y Y value + * @param z Z value */ TF2SIMD_FORCE_INLINE Vector3(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z) { @@ -86,7 +86,7 @@ ATTRIBUTE_ALIGNED16(class) Vector3 m_floats[3] = tf2Scalar(0.); } -/**@brief Add a vector to this one +/**@brief Add a vector to this one * @param The vector to add to this one */ TF2SIMD_FORCE_INLINE Vector3& operator+=(const Vector3& v) { @@ -98,7 +98,7 @@ ATTRIBUTE_ALIGNED16(class) Vector3 /**@brief Sutf2ract a vector from this one * @param The vector to sutf2ract */ - TF2SIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v) + TF2SIMD_FORCE_INLINE Vector3& operator-=(const Vector3& v) { m_floats[0] -= v.m_floats[0]; m_floats[1] -= v.m_floats[1];m_floats[2] -= v.m_floats[2]; return *this; @@ -111,9 +111,9 @@ ATTRIBUTE_ALIGNED16(class) Vector3 return *this; } - /**@brief Inversely scale the vector + /**@brief Inversely scale the vector * @param s Scale factor to divide by */ - TF2SIMD_FORCE_INLINE Vector3& operator/=(const tf2Scalar& s) + TF2SIMD_FORCE_INLINE Vector3& operator/=(const tf2Scalar& s) { tf2FullAssert(s != tf2Scalar(0.0)); return *this *= tf2Scalar(1.0) / s; @@ -146,9 +146,9 @@ ATTRIBUTE_ALIGNED16(class) Vector3 * This is symantically treating the vector like a point */ TF2SIMD_FORCE_INLINE tf2Scalar distance(const Vector3& v) const; - /**@brief Normalize this vector + /**@brief Normalize this vector * x^2 + y^2 + z^2 = 1 */ - TF2SIMD_FORCE_INLINE Vector3& normalize() + TF2SIMD_FORCE_INLINE Vector3& normalize() { return *this /= length(); } @@ -156,28 +156,28 @@ ATTRIBUTE_ALIGNED16(class) Vector3 /**@brief Return a normalized version of this vector */ TF2SIMD_FORCE_INLINE Vector3 normalized() const; - /**@brief Rotate this vector - * @param wAxis The axis to rotate about + /**@brief Rotate this vector + * @param wAxis The axis to rotate about * @param angle The angle to rotate by */ TF2SIMD_FORCE_INLINE Vector3 rotate( const Vector3& wAxis, const tf2Scalar angle ) const; /**@brief Return the angle between this and another vector * @param v The other vector */ - TF2SIMD_FORCE_INLINE tf2Scalar angle(const Vector3& v) const + TF2SIMD_FORCE_INLINE tf2Scalar angle(const Vector3& v) const { tf2Scalar s = tf2Sqrt(length2() * v.length2()); tf2FullAssert(s != tf2Scalar(0.0)); return tf2Acos(dot(v) / s); } /**@brief Return a vector will the absolute values of each element */ - TF2SIMD_FORCE_INLINE Vector3 absolute() const + TF2SIMD_FORCE_INLINE Vector3 absolute() const { return Vector3( - tf2Fabs(m_floats[0]), - tf2Fabs(m_floats[1]), + tf2Fabs(m_floats[0]), + tf2Fabs(m_floats[1]), tf2Fabs(m_floats[2])); } - /**@brief Return the cross product between this and another vector + /**@brief Return the cross product between this and another vector * @param v The other vector */ TF2SIMD_FORCE_INLINE Vector3 cross(const Vector3& v) const { @@ -189,21 +189,21 @@ ATTRIBUTE_ALIGNED16(class) Vector3 TF2SIMD_FORCE_INLINE tf2Scalar triple(const Vector3& v1, const Vector3& v2) const { - return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) + - m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) + + return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) + + m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) + m_floats[2] * (v1.m_floats[0] * v2.m_floats[1] - v1.m_floats[1] * v2.m_floats[0]); } - /**@brief Return the axis with the smallest value + /**@brief Return the axis with the smallest value * Note return values are 0,1,2 for x, y, or z */ TF2SIMD_FORCE_INLINE int minAxis() const { return m_floats[0] < m_floats[1] ? (m_floats[0] return this, t=1 => return other) */ - TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tf2Scalar& t) const + TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3& v, const tf2Scalar& t) const { return Vector3(m_floats[0] + (v.m_floats[0] - m_floats[0]) * t, m_floats[1] + (v.m_floats[1] - m_floats[1]) * t, m_floats[2] + (v.m_floats[2] -m_floats[2]) * t); } - /**@brief Elementwise multiply this vector by the other + /**@brief Elementwise multiply this vector by the other * @param v The other vector */ TF2SIMD_FORCE_INLINE Vector3& operator*=(const Vector3& v) { @@ -269,7 +269,7 @@ ATTRIBUTE_ALIGNED16(class) Vector3 /**@brief Return the w value */ TF2SIMD_FORCE_INLINE const tf2Scalar& w() const { return m_floats[3]; } - //TF2SIMD_FORCE_INLINE tf2Scalar& operator[](int i) { return (&m_floats[0])[i]; } + //TF2SIMD_FORCE_INLINE tf2Scalar& operator[](int i) { return (&m_floats[0])[i]; } //TF2SIMD_FORCE_INLINE const tf2Scalar& operator[](int i) const { return (&m_floats[0])[i]; } ///operator tf2Scalar*() replaces operator[], using implicit conversion. We added operator != and operator == to avoid pointer comparisons. TF2SIMD_FORCE_INLINE operator tf2Scalar *() { return &m_floats[0]; } @@ -286,7 +286,7 @@ ATTRIBUTE_ALIGNED16(class) Vector3 } /**@brief Set each element to the max of the current values and the values of another Vector3 - * @param other The other Vector3 to compare with + * @param other The other Vector3 to compare with */ TF2SIMD_FORCE_INLINE void setMax(const Vector3& other) { @@ -296,7 +296,7 @@ ATTRIBUTE_ALIGNED16(class) Vector3 tf2SetMax(m_floats[3], other.w()); } /**@brief Set each element to the min of the current values and the values of another Vector3 - * @param other The other Vector3 to compare with + * @param other The other Vector3 to compare with */ TF2SIMD_FORCE_INLINE void setMin(const Vector3& other) { @@ -328,12 +328,12 @@ ATTRIBUTE_ALIGNED16(class) Vector3 setValue(tf2Scalar(0.),tf2Scalar(0.),tf2Scalar(0.)); } - TF2SIMD_FORCE_INLINE bool isZero() const + TF2SIMD_FORCE_INLINE bool isZero() const { return m_floats[0] == tf2Scalar(0) && m_floats[1] == tf2Scalar(0) && m_floats[2] == tf2Scalar(0); } - TF2SIMD_FORCE_INLINE bool fuzzyZero() const + TF2SIMD_FORCE_INLINE bool fuzzyZero() const { return length2() < TF2SIMD_EPSILON; } @@ -353,44 +353,44 @@ ATTRIBUTE_ALIGNED16(class) Vector3 }; /**@brief Return the sum of two vectors (Point symantics)*/ -TF2SIMD_FORCE_INLINE Vector3 -operator+(const Vector3& v1, const Vector3& v2) +TF2SIMD_FORCE_INLINE Vector3 +operator+(const Vector3& v1, const Vector3& v2) { return Vector3(v1.m_floats[0] + v2.m_floats[0], v1.m_floats[1] + v2.m_floats[1], v1.m_floats[2] + v2.m_floats[2]); } /**@brief Return the elementwise product of two vectors */ -TF2SIMD_FORCE_INLINE Vector3 -operator*(const Vector3& v1, const Vector3& v2) +TF2SIMD_FORCE_INLINE Vector3 +operator*(const Vector3& v1, const Vector3& v2) { return Vector3(v1.m_floats[0] * v2.m_floats[0], v1.m_floats[1] * v2.m_floats[1], v1.m_floats[2] * v2.m_floats[2]); } /**@brief Return the difference between two vectors */ -TF2SIMD_FORCE_INLINE Vector3 +TF2SIMD_FORCE_INLINE Vector3 operator-(const Vector3& v1, const Vector3& v2) { return Vector3(v1.m_floats[0] - v2.m_floats[0], v1.m_floats[1] - v2.m_floats[1], v1.m_floats[2] - v2.m_floats[2]); } /**@brief Return the negative of the vector */ -TF2SIMD_FORCE_INLINE Vector3 +TF2SIMD_FORCE_INLINE Vector3 operator-(const Vector3& v) { return Vector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]); } /**@brief Return the vector scaled by s */ -TF2SIMD_FORCE_INLINE Vector3 +TF2SIMD_FORCE_INLINE Vector3 operator*(const Vector3& v, const tf2Scalar& s) { return Vector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s); } /**@brief Return the vector scaled by s */ -TF2SIMD_FORCE_INLINE Vector3 +TF2SIMD_FORCE_INLINE Vector3 operator*(const tf2Scalar& s, const Vector3& v) -{ - return v * s; +{ + return v * s; } /**@brief Return the vector inversely scaled by s */ @@ -409,40 +409,40 @@ operator/(const Vector3& v1, const Vector3& v2) } /**@brief Return the dot product between two vectors */ -TF2SIMD_FORCE_INLINE tf2Scalar -tf2Dot(const Vector3& v1, const Vector3& v2) -{ - return v1.dot(v2); +TF2SIMD_FORCE_INLINE tf2Scalar +tf2Dot(const Vector3& v1, const Vector3& v2) +{ + return v1.dot(v2); } /**@brief Return the distance squared between two vectors */ TF2SIMD_FORCE_INLINE tf2Scalar -tf2Distance2(const Vector3& v1, const Vector3& v2) -{ - return v1.distance2(v2); +tf2Distance2(const Vector3& v1, const Vector3& v2) +{ + return v1.distance2(v2); } /**@brief Return the distance between two vectors */ TF2SIMD_FORCE_INLINE tf2Scalar -tf2Distance(const Vector3& v1, const Vector3& v2) -{ - return v1.distance(v2); +tf2Distance(const Vector3& v1, const Vector3& v2) +{ + return v1.distance(v2); } /**@brief Return the angle between two vectors */ TF2SIMD_FORCE_INLINE tf2Scalar -tf2Angle(const Vector3& v1, const Vector3& v2) -{ - return v1.angle(v2); +tf2Angle(const Vector3& v1, const Vector3& v2) +{ + return v1.angle(v2); } /**@brief Return the cross product of two vectors */ -TF2SIMD_FORCE_INLINE Vector3 -tf2Cross(const Vector3& v1, const Vector3& v2) -{ - return v1.cross(v2); +TF2SIMD_FORCE_INLINE Vector3 +tf2Cross(const Vector3& v1, const Vector3& v2) +{ + return v1.cross(v2); } TF2SIMD_FORCE_INLINE tf2Scalar @@ -452,10 +452,10 @@ tf2Triple(const Vector3& v1, const Vector3& v2, const Vector3& v3) } /**@brief Return the linear interpolation between two vectors - * @param v1 One vector - * @param v2 The other vector + * @param v1 One vector + * @param v2 The other vector * @param t The ration of this to v (t = 0 => return v1, t=1 => return v2) */ -TF2SIMD_FORCE_INLINE Vector3 +TF2SIMD_FORCE_INLINE Vector3 lerp(const Vector3& v1, const Vector3& v2, const tf2Scalar& t) { return v1.lerp(v2, t); @@ -476,7 +476,7 @@ TF2SIMD_FORCE_INLINE tf2Scalar Vector3::distance(const Vector3& v) const TF2SIMD_FORCE_INLINE Vector3 Vector3::normalized() const { return *this / length(); -} +} TF2SIMD_FORCE_INLINE Vector3 Vector3::rotate( const Vector3& wAxis, const tf2Scalar angle ) const { @@ -498,18 +498,18 @@ class tf2Vector4 : public Vector3 TF2SIMD_FORCE_INLINE tf2Vector4() {} - TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w) + TF2SIMD_FORCE_INLINE tf2Vector4(const tf2Scalar& x, const tf2Scalar& y, const tf2Scalar& z,const tf2Scalar& w) : Vector3(x,y,z) { m_floats[3] = w; } - TF2SIMD_FORCE_INLINE tf2Vector4 absolute4() const + TF2SIMD_FORCE_INLINE tf2Vector4 absolute4() const { return tf2Vector4( - tf2Fabs(m_floats[0]), - tf2Fabs(m_floats[1]), + tf2Fabs(m_floats[0]), + tf2Fabs(m_floats[1]), tf2Fabs(m_floats[2]), tf2Fabs(m_floats[3])); } @@ -543,9 +543,9 @@ class tf2Vector4 : public Vector3 { maxIndex = 3; } - - - + + + return maxIndex; @@ -575,35 +575,35 @@ class tf2Vector4 : public Vector3 { minIndex = 3; } - + return minIndex; } - TF2SIMD_FORCE_INLINE int closestAxis4() const + TF2SIMD_FORCE_INLINE int closestAxis4() const { return absolute4().maxAxis4(); } + + - - - /**@brief Set x,y,z and zero w + /**@brief Set x,y,z and zero w * @param x Value of x * @param y Value of y * @param z Value of z */ + - -/* void getValue(tf2Scalar *m) const +/* void getValue(tf2Scalar *m) const { m[0] = m_floats[0]; m[1] = m_floats[1]; m[2] =m_floats[2]; } */ -/**@brief Set the values +/**@brief Set the values * @param x Value of x * @param y Value of y * @param z Value of z @@ -732,4 +732,4 @@ TF2SIMD_FORCE_INLINE void Vector3::deSerialize(const struct Vector3Data& dataIn) } -#endif //TF2_VECTOR3_HPP +#endif // TF2__LINEARMATH__VECTOR3_HPP_