PX4 Firmware
PX4 Autopilot Software http://px4.io
matrix Namespace Reference

Namespaces

 typeFunction
 

Classes

class  AxisAngle
 AxisAngle class. More...
 
class  Dcm
 Direction cosine matrix class. More...
 
struct  Dual
 
class  Euler
 Euler angles class. More...
 
class  GeninvImpl
 Geninv implementation detail. More...
 
class  GeninvImpl< Type, M, N, 0 >
 
class  LeastSquaresSolver
 
class  Matrix
 
class  Quaternion
 Quaternion class. More...
 
class  Scalar
 
class  Slice
 
class  SquareMatrix
 
class  Vector
 
class  Vector2
 
class  Vector3
 

Typedefs

typedef AxisAngle< float > AxisAnglef
 
typedef Dcm< float > Dcmf
 
typedef Euler< float > Eulerf
 
typedef Quaternion< float > Quatf
 
typedef Quaternion< float > Quaternionf
 
typedef Scalar< float > Scalarf
 
typedef SquareMatrix< float, 3 > SquareMatrix3f
 
typedef SquareMatrix< float, 3 > Matrix3f
 
typedef Vector2< float > Vector2f
 
typedef Vector3< float > Vector3f
 

Functions

template<typename Scalar , size_t N>
Dual< Scalar, N > operator+ (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator- (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator+ (const Dual< Scalar, N > &a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator- (const Dual< Scalar, N > &a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator+ (const Dual< Scalar, N > &a, Scalar b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator- (const Dual< Scalar, N > &a, Scalar b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator+ (Scalar a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator- (Scalar a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator* (const Dual< Scalar, N > &a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator* (const Dual< Scalar, N > &a, Scalar b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator* (Scalar a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator/ (const Dual< Scalar, N > &a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator/ (const Dual< Scalar, N > &a, Scalar b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > operator/ (Scalar a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > sqrt (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > abs (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > ceil (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > floor (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > fmod (const Dual< Scalar, N > &a, Scalar mod)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > max (const Dual< Scalar, N > &a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > min (const Dual< Scalar, N > &a, const Dual< Scalar, N > &b)
 
template<typename Scalar >
bool IsNan (Scalar a)
 
template<typename Scalar , size_t N>
bool IsNan (const Dual< Scalar, N > &a)
 
template<typename Scalar >
bool IsFinite (Scalar a)
 
template<typename Scalar , size_t N>
bool IsFinite (const Dual< Scalar, N > &a)
 
template<typename Scalar >
bool IsInf (Scalar a)
 
template<typename Scalar , size_t N>
bool IsInf (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > sin (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > cos (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > tan (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > asin (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > acos (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > atan (const Dual< Scalar, N > &a)
 
template<typename Scalar , size_t N>
Dual< Scalar, N > atan2 (const Dual< Scalar, N > &a, const Dual< Scalar, N > &b)
 
template<typename Scalar , size_t M, size_t N>
Matrix< Scalar, M, N > collectDerivatives (const Matrix< Dual< Scalar, N >, M, 1 > &input)
 
template<typename Scalar , size_t M, size_t N, size_t D>
Matrix< Scalar, M, N > collectReals (const Matrix< Dual< Scalar, D >, M, N > &input)
 
template<typename Type , size_t M, size_t N>
int kalman_correct (const Matrix< Type, M, M > &P, const Matrix< Type, N, M > &C, const Matrix< Type, N, N > &R, const Matrix< Type, N, 1 > &r, Matrix< Type, M, 1 > &dx, Matrix< Type, M, M > &dP, Type &beta)
 
template<typename Type >
bool is_finite (Type x)
 
template<typename Type >
bool isEqualF (const Type x, const Type y, const Type eps=1e-4f)
 Compare if two floating point numbers are equal. More...
 
template<typename Type >
Type wrap (Type x, Type low, Type high)
 Wrap value to stay in range [low, high) More...
 
template<typename Type >
Type wrap_pi (Type x)
 Wrap value in range [-π, π) More...
 
template<typename Type >
Type wrap_2pi (Type x)
 Wrap value in range [0, 2π) More...
 
template<typename Type , size_t M, size_t N>
int integrate_rk4 (Vector< Type, M >(*f)(Type, const Matrix< Type, M, 1 > &x, const Matrix< Type, N, 1 > &u), const Matrix< Type, M, 1 > &y0, const Matrix< Type, N, 1 > &u, Type t0, Type tf, Type h0, Matrix< Type, M, 1 > &y1)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > zeros ()
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > ones ()
 
template<size_t M, size_t N>
Matrix< float, M, N > nans ()
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > operator* (Type scalar, const Matrix< Type, M, N > &other)
 
template<typename Type , size_t M, size_t N>
bool isEqual (const Matrix< Type, M, N > &x, const Matrix< Type, M, N > &y, const Type eps=1e-4f)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > min (const Matrix< Type, M, N > &x, const Type scalar_upper_bound)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > min (const Type scalar_upper_bound, const Matrix< Type, M, N > &x)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > min (const Matrix< Type, M, N > &x1, const Matrix< Type, M, N > &x2)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > max (const Matrix< Type, M, N > &x, const Type scalar_lower_bound)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > max (const Type scalar_lower_bound, const Matrix< Type, M, N > &x)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > max (const Matrix< Type, M, N > &x1, const Matrix< Type, M, N > &x2)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > constrain (const Matrix< Type, M, N > &x, const Type scalar_lower_bound, const Type scalar_upper_bound)
 
template<typename Type , size_t M, size_t N>
Matrix< Type, M, N > constrain (const Matrix< Type, M, N > &x, const Matrix< Type, M, N > &x_lower_bound, const Matrix< Type, M, N > &x_upper_bound)
 
template<typename Type , size_t N>
SquareMatrix< Type, N > fullRankCholesky (const SquareMatrix< Type, N > &A, size_t &rank)
 Full rank Cholesky factorization of A. More...
 
template<typename Type , size_t M, size_t N>
Matrix< Type, N, M > geninv (const Matrix< Type, M, N > &G)
 Geninv Fast pseudoinverse based on full rank cholesky factorisation. More...
 
template<typename Type >
void fullRankCholeskyTolerance (Type &tol)
 Full rank Cholesky factorization of A. More...
 
template<>
void fullRankCholeskyTolerance< double > (double &tol)
 
template<typename Type , size_t M>
SquareMatrix< Type, M > eye ()
 
template<typename Type , size_t M>
SquareMatrix< Type, M > diag (Vector< Type, M > d)
 
template<typename Type , size_t M>
SquareMatrix< Type, M > expm (const Matrix< Type, M, M > &A, size_t order=5)
 
template<typename Type , size_t M>
bool inv (const SquareMatrix< Type, M > &A, SquareMatrix< Type, M > &inv)
 inverse based on LU factorization with partial pivotting More...
 
template<typename Type , size_t M>
SquareMatrix< Type, M > inv (const SquareMatrix< Type, M > &A)
 inverse based on LU factorization with partial pivotting More...
 
template<typename Type , size_t M>
SquareMatrix< Type, M > cholesky (const SquareMatrix< Type, M > &A)
 cholesky decomposition More...
 
template<typename Type , size_t M>
SquareMatrix< Type, M > choleskyInv (const SquareMatrix< Type, M > &A)
 cholesky inverse More...
 

Typedef Documentation

◆ AxisAnglef

typedef AxisAngle<float> matrix::AxisAnglef

Definition at line 160 of file AxisAngle.hpp.

◆ Dcmf

typedef Dcm<float> matrix::Dcmf

Definition at line 185 of file Dcm.hpp.

◆ Eulerf

typedef Euler<float> matrix::Eulerf

Definition at line 156 of file Euler.hpp.

◆ Matrix3f

typedef SquareMatrix<float, 3> matrix::Matrix3f

Definition at line 351 of file SquareMatrix.hpp.

◆ Quaternionf

Definition at line 545 of file Quaternion.hpp.

◆ Quatf

typedef Quaternion<float> matrix::Quatf

Definition at line 544 of file Quaternion.hpp.

◆ Scalarf

typedef Scalar<float> matrix::Scalarf

Definition at line 53 of file Scalar.hpp.

◆ SquareMatrix3f

Definition at line 123 of file SquareMatrix.hpp.

◆ Vector2f

typedef Vector2<float> matrix::Vector2f

Definition at line 69 of file Vector2.hpp.

◆ Vector3f

typedef Vector3<float> matrix::Vector3f

Definition at line 136 of file Vector3.hpp.

Function Documentation

◆ abs()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::abs ( const Dual< Scalar, N > &  a)

◆ acos()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::acos ( const Dual< Scalar, N > &  a)

Definition at line 309 of file Dual.hpp.

References matrix::Dual< Scalar, N >::derivative, sqrt(), and matrix::Dual< Scalar, N >::value.

Referenced by matrix::AxisAngle< Type >::AxisAngle(), main(), map_projection_project(), and MicroBenchMath::MicroBenchMath::time_double_precision_float_trig().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ asin()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::asin ( const Dual< Scalar, N > &  a)

Definition at line 301 of file Dual.hpp.

References matrix::Dual< Scalar, N >::derivative, sqrt(), and matrix::Dual< Scalar, N >::value.

Referenced by matrix::Euler< Type >::Euler(), main(), map_projection_reproject(), MicroBenchMath::MicroBenchMath::time_double_precision_float_trig(), and waypoint_from_heading_and_distance().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ atan()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::atan ( const Dual< Scalar, N > &  a)

Definition at line 317 of file Dual.hpp.

References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.

Referenced by main().

Here is the caller graph for this function:

◆ atan2()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::atan2 ( const Dual< Scalar, N > &  a,
const Dual< Scalar, N > &  b 
)

◆ ceil()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::ceil ( const Dual< Scalar, N > &  a)

Definition at line 203 of file Dual.hpp.

References matrix::Dual< Scalar, N >::value.

Referenced by CollisionPrevention::_addObstacleSensorData(), float2SigExp(), main(), and TEST_F().

Here is the caller graph for this function:

◆ cholesky()

template<typename Type , size_t M>
SquareMatrix<Type, M> matrix::cholesky ( const SquareMatrix< Type, M > &  A)

cholesky decomposition

Note: A must be positive definite

Definition at line 306 of file SquareMatrix.hpp.

References sqrt().

Referenced by choleskyInv(), and main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ choleskyInv()

template<typename Type , size_t M>
SquareMatrix<Type, M> matrix::choleskyInv ( const SquareMatrix< Type, M > &  A)

cholesky inverse

TODO: Check if gaussian elimination jumps straight to back-substitution for L or we need to do it manually. Will impact speed otherwise.

Definition at line 345 of file SquareMatrix.hpp.

References cholesky(), inv(), and matrix::Matrix< Type, M, M >::T().

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ collectDerivatives()

template<typename Scalar , size_t M, size_t N>
Matrix<Scalar, M, N> matrix::collectDerivatives ( const Matrix< Dual< Scalar, N >, M, 1 > &  input)

Definition at line 334 of file Dual.hpp.

References matrix::Matrix< Type, M, N >::row().

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ collectReals()

template<typename Scalar , size_t M, size_t N, size_t D>
Matrix<Scalar, M, N> matrix::collectReals ( const Matrix< Dual< Scalar, D >, M, N > &  input)

Definition at line 345 of file Dual.hpp.

References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.

Referenced by main().

Here is the caller graph for this function:

◆ constrain() [1/2]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::constrain ( const Matrix< Type, M, N > &  x,
const Type  scalar_lower_bound,
const Type  scalar_upper_bound 
)

Definition at line 684 of file Matrix.hpp.

References matrix::typeFunction::constrain(), and matrix::Matrix< Type, M, N >::setNaN().

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ constrain() [2/2]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::constrain ( const Matrix< Type, M, N > &  x,
const Matrix< Type, M, N > &  x_lower_bound,
const Matrix< Type, M, N > &  x_upper_bound 
)

Definition at line 701 of file Matrix.hpp.

References matrix::typeFunction::constrain().

Here is the call graph for this function:

◆ cos()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::cos ( const Dual< Scalar, N > &  a)

◆ diag()

template<typename Type , size_t M>
SquareMatrix<Type, M> matrix::diag ( Vector< Type, M >  d)

Definition at line 133 of file SquareMatrix.hpp.

Referenced by main(), Sih::parameters_updated(), and MatrixTest::vectorAssignmentTests().

Here is the caller graph for this function:

◆ expm()

template<typename Type , size_t M>
SquareMatrix<Type, M> matrix::expm ( const Matrix< Type, M, M > &  A,
size_t  order = 5 
)

Definition at line 142 of file SquareMatrix.hpp.

References matrix::Matrix< Type, M, M >::setIdentity().

Referenced by main(), and MatrixTest::squareMatrixTests().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ eye()

template<typename Type , size_t M>
SquareMatrix<Type, M> matrix::eye ( )

Definition at line 126 of file SquareMatrix.hpp.

References matrix::Matrix< Type, M, M >::setIdentity().

Here is the call graph for this function:

◆ floor()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::floor ( const Dual< Scalar, N > &  a)

Definition at line 210 of file Dual.hpp.

References matrix::Dual< Scalar, N >::value.

Referenced by CollisionPrevention::_adaptSetpointDirection(), CollisionPrevention::_addDistanceSensorData(), CollisionPrevention::_calculateConstrainedSetpoint(), float2SigExp(), main(), TEST_F(), and wrap().

Here is the caller graph for this function:

◆ fmod()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::fmod ( const Dual< Scalar, N > &  a,
Scalar  mod 
)

Definition at line 217 of file Dual.hpp.

References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.

Referenced by main().

Here is the caller graph for this function:

◆ fullRankCholesky()

template<typename Type , size_t N>
SquareMatrix< Type, N > matrix::fullRankCholesky ( const SquareMatrix< Type, N > &  A,
size_t &  rank 
)

Full rank Cholesky factorization of A.

Definition at line 28 of file PseudoInverse.hpp.

Referenced by geninv().

Here is the caller graph for this function:

◆ fullRankCholeskyTolerance()

template<typename Type >
void matrix::fullRankCholeskyTolerance ( Type &  tol)

Full rank Cholesky factorization of A.

Definition at line 16 of file PseudoInverse.hpp.

Referenced by main().

Here is the caller graph for this function:

◆ fullRankCholeskyTolerance< double >()

template<>
void matrix::fullRankCholeskyTolerance< double > ( double &  tol)
inline

Definition at line 22 of file PseudoInverse.hpp.

◆ geninv()

template<typename Type , size_t M, size_t N>
Matrix<Type, N, M> matrix::geninv ( const Matrix< Type, M, N > &  G)

Geninv Fast pseudoinverse based on full rank cholesky factorisation.

Courrieu, P. (2008). Fast Computation of Moore-Penrose Inverse Matrices, 8(2), 25–29. http://arxiv.org/abs/0804.4809

Definition at line 34 of file PseudoInverse.hpp.

References fullRankCholesky(), matrix::GeninvImpl< Type, M, N, R >::genInvOverdetermined(), matrix::GeninvImpl< Type, M, N, R >::genInvUnderdetermined(), and matrix::Matrix< Type, M, N >::transpose().

Referenced by main(), MatrixTest::pseudoInverseTests(), and MicroBenchMatrix::ut_declare_test_c().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ integrate_rk4()

template<typename Type , size_t M, size_t N>
int matrix::integrate_rk4 ( Vector< Type, M >(*)(Type, const Matrix< Type, M, 1 > &x, const Matrix< Type, N, 1 > &u)  f,
const Matrix< Type, M, 1 > &  y0,
const Matrix< Type, N, 1 > &  u,
Type  t0,
Type  tf,
Type  h0,
Matrix< Type, M, 1 > &  y1 
)

Definition at line 8 of file integration.hpp.

References f(), and t1.

Referenced by MatrixTest::integrationTests(), and main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ inv() [1/2]

template<typename Type , size_t M>
bool matrix::inv ( const SquareMatrix< Type, M > &  A,
SquareMatrix< Type, M > &  inv 
)

inverse based on LU factorization with partial pivotting

Definition at line 162 of file SquareMatrix.hpp.

References f(), FLT_EPSILON, is_finite(), P, matrix::Matrix< Type, M, M >::setIdentity(), matrix::Matrix< Type, M, M >::swapCols(), and matrix::Matrix< Type, M, M >::swapRows().

Referenced by choleskyInv(), matrix::SquareMatrix< Type, 3 >::I(), inv(), inverse4x4(), MatrixTest::inverseTests(), main(), Sih::parameters_updated(), and MatrixTest::pseudoInverseTests().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ inv() [2/2]

template<typename Type , size_t M>
SquareMatrix<Type, M> matrix::inv ( const SquareMatrix< Type, M > &  A)

inverse based on LU factorization with partial pivotting

Definition at line 289 of file SquareMatrix.hpp.

References inv(), and matrix::Matrix< Type, M, M >::setZero().

Here is the call graph for this function:

◆ is_finite()

template<typename Type >
bool matrix::is_finite ( Type  x)

Definition at line 13 of file helper_functions.hpp.

Referenced by inv(), and main().

Here is the caller graph for this function:

◆ isEqual()

template<typename Type , size_t M, size_t N>
bool matrix::isEqual ( const Matrix< Type, M, N > &  x,
const Matrix< Type, M, N > &  y,
const Type  eps = 1e-4f 
)

Definition at line 571 of file Matrix.hpp.

References isEqualF().

Referenced by MatrixTest::filterTests(), MatrixTest::helperTests(), MatrixTest::integrationTests(), main(), MatrixTest::matrixAssignmentTests(), MatrixTest::matrixMultTests(), MatrixTest::matrixScalarMultTests(), matrix::Matrix< float, n_x, n_u >::operator==(), MatrixTest::run_tests(), MatrixTest::sliceTests(), MatrixTest::squareMatrixTests(), test_4x3(), test_4x4(), test_div_zero(), MatrixTest::transposeTests(), MatrixTest::vector3Tests(), and MatrixTest::vectorTests().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isEqualF()

template<typename Type >
bool matrix::isEqualF ( const Type  x,
const Type  y,
const Type  eps = 1e-4f 
)

Compare if two floating point numbers are equal.

NAN is considered equal to NAN and -NAN INFINITY is considered equal INFINITY but not -INFINITY

Parameters
xright side of equality check
yleft side of equality check
epsnumerical tolerance of the check
Returns
true if the two values are considered equal, false otherwise

Definition at line 35 of file helper_functions.hpp.

Referenced by isEqual(), isEqualAll(), main(), and matrix::LeastSquaresSolver< Type, M, N >::solve().

Here is the caller graph for this function:

◆ IsFinite() [1/2]

template<typename Scalar >
bool matrix::IsFinite ( Scalar  a)

Definition at line 251 of file Dual.hpp.

Referenced by IsFinite(), and main().

Here is the caller graph for this function:

◆ IsFinite() [2/2]

template<typename Scalar , size_t N>
bool matrix::IsFinite ( const Dual< Scalar, N > &  a)

Definition at line 257 of file Dual.hpp.

References IsFinite(), and matrix::Dual< Scalar, N >::value.

Here is the call graph for this function:

◆ IsInf() [1/2]

template<typename Scalar >
bool matrix::IsInf ( Scalar  a)

Definition at line 264 of file Dual.hpp.

Referenced by IsInf(), and main().

Here is the caller graph for this function:

◆ IsInf() [2/2]

template<typename Scalar , size_t N>
bool matrix::IsInf ( const Dual< Scalar, N > &  a)

Definition at line 270 of file Dual.hpp.

References IsInf(), and matrix::Dual< Scalar, N >::value.

Here is the call graph for this function:

◆ IsNan() [1/2]

template<typename Scalar >
bool matrix::IsNan ( Scalar  a)

Definition at line 238 of file Dual.hpp.

Referenced by IsNan(), and main().

Here is the caller graph for this function:

◆ IsNan() [2/2]

template<typename Scalar , size_t N>
bool matrix::IsNan ( const Dual< Scalar, N > &  a)

Definition at line 244 of file Dual.hpp.

References IsNan(), and matrix::Dual< Scalar, N >::value.

Here is the call graph for this function:

◆ kalman_correct()

template<typename Type , size_t M, size_t N>
int matrix::kalman_correct ( const Matrix< Type, M, M > &  P,
const Matrix< Type, N, M > &  C,
const Matrix< Type, N, N > &  R,
const Matrix< Type, N, 1 > &  r,
Matrix< Type, M, 1 > &  dx,
Matrix< Type, M, M > &  dP,
Type &  beta 
)

Definition at line 8 of file filter.hpp.

References matrix::Matrix< Type, M, N >::T().

Here is the call graph for this function:

◆ max() [1/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::max ( const Dual< Scalar, N > &  a,
const Dual< Scalar, N > &  b 
)

Definition at line 224 of file Dual.hpp.

References matrix::Dual< Scalar, N >::value.

Referenced by FlightTaskAutoLineSmoothVel::_constrainOneSide(), ControlMath::constrainXY(), MatrixTest::inverseTests(), main(), MatrixTest::pseudoInverseTests(), PositionControl::setThrustLimits(), MatrixTest::squareMatrixTests(), and TEST().

Here is the caller graph for this function:

◆ max() [2/4]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::max ( const Matrix< Type, M, N > &  x,
const Type  scalar_lower_bound 
)

Definition at line 657 of file Matrix.hpp.

References matrix::typeFunction::max().

Here is the call graph for this function:

◆ max() [3/4]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::max ( const Type  scalar_lower_bound,
const Matrix< Type, M, N > &  x 
)

Definition at line 668 of file Matrix.hpp.

References matrix::Matrix< Type, M, N >::max().

Here is the call graph for this function:

◆ max() [4/4]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::max ( const Matrix< Type, M, N > &  x1,
const Matrix< Type, M, N > &  x2 
)

Definition at line 673 of file Matrix.hpp.

References matrix::typeFunction::max().

Here is the call graph for this function:

◆ min() [1/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::min ( const Dual< Scalar, N > &  a,
const Dual< Scalar, N > &  b 
)

Definition at line 231 of file Dual.hpp.

References matrix::Dual< Scalar, N >::value.

Referenced by FlightTaskAutoLineSmoothVel::_constrainOneSide(), main(), and PositionControl::setThrustLimits().

Here is the caller graph for this function:

◆ min() [2/4]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::min ( const Matrix< Type, M, N > &  x,
const Type  scalar_upper_bound 
)

Definition at line 630 of file Matrix.hpp.

References matrix::typeFunction::min().

Here is the call graph for this function:

◆ min() [3/4]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::min ( const Type  scalar_upper_bound,
const Matrix< Type, M, N > &  x 
)

Definition at line 641 of file Matrix.hpp.

References matrix::Matrix< Type, M, N >::min().

Here is the call graph for this function:

◆ min() [4/4]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::min ( const Matrix< Type, M, N > &  x1,
const Matrix< Type, M, N > &  x2 
)

Definition at line 646 of file Matrix.hpp.

References matrix::typeFunction::min().

Here is the call graph for this function:

◆ nans()

template<size_t M, size_t N>
Matrix<float, M, N> matrix::nans ( )

Definition at line 558 of file Matrix.hpp.

References matrix::Matrix< Type, M, N >::setNaN().

Here is the call graph for this function:

◆ ones()

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::ones ( )

Definition at line 551 of file Matrix.hpp.

References matrix::Matrix< Type, M, N >::setOne().

Here is the call graph for this function:

◆ operator*() [1/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator* ( const Dual< Scalar, N > &  a,
const Dual< Scalar, N > &  b 
)

◆ operator*() [2/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator* ( const Dual< Scalar, N > &  a,
Scalar  b 
)

◆ operator*() [3/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator* ( Scalar  a,
const Dual< Scalar, N > &  b 
)

Definition at line 158 of file Dual.hpp.

◆ operator*() [4/4]

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::operator* ( Type  scalar,
const Matrix< Type, M, N > &  other 
)

Definition at line 565 of file Matrix.hpp.

◆ operator+() [1/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator+ ( const Dual< Scalar, N > &  a)

Definition at line 98 of file Dual.hpp.

◆ operator+() [2/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator+ ( const Dual< Scalar, N > &  a,
const Dual< Scalar, N > &  b 
)

◆ operator+() [3/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator+ ( const Dual< Scalar, N > &  a,
Scalar  b 
)

◆ operator+() [4/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator+ ( Scalar  a,
const Dual< Scalar, N > &  b 
)

◆ operator-() [1/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator- ( const Dual< Scalar, N > &  a)

◆ operator-() [2/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator- ( const Dual< Scalar, N > &  a,
const Dual< Scalar, N > &  b 
)

Definition at line 116 of file Dual.hpp.

◆ operator-() [3/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator- ( const Dual< Scalar, N > &  a,
Scalar  b 
)

Definition at line 128 of file Dual.hpp.

◆ operator-() [4/4]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator- ( Scalar  a,
const Dual< Scalar, N > &  b 
)

Definition at line 140 of file Dual.hpp.

◆ operator/() [1/3]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator/ ( const Dual< Scalar, N > &  a,
const Dual< Scalar, N > &  b 
)

◆ operator/() [2/3]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator/ ( const Dual< Scalar, N > &  a,
Scalar  b 
)

Definition at line 172 of file Dual.hpp.

◆ operator/() [3/3]

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::operator/ ( Scalar  a,
const Dual< Scalar, N > &  b 
)

◆ sin()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::sin ( const Dual< Scalar, N > &  a)

◆ sqrt()

◆ tan()

template<typename Scalar , size_t N>
Dual<Scalar, N> matrix::tan ( const Dual< Scalar, N > &  a)

Definition at line 293 of file Dual.hpp.

References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.

Referenced by main(), and MicroBenchMath::MicroBenchMath::time_double_precision_float_trig().

Here is the caller graph for this function:

◆ wrap()

template<typename Type >
Type matrix::wrap ( Type  x,
Type  low,
Type  high 
)

Wrap value to stay in range [low, high)

Parameters
xinput possibly outside of the range
lowlower limit of the allowed range
highupper limit of the allowed range
Returns
wrapped value inside the range

Definition at line 51 of file helper_functions.hpp.

References floor().

Referenced by main(), TEST_F(), wrap_2pi(), and wrap_pi().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wrap_2pi()

template<typename Type >
Type matrix::wrap_2pi ( Type  x)

◆ wrap_pi()

◆ zeros()

template<typename Type , size_t M, size_t N>
Matrix<Type, M, N> matrix::zeros ( )

Definition at line 544 of file Matrix.hpp.

References matrix::Matrix< Type, M, N >::setZero().

Here is the call graph for this function: