From 030c916d22bd9ec7937ed2f91cf40486e8f8edcd Mon Sep 17 00:00:00 2001 From: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Date: Tue, 5 Nov 2024 21:01:37 -0500 Subject: [PATCH] Linter Vector3.hpp Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> --- tf2/include/tf2/LinearMath/Vector3.hpp | 168 ++++++++++++------------- 1 file changed, 84 insertions(+), 84 deletions(-) diff --git a/tf2/include/tf2/LinearMath/Vector3.hpp b/tf2/include/tf2/LinearMath/Vector3.hpp index dce58e6b0..6e0e82950 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_