UFO 1.0.0
An Efficient Probabilistic 3D Mapping Framework That Embraces the Unknown
Loading...
Searching...
No Matches
Numeric Module

All numeric-related classes and functions. More...

Namespaces

namespace  ufo
 All vision-related classes and functions.
 

Concepts

concept  ufo::Matrix
 Concept satisfied by any specialization of Mat<Rows, Cols, U>.
 

Classes

struct  ufo::Mat< Rows, Cols, T >
 A fixed-size matrix with Rows rows and Cols columns. More...
 
struct  ufo::Quat< T >
 Unit quaternion representing an orientation or rotation in 3-D space. More...
 
struct  ufo::Transform< Dim, T >
 Rigid-body transform: a rotation matrix plus a translation vector. More...
 
struct  ufo::Vec< Dim, T >
 A fixed-size arithmetic vector of up to 4 dimensions. More...
 

Typedefs

template<class T = float>
using ufo::Mat2 = Mat< 2, 2, T >
 
using ufo::Quatf = Quat< float >
 
template<std::floating_point T = float>
using ufo::Transform2 = Transform< 2, T >
 
using ufo::Vec1b = Vec< 1, bool >
 

Functions

constexpr ufo::Quat< T >::Quat () noexcept=default
 Default constructor; initializes to the identity rotation (1, 0, 0, 0).
 
constexpr ufo::Transform< Dim, T >::Transform () noexcept=default
 Default constructor; initializes to the identity transform (zero translation and identity rotation).
 
template<std::floating_point T>
ufo::angle (Quat< T > const &q) noexcept
 Extracts the rotation angle (in radians) from a unit quaternion.
 
template<class T , std::size_t Dim, class U >
constexpr Vec< Dim, T > ufo::cast (Vec< Dim, U > const &v) noexcept
 Casts each element of a vector to a new type.
 
template<SquareMatrix M>
constexpr auto ufo::determinant (M const &m) noexcept
 Computes the determinant of a square matrix.
 
template<std::floating_point T>
constexpr T ufo::dot (Quat< T > const &a, Quat< T > const &b) noexcept
 Computes the four-component dot product a.w*b.w + a.x*b.x + a.y*b.y + a.z*b.z.
 
template<std::floating_point T>
constexpr Vec< 3, T > ufo::eigenValues (Mat< 3, 3, T > const &m) noexcept
 Computes the eigenvalues of a real symmetric 3×3 matrix, sorted ascending.
 
template<std::size_t I, std::size_t Rows, std::size_t Cols, class T >
requires (I < Rows)
constexpr Vec< Cols, T > & ufo::get (Mat< Rows, Cols, T > &m) noexcept
 Structured-binding accessor — lvalue reference to row I.
 
template<std::size_t I, std::size_t Dim, class T >
requires (I < Dim)
constexpr T & ufo::get (Vec< Dim, T > &v) noexcept
 Returns a reference to the I-th element for structured bindings.
 
template<std::size_t Dim, std::floating_point T>
constexpr Transform< Dim, T > ufo::inverse (Transform< Dim, T > const &t)
 Returns the inverse of a rigid-body transform.
 
template<std::floating_point T>
Vec< 4, bool > ufo::isnan (Quat< T > const &q) noexcept
 Returns a bool vector indicating which components are NaN.
 
template<std::floating_point T>
Quat< T > ufo::mix (Quat< T > const &x, Quat< T > const &y, T a)
 Spherical or linear interpolation between two quaternions.
 
constexpr ufo::Quat< T >::operator Mat< 3, 3, T > () const noexcept
 Converts to a row-major 3×3 rotation matrix.
 
template<std::floating_point U>
constexpr ufo::Transform< Dim, T >::operator Mat< Dim, Dim, U > () const
 Extracts the rotation component as a Dim × Dim matrix.
 
template<std::floating_point U>
constexpr Vec< Dim, U > ufo::Transform< Dim, T >::operator() (Vec< Dim, U > const &v) const
 Applies the transform to a vector: result = R * v + t.
 
template<std::size_t Rows, std::size_t Cols, class T >
constexpr Vec< Rows, T > ufo::operator* (Mat< Rows, Cols, T > const &m, Vec< Cols, T > const &v) noexcept
 Multiplies a matrix by a column vector (M * v).
 
template<std::size_t Rows, std::size_t Shared, std::size_t Cols, class T >
constexpr Mat< Rows, Cols, T > ufo::operator* (Mat< Rows, Shared, T > const &a, Mat< Shared, Cols, T > const &b) noexcept
 Matrix × matrix product.
 
template<std::size_t Dim, std::floating_point T>
constexpr Transform< Dim, T > ufo::operator* (Transform< Dim, T > t1, Transform< Dim, T > const &t2)
 Composes two transforms: (t1 * t2)(v) = t1(t2(v)).
 
constexpr Mat ufo::Mat< Rows, Cols, T >::operator+ () const noexcept
 Unary identity operator.
 
constexpr Vec ufo::Vec< Dim, T >::operator+ () const noexcept
 Unary identity operator.
 
template<std::size_t Rows, std::size_t Cols, class T >
constexpr Mat< Rows, Cols, T > ufo::operator+ (Mat< Rows, Cols, T > lhs, Mat< Rows, Cols, T > const &rhs) noexcept
 Element-wise addition of two matrices.
 
template<std::size_t Rows, std::size_t Cols, class T >
constexpr Mat< Rows, Cols, T > ufo::operator+ (Mat< Rows, Cols, T > lhs, T rhs) noexcept
 Adds scalar rhs to every element of lhs.
 
template<std::floating_point T>
constexpr Quat< T > ufo::operator+ (Quat< T > const &q) noexcept
 Unary plus — returns a copy of q unchanged.
 
template<std::floating_point T>
constexpr Quat< T > ufo::operator+ (Quat< T > lhs, Quat< T > const &rhs) noexcept
 Component-wise addition of two quaternions.
 
template<std::size_t Dim, class T >
constexpr Vec< Dim, T > ufo::operator+ (Vec< Dim, T > lhs, T rhs) noexcept
 Adds scalar rhs to every component of lhs.
 
template<std::size_t Dim, class T >
constexpr Vec< Dim, T > ufo::operator+ (Vec< Dim, T > lhs, Vec< Dim, T > const &rhs) noexcept
 Component-wise addition of two vectors.
 
constexpr Matufo::Mat< Rows, Cols, T >::operator+= (Mat const &rhs) noexcept
 Adds rhs element-wise to this matrix.
 
constexpr Quatufo::Quat< T >::operator+= (Quat const &q) noexcept
 Component-wise addition.
 
constexpr Matufo::Mat< Rows, Cols, T >::operator+= (T rhs) noexcept
 Adds scalar rhs to every element.
 
constexpr Vecufo::Vec< Dim, T >::operator+= (T rhs) noexcept
 Adds scalar rhs to every component.
 
constexpr Vecufo::Vec< Dim, T >::operator+= (Vec const &rhs) noexcept
 Adds each component of rhs to the corresponding component.
 
template<std::size_t Rows, std::size_t Cols, class T >
std::ostream & ufo::operator<< (std::ostream &out, Mat< Rows, Cols, T > const &m)
 Writes a matrix to an output stream, one row per line.
 
template<std::floating_point T>
std::ostream & ufo::operator<< (std::ostream &out, Quat< T > const &q)
 Writes the quaternion to an output stream as "qw: W qx: X qy: Y qz: Z".
 
template<std::size_t Dim, class T >
std::ostream & ufo::operator<< (std::ostream &out, Vec< Dim, T > const &v)
 Writes a human-readable representation of a vector to a stream.
 
constexpr Quatufo::Quat< T >::operator= (Quat const &) noexcept=default
 Copy assignment operator.
 
constexpr Transformufo::Transform< Dim, T >::operator= (Transform const &) noexcept=default
 Default copy assignment operator.
 
constexpr auto & ufo::Vec< Dim, T >::operator[] (this auto &self, size_type i) noexcept
 Accesses the element at index i.
 
constexpr auto & ufo::Quat< T >::operator[] (this auto &self, size_type pos) noexcept
 Component access by index: 0->w, 1->x, 2->y, 3->z.
 
constexpr auto & ufo::Mat< Rows, Cols, T >::operator[] (this auto &self, size_type r, size_type c) noexcept
 Accesses the element at row r, column c.
 
template<std::floating_point T>
Mat< 4, 4, T > ufo::orthogonal (T left, T right, T bottom, T top)
 Builds a right-handed 2-D orthographic projection matrix (no depth clipping).
 
template<std::floating_point T>
ufo::roll (Quat< T > const &q) noexcept
 Extracts the roll angle (rotation about the X-axis) in radians.
 
template<std::floating_point T>
Quat< T > ufo::rotate (Quat< T > const &q, T angle, Vec< 3, T > axis)
 Appends an angle-axis rotation to a quaternion.
 
static constexpr size_type ufo::Quat< T >::size () noexcept
 Returns the number of components (always 4: w, x, y, z).
 
void ufo::Quat< T >::swap (Quat &other) noexcept
 Swaps all components with other.
 
template<std::floating_point T>
void ufo::swap (Quat< T > &lhs, Quat< T > &rhs) noexcept
 Non-member swap — exchanges all components of lhs and rhs.
 
constexpr T ufo::Mat< Rows, Cols, T >::trace () const noexcept
 Computes the trace (sum of diagonal elements) of a square matrix.
 
template<class T >
constexpr int ufo::sign (T val) noexcept
 Returns the sign of a value.
 
template<std::floating_point T>
constexpr T ufo::radians (T deg) noexcept
 Converts degrees to radians.
 
template<std::floating_point T>
constexpr T ufo::degrees (T rad) noexcept
 Converts radians to degrees.
 
template<class T >
requires std::is_arithmetic_v<T>
constexpr T ufo::ipow (T base, int exp) noexcept
 Computes integer power of a base.
 
template<std::floating_point T>
constexpr T ufo::probabilityToLogit (T probability)
 Converts probability to logit value.
 
template<std::floating_point T>
constexpr T ufo::logitToProbability (T logit)
 Converts logit value to probability.
 

Detailed Description

All numeric-related classes and functions.

Author
Daniel Duberg (danie.nosp@m.ldub.nosp@m.erg@g.nosp@m.mail.nosp@m..com)
See also
https://github.com/UnknownFreeOccupied/ufo
Version
1.0
Date
2026-02-22

Copyright (c) 2020-2026, Daniel Duberg All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

  1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  2. 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.
  3. Neither the name of the copyright holder 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 HOLDER 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.

Typedef Documentation

◆ Mat2

template<class T = float>
using ufo::Mat2 = typedef Mat<2, 2, T>

Definition at line 751 of file mat.hpp.

◆ Quatf

using ufo::Quatf = typedef Quat<float>

Definition at line 427 of file quat.hpp.

◆ Transform2

template<std::floating_point T = float>
using ufo::Transform2 = typedef Transform<2, T>

Definition at line 382 of file transform.hpp.

◆ Vec1b

using ufo::Vec1b = typedef Vec<1, bool>

Definition at line 502 of file vec.hpp.

Function Documentation

◆ angle()

template<std::floating_point T>
T ufo::angle ( Quat< T > const &  q)
noexcept

Extracts the rotation angle (in radians) from a unit quaternion.

Template Parameters
TFloating-point scalar type.
Parameters
[in]qUnit quaternion.
Returns
Rotation angle in [0, 2π).

Definition at line 852 of file quat.hpp.

◆ cast()

template<class T , std::size_t Dim, class U >
constexpr Vec< Dim, T > ufo::cast ( Vec< Dim, U > const &  v)
constexprnoexcept

Casts each element of a vector to a new type.

Template Parameters
TTarget element type.
DimNumber of dimensions.
USource element type.
Parameters
[in]vThe source vector.
Returns
A new vector with elements cast to type T.

Definition at line 1042 of file vec.hpp.

◆ degrees()

template<std::floating_point T>
constexpr T ufo::degrees ( rad)
constexprnoexcept

Converts radians to degrees.

Template Parameters
TFloating point type (e.g., float, double).
Parameters
[in]radThe angle in radians.
Returns
The angle in degrees.

Definition at line 98 of file math.hpp.

◆ determinant()

template<SquareMatrix M>
constexpr auto ufo::determinant ( M const &  m)
constexprnoexcept

Computes the determinant of a square matrix.

Closed-form implementations are provided for 2×2, 3×3, and 4×4 matrices. Requesting any other size triggers a static_assert at compile time.

Template Parameters
MA square matrix type satisfying SquareMatrix.
Parameters
[in]mThe matrix.
Returns
The determinant of m as M::value_type.

Definition at line 1056 of file mat.hpp.

◆ dot()

template<std::floating_point T>
constexpr T ufo::dot ( Quat< T > const &  a,
Quat< T > const &  b 
)
constexprnoexcept

Computes the four-component dot product a.w*b.w + a.x*b.x + a.y*b.y + a.z*b.z.

Template Parameters
TFloating-point scalar type.
Parameters
[in]aFirst quaternion.
[in]bSecond quaternion.
Returns
Scalar dot product.

Definition at line 643 of file quat.hpp.

◆ eigenValues()

template<std::floating_point T>
constexpr Vec< 3, T > ufo::eigenValues ( Mat< 3, 3, T > const &  m)
constexprnoexcept

Computes the eigenvalues of a real symmetric 3×3 matrix, sorted ascending.

Uses the closed-form trigonometric solution (Cardano's method adapted for symmetric 3×3 matrices). Only the upper triangle of m is read; the lower triangle is assumed to equal the upper triangle.

Template Parameters
TFloating-point scalar type.
Parameters
[in]mA real symmetric 3×3 matrix.
Returns
Vec<3, T> with eigenvalues e[0] ≤ e[1] ≤ e[2].

Definition at line 1252 of file mat.hpp.

◆ get() [1/2]

template<std::size_t I, std::size_t Rows, std::size_t Cols, class T >
requires (I < Rows)
constexpr Vec< Cols, T > & ufo::get ( Mat< Rows, Cols, T > &  m)
constexprnoexcept

Structured-binding accessor — lvalue reference to row I.

Template Parameters
IRow index (must satisfy I < Rows).
RowsNumber of rows in the matrix.
ColsNumber of columns in the matrix.
TElement type.
Parameters
[in]mThe matrix.
Returns
A mutable reference to row I as Vec<Cols, T>&.

Definition at line 1586 of file mat.hpp.

◆ get() [2/2]

template<std::size_t I, std::size_t Dim, class T >
requires (I < Dim)
constexpr T & ufo::get ( Vec< Dim, T > &  v)
constexprnoexcept

Returns a reference to the I-th element for structured bindings.

Template Parameters
IZero-based compile-time index (must be less than Dim).
DimNumber of dimensions.
TElement type.
Parameters
[in]vThe vector.
Returns
Lvalue reference to v[I].

Definition at line 1729 of file vec.hpp.

◆ inverse()

template<std::size_t Dim, std::floating_point T>
constexpr Transform< Dim, T > ufo::inverse ( Transform< Dim, T > const &  t)
constexpr

Returns the inverse of a rigid-body transform.

For an orthogonal rotation matrix R, the inverse is R^T. The inverse translation is -(R^T * t), so inverse(t)(v) = R^T * (v - t).

Template Parameters
DimSpatial dimension.
TFloating-point scalar type.
Parameters
[in]tThe transform to invert (rotation must be orthogonal).
Returns
The inverse transform such that inverse(t) * t = identity.

Definition at line 478 of file transform.hpp.

◆ ipow()

template<class T >
requires std::is_arithmetic_v<T>
constexpr T ufo::ipow ( base,
int  exp 
)
constexprnoexcept

Computes integer power of a base.

Template Parameters
TNumeric type (e.g., int, float).
Parameters
[in]baseThe base value.
[in]expThe exponent (can be negative).
Returns
The result of raising the base to the exponent.

Definition at line 112 of file math.hpp.

◆ isnan()

template<std::floating_point T>
Vec< 4, bool > ufo::isnan ( Quat< T > const &  q)
noexcept

Returns a bool vector indicating which components are NaN.

Template Parameters
TFloating-point scalar type.
Parameters
[in]qInput quaternion.
Returns
Vec<4, bool> where element i is true iff component i is NaN.

Definition at line 1010 of file quat.hpp.

◆ logitToProbability()

template<std::floating_point T>
constexpr T ufo::logitToProbability ( logit)
constexpr

Converts logit value to probability.

Template Parameters
TFloating point type (e.g., float, double).
Parameters
[in]logitThe logit value.
Returns
The corresponding probability value in the range [0, 1].

Definition at line 148 of file math.hpp.

◆ mix()

template<std::floating_point T>
Quat< T > ufo::mix ( Quat< T > const &  x,
Quat< T > const &  y,
a 
)

Spherical or linear interpolation between two quaternions.

Falls back to lerp when the quaternions are nearly parallel (cos θ > 1 − ε) to avoid division by near-zero sine.

Template Parameters
TFloating-point scalar type.
Parameters
[in]xStart quaternion.
[in]yEnd quaternion.
[in]aInterpolation factor in [0, 1].
Returns
Interpolated quaternion (not necessarily unit-length if inputs are not).

Definition at line 746 of file quat.hpp.

◆ operator Mat< 3, 3, T >()

template<std::floating_point T = float>
constexpr ufo::Quat< T >::operator Mat< 3, 3, T > ( ) const
inlineexplicitconstexprnoexcept

Converts to a row-major 3×3 rotation matrix.

Returns
Mat<3, 3, T> where m[row][col] = R_{row,col}.

Assumes the quaternion is unit-length.

Definition at line 255 of file quat.hpp.

◆ operator Mat< Dim, Dim, U >()

template<std::size_t Dim, std::floating_point T = float>
template<std::floating_point U>
constexpr ufo::Transform< Dim, T >::operator Mat< Dim, Dim, U > ( ) const
inlineexplicitconstexpr

Extracts the rotation component as a Dim × Dim matrix.

Template Parameters
UTarget scalar type.
Returns
A copy of the rotation matrix converted to U.

Definition at line 275 of file transform.hpp.

◆ operator()()

template<std::size_t Dim, std::floating_point T = float>
template<std::floating_point U>
constexpr Vec< Dim, U > ufo::Transform< Dim, T >::operator() ( Vec< Dim, U > const &  v) const
inlineconstexpr

Applies the transform to a vector: result = R * v + t.

Template Parameters
UScalar type of the vector (may differ from T).
Parameters
[in]vInput vector.
Returns
Transformed vector.

Definition at line 323 of file transform.hpp.

◆ operator*() [1/3]

template<std::size_t Rows, std::size_t Cols, class T >
constexpr Vec< Rows, T > ufo::operator* ( Mat< Rows, Cols, T > const &  m,
Vec< Cols, T > const &  v 
)
constexprnoexcept

Multiplies a matrix by a column vector (M * v).

Template Parameters
RowsNumber of rows in m.
ColsNumber of columns in m (equals the dimension of v).
TElement type.
Parameters
[in]mLeft-hand side matrix.
[in]vColumn vector.
Returns
A Vec<Rows, T> where element r is dot(m.row(r), v).

Definition at line 975 of file mat.hpp.

◆ operator*() [2/3]

template<std::size_t Rows, std::size_t Shared, std::size_t Cols, class T >
constexpr Mat< Rows, Cols, T > ufo::operator* ( Mat< Rows, Shared, T > const &  a,
Mat< Shared, Cols, T > const &  b 
)
constexprnoexcept

Matrix × matrix product.

Computes the standard matrix product a * b via the triple-loop formula. The number of columns in a must equal the number of rows in b (Shared).

Template Parameters
RowsNumber of rows in a (and in the result).
SharedInner dimension: columns of a and rows of b.
ColsNumber of columns in b (and in the result).
TElement type.
Parameters
[in]aLeft-hand side matrix of shape Rows × Shared.
[in]bRight-hand side matrix of shape Shared × Cols.
Returns
A Mat<Rows, Cols, T> where result[r][c] = sum_k a[r][k] * b[k][c].

Definition at line 1027 of file mat.hpp.

◆ operator*() [3/3]

template<std::size_t Dim, std::floating_point T>
constexpr Transform< Dim, T > ufo::operator* ( Transform< Dim, T >  t1,
Transform< Dim, T > const &  t2 
)
constexpr

Composes two transforms: (t1 * t2)(v) = t1(t2(v)).

Template Parameters
DimSpatial dimension (2 or 3).
TFloating-point scalar type.
Parameters
[in]t1Outer transform.
[in]t2Inner transform.
Returns
The composed transform.

Definition at line 406 of file transform.hpp.

◆ operator+() [1/8]

template<std::size_t Rows, std::size_t Cols, class T >
constexpr Mat ufo::Mat< Rows, Cols, T >::operator+ ( ) const
inlineconstexprnoexcept

Unary identity operator.

Returns
A copy of this matrix, unchanged.

Definition at line 639 of file mat.hpp.

◆ operator+() [2/8]

template<std::size_t Dim, class T >
constexpr Vec ufo::Vec< Dim, T >::operator+ ( ) const
inlineconstexprnoexcept

Unary identity operator.

Returns
A copy of this vector, unchanged.

Definition at line 219 of file vec.hpp.

◆ operator+() [3/8]

template<std::size_t Rows, std::size_t Cols, class T >
constexpr Mat< Rows, Cols, T > ufo::operator+ ( Mat< Rows, Cols, T >  lhs,
Mat< Rows, Cols, T > const &  rhs 
)
constexprnoexcept

Element-wise addition of two matrices.

Template Parameters
RowsNumber of rows.
ColsNumber of columns.
TElement type.
Parameters
[in]lhsLeft-hand side matrix.
[in]rhsRight-hand side matrix.
Returns
A matrix whose element [r][c] is lhs[r][c] + rhs[r][c].

Definition at line 789 of file mat.hpp.

◆ operator+() [4/8]

template<std::size_t Rows, std::size_t Cols, class T >
constexpr Mat< Rows, Cols, T > ufo::operator+ ( Mat< Rows, Cols, T >  lhs,
rhs 
)
constexprnoexcept

Adds scalar rhs to every element of lhs.

Template Parameters
RowsNumber of rows.
ColsNumber of columns.
TElement type.
Parameters
[in]lhsLeft-hand side matrix.
[in]rhsScalar value.
Returns
A matrix whose element [r][c] is lhs[r][c] + rhs.

Definition at line 829 of file mat.hpp.

◆ operator+() [5/8]

template<std::floating_point T>
constexpr Quat< T > ufo::operator+ ( Quat< T > const &  q)
constexprnoexcept

Unary plus — returns a copy of q unchanged.

Template Parameters
TFloating-point scalar type.
Parameters
[in]qInput quaternion.
Returns
q.

Definition at line 443 of file quat.hpp.

◆ operator+() [6/8]

template<std::floating_point T>
constexpr Quat< T > ufo::operator+ ( Quat< T >  lhs,
Quat< T > const &  rhs 
)
constexprnoexcept

Component-wise addition of two quaternions.

Template Parameters
TFloating-point scalar type.
Parameters
[in]lhsLeft-hand side.
[in]rhsRight-hand side.
Returns
Component-wise sum.

Definition at line 474 of file quat.hpp.

◆ operator+() [7/8]

template<std::size_t Dim, class T >
constexpr Vec< Dim, T > ufo::operator+ ( Vec< Dim, T >  lhs,
rhs 
)
constexprnoexcept

Adds scalar rhs to every component of lhs.

Template Parameters
DimNumber of dimensions.
TElement type.
Parameters
[in]lhsLeft-hand side vector.
[in]rhsScalar value.
Returns
A vector whose element i is lhs[i] + rhs.

Definition at line 734 of file vec.hpp.

◆ operator+() [8/8]

template<std::size_t Dim, class T >
constexpr Vec< Dim, T > ufo::operator+ ( Vec< Dim, T >  lhs,
Vec< Dim, T > const &  rhs 
)
constexprnoexcept

Component-wise addition of two vectors.

Template Parameters
DimNumber of dimensions.
TElement type.
Parameters
[in]lhsLeft-hand side vector.
[in]rhsRight-hand side vector.
Returns
A vector whose element i is lhs[i] + rhs[i].

Definition at line 538 of file vec.hpp.

◆ operator+=() [1/5]

template<std::size_t Rows, std::size_t Cols, class T >
constexpr Mat & ufo::Mat< Rows, Cols, T >::operator+= ( Mat< Rows, Cols, T > const &  rhs)
inlineconstexprnoexcept

Adds rhs element-wise to this matrix.

Parameters
[in]rhsRight-hand side matrix.
Returns
Reference to *this.

Definition at line 663 of file mat.hpp.

◆ operator+=() [2/5]

template<std::floating_point T = float>
constexpr Quat & ufo::Quat< T >::operator+= ( Quat< T > const &  q)
inlineconstexprnoexcept

Component-wise addition.

Parameters
[in]qQuaternion to add.
Returns
Reference to *this.

Definition at line 314 of file quat.hpp.

◆ operator+=() [3/5]

template<std::size_t Rows, std::size_t Cols, class T >
constexpr Mat & ufo::Mat< Rows, Cols, T >::operator+= ( rhs)
inlineconstexprnoexcept

Adds scalar rhs to every element.

Parameters
[in]rhsScalar value.
Returns
Reference to *this.

Definition at line 703 of file mat.hpp.

◆ operator+=() [4/5]

template<std::size_t Dim, class T >
constexpr Vec & ufo::Vec< Dim, T >::operator+= ( rhs)
inlineconstexprnoexcept

Adds scalar rhs to every component.

Parameters
[in]rhsScalar value.
Returns
Reference to *this.

Definition at line 383 of file vec.hpp.

◆ operator+=() [5/5]

template<std::size_t Dim, class T >
constexpr Vec & ufo::Vec< Dim, T >::operator+= ( Vec< Dim, T > const &  rhs)
inlineconstexprnoexcept

Adds each component of rhs to the corresponding component.

Parameters
[in]rhsRight-hand side vector.
Returns
Reference to *this.

Definition at line 255 of file vec.hpp.

◆ operator<<() [1/3]

template<std::size_t Rows, std::size_t Cols, class T >
std::ostream & ufo::operator<< ( std::ostream &  out,
Mat< Rows, Cols, T > const &  m 
)

Writes a matrix to an output stream, one row per line.

Each row is formatted using Vec's operator<<, separated by newlines.

Template Parameters
RowsNumber of rows.
ColsNumber of columns.
TElement type.
Parameters
[in]outOutput stream.
[in]mMatrix to print.
Returns
Reference to out.

Definition at line 1640 of file mat.hpp.

◆ operator<<() [2/3]

template<std::floating_point T>
std::ostream & ufo::operator<< ( std::ostream &  out,
Quat< T > const &  q 
)

Writes the quaternion to an output stream as "qw: W qx: X qy: Y qz: Z".

Template Parameters
TFloating-point scalar type.
Parameters
[in]outOutput stream.
[in]qQuaternion to print.
Returns
Reference to out.

Definition at line 1041 of file quat.hpp.

◆ operator<<() [3/3]

template<std::size_t Dim, class T >
std::ostream & ufo::operator<< ( std::ostream &  out,
Vec< Dim, T > const &  v 
)

Writes a human-readable representation of a vector to a stream.

Template Parameters
DimNumber of dimensions.
TElement type.
Parameters
[in,out]outThe output stream.
[in]vThe vector to print.
Returns
Reference to out.

Outputs each component labeled by its name (x, y, z, w), separated by spaces. Example output for a Vec3f{1, 2, 3}: x: 1 y: 2 z: 3.

Definition at line 1783 of file vec.hpp.

◆ operator=() [1/2]

template<std::floating_point T = float>
constexpr Quat & ufo::Quat< T >::operator= ( Quat< T > const &  )
constexprdefaultnoexcept

Copy assignment operator.

Returns
Reference to *this.

◆ operator=() [2/2]

template<std::size_t Dim, std::floating_point T = float>
constexpr Transform & ufo::Transform< Dim, T >::operator= ( Transform< Dim, T > const &  )
constexprdefaultnoexcept

Default copy assignment operator.

Returns
Reference to *this.

◆ operator[]() [1/3]

template<std::size_t Dim, class T >
constexpr auto & ufo::Vec< Dim, T >::operator[] ( this auto &  self,
size_type  i 
)
inlineconstexprnoexcept

Accesses the element at index i.

Parameters
[in]iZero-based element index.
Returns
Reference to the element (const or non-const, deduced from this).

Definition at line 127 of file vec.hpp.

◆ operator[]() [2/3]

template<std::floating_point T = float>
constexpr auto & ufo::Quat< T >::operator[] ( this auto &  self,
size_type  pos 
)
inlineconstexprnoexcept

Component access by index: 0->w, 1->x, 2->y, 3->z.

Parameters
[in]posComponent index (must be < 4; asserted in debug builds).
Returns
Reference to the selected component (const or non-const, deduced from this).

Definition at line 292 of file quat.hpp.

◆ operator[]() [3/3]

template<std::size_t Rows, std::size_t Cols, class T >
constexpr auto & ufo::Mat< Rows, Cols, T >::operator[] ( this auto &  self,
size_type  r,
size_type  c 
)
inlineconstexprnoexcept

Accesses the element at row r, column c.

Parameters
[in]rRow index.
[in]cColumn index.
Returns
Reference to the element (const or non-const, deduced from this).

Definition at line 232 of file mat.hpp.

◆ orthogonal()

template<std::floating_point T>
Mat< 4, 4, T > ufo::orthogonal ( left,
right,
bottom,
top 
)

Builds a right-handed 2-D orthographic projection matrix (no depth clipping).

Maps the rectangle [left, right] × [bottom, top] to the NDC square [-1, 1]². The resulting matrix has m[2][2] = -1 and m[3][3] = 1.

Template Parameters
TFloating-point element type.
Parameters
[in]leftLeft clipping plane.
[in]rightRight clipping plane.
[in]bottomBottom clipping plane.
[in]topTop clipping plane.
Returns
A Mat<4, 4, T> representing the orthographic projection.

Definition at line 1359 of file mat.hpp.

◆ probabilityToLogit()

template<std::floating_point T>
constexpr T ufo::probabilityToLogit ( probability)
constexpr

Converts probability to logit value.

Template Parameters
TFloating point type (e.g., float, double).
Parameters
[in]probabilityThe probability value in the range [0, 1].
Returns
The corresponding logit value.

Handles edge cases for probability == 0 or probability == 1.

Definition at line 129 of file math.hpp.

◆ radians()

template<std::floating_point T>
constexpr T ufo::radians ( deg)
constexprnoexcept

Converts degrees to radians.

Template Parameters
TFloating point type (e.g., float, double).
Parameters
[in]degThe angle in degrees.
Returns
The angle in radians.

Definition at line 86 of file math.hpp.

◆ roll()

template<std::floating_point T>
T ufo::roll ( Quat< T > const &  q)
noexcept

Extracts the roll angle (rotation about the X-axis) in radians.

Template Parameters
TFloating-point scalar type.
Parameters
[in]qUnit quaternion.
Returns
Roll angle in [-π, π].

Definition at line 905 of file quat.hpp.

◆ rotate()

template<std::floating_point T>
Quat< T > ufo::rotate ( Quat< T > const &  q,
angle,
Vec< 3, T >  axis 
)

Appends an angle-axis rotation to a quaternion.

Computes q * angleAxis(angle, axis), normalising axis only if it deviates from unit length by more than 0.001.

Template Parameters
TFloating-point scalar type.
Parameters
[in]qBase unit quaternion.
[in]angleAdditional rotation angle in radians.
[in]axisRotation axis (normalised internally if needed).
Returns
Resulting unit quaternion.

Definition at line 965 of file quat.hpp.

◆ sign()

template<class T >
constexpr int ufo::sign ( val)
constexprnoexcept

Returns the sign of a value.

Template Parameters
TNumeric type (e.g., int, float).
Parameters
[in]valThe value to check.
Return values
-1val < 0
0val == 0
1val > 0

Definition at line 70 of file math.hpp.

◆ size()

template<std::floating_point T = float>
static constexpr size_type ufo::Quat< T >::size ( )
inlinestaticconstexprnoexcept

Returns the number of components (always 4: w, x, y, z).

Returns
4.

Definition at line 390 of file quat.hpp.

◆ swap() [1/2]

template<std::floating_point T = float>
void ufo::Quat< T >::swap ( Quat< T > &  other)
inlinenoexcept

Swaps all components with other.

Parameters
[in]otherQuaternion to swap with.

Definition at line 402 of file quat.hpp.

◆ swap() [2/2]

template<std::floating_point T>
void ufo::swap ( Quat< T > &  lhs,
Quat< T > &  rhs 
)
noexcept

Non-member swap — exchanges all components of lhs and rhs.

Template Parameters
TFloating-point scalar type.
Parameters
[in]lhsFirst quaternion.
[in]rhsSecond quaternion.

Definition at line 624 of file quat.hpp.

◆ trace()

template<std::size_t Rows, std::size_t Cols, class T >
constexpr T ufo::Mat< Rows, Cols, T >::trace ( ) const
inlineconstexprnoexcept

Computes the trace (sum of diagonal elements) of a square matrix.

Returns
fields[0][0] + fields[1][1] + ... + fields[N-1][N-1].

Definition at line 345 of file mat.hpp.