PX4 Firmware
PX4 Autopilot Software http://px4.io
|
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 AxisAngle<float> matrix::AxisAnglef |
Definition at line 160 of file AxisAngle.hpp.
typedef Dcm<float> matrix::Dcmf |
typedef Euler<float> matrix::Eulerf |
typedef SquareMatrix<float, 3> matrix::Matrix3f |
Definition at line 351 of file SquareMatrix.hpp.
typedef Quaternion<float> matrix::Quaternionf |
Definition at line 545 of file Quaternion.hpp.
typedef Quaternion<float> matrix::Quatf |
Definition at line 544 of file Quaternion.hpp.
typedef Scalar<float> matrix::Scalarf |
Definition at line 53 of file Scalar.hpp.
typedef SquareMatrix<float, 3> matrix::SquareMatrix3f |
Definition at line 123 of file SquareMatrix.hpp.
typedef Vector2<float> matrix::Vector2f |
Definition at line 69 of file Vector2.hpp.
typedef Vector3<float> matrix::Vector3f |
Definition at line 136 of file Vector3.hpp.
Definition at line 196 of file Dual.hpp.
References matrix::Dual< Scalar, N >::value.
Referenced by CollisionPrevention::_adaptSetpointDirection(), build_gps_response(), QMC5883::collect(), HMC5883::collect(), RCTest::crsfTest(), RCTest::dsmTest(), float2SigExp(), MatrixTest::inverseTests(), main(), MixerTest::mixerTest(), BlockLocalPositionEstimator::predict(), MatrixTest::pseudoInverseTests(), Ekf::resetHeight(), LSM303AGR::self_test(), MatrixTest::squareMatrixTests(), TEST_F(), test_ppm_loopback(), test_rc(), and test_time().
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().
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().
Definition at line 317 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Referenced by main().
Dual<Scalar, N> matrix::atan2 | ( | const Dual< Scalar, N > & | a, |
const Dual< Scalar, N > & | b | ||
) |
Definition at line 325 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Referenced by FloatTest::doublePrecisionTests(), GPSHelper::ECEF2lla(), matrix::Euler< Type >::Euler(), get_distance_to_next_waypoint(), get_distance_to_point_global_wgs84(), main(), map_projection_reproject(), Sih::send_gps(), TEST_F(), MicroBenchMath::MicroBenchMath::time_double_precision_float_trig(), matrix::Quaternion< Type >::to_axis_angle(), and waypoint_from_heading_and_distance().
Definition at line 203 of file Dual.hpp.
References matrix::Dual< Scalar, N >::value.
Referenced by CollisionPrevention::_addObstacleSensorData(), float2SigExp(), main(), and TEST_F().
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().
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().
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().
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().
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().
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().
Definition at line 286 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, sin(), and matrix::Dual< Scalar, N >::value.
Referenced by add_vector_to_global_position(), matrix::Dcm< float >::Dcm(), GPSHelper::ECEF2lla(), matrix::Quaternion< Type >::from_axis_angle(), get_bearing_to_next_waypoint(), get_distance_to_arc(), get_distance_to_next_waypoint(), get_distance_to_point_global_wgs84(), get_vector_to_next_waypoint(), get_vector_to_next_waypoint_fast(), main(), map_projection_init_timestamped(), map_projection_project(), map_projection_reproject(), matrix::Quaternion< Type >::Quaternion(), sin(), MicroBenchMath::MicroBenchMath::time_double_precision_float_trig(), and waypoint_from_heading_and_distance().
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().
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().
SquareMatrix<Type, M> matrix::eye | ( | ) |
Definition at line 126 of file SquareMatrix.hpp.
References matrix::Matrix< Type, M, M >::setIdentity().
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().
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().
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().
void matrix::fullRankCholeskyTolerance | ( | Type & | tol | ) |
Full rank Cholesky factorization of A.
Definition at line 16 of file PseudoInverse.hpp.
Referenced by main().
|
inline |
Definition at line 22 of file PseudoInverse.hpp.
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().
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.
Referenced by MatrixTest::integrationTests(), and main().
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().
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().
bool matrix::is_finite | ( | Type | x | ) |
Definition at line 13 of file helper_functions.hpp.
Referenced by inv(), and main().
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().
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
x | right side of equality check |
y | left side of equality check |
eps | numerical tolerance of the check |
Definition at line 35 of file helper_functions.hpp.
Referenced by isEqual(), isEqualAll(), main(), and matrix::LeastSquaresSolver< Type, M, N >::solve().
bool matrix::IsFinite | ( | Scalar | a | ) |
Definition at line 251 of file Dual.hpp.
Referenced by IsFinite(), and main().
Definition at line 257 of file Dual.hpp.
References IsFinite(), and matrix::Dual< Scalar, N >::value.
bool matrix::IsInf | ( | Scalar | a | ) |
Definition at line 270 of file Dual.hpp.
References IsInf(), and matrix::Dual< Scalar, N >::value.
bool matrix::IsNan | ( | Scalar | a | ) |
Definition at line 244 of file Dual.hpp.
References IsNan(), and matrix::Dual< Scalar, N >::value.
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().
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().
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().
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().
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().
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().
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().
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().
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().
Matrix<float, M, N> matrix::nans | ( | ) |
Definition at line 558 of file Matrix.hpp.
References matrix::Matrix< Type, M, N >::setNaN().
Matrix<Type, M, N> matrix::ones | ( | ) |
Definition at line 551 of file Matrix.hpp.
References matrix::Matrix< Type, M, N >::setOne().
Dual<Scalar, N> matrix::operator* | ( | const Dual< Scalar, N > & | a, |
const Dual< Scalar, N > & | b | ||
) |
Definition at line 146 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Dual<Scalar, N> matrix::operator* | ( | const Dual< Scalar, N > & | a, |
Scalar | b | ||
) |
Definition at line 152 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Matrix<Type, M, N> matrix::operator* | ( | Type | scalar, |
const Matrix< Type, M, N > & | other | ||
) |
Definition at line 565 of file Matrix.hpp.
Dual<Scalar, N> matrix::operator+ | ( | const Dual< Scalar, N > & | a, |
const Dual< Scalar, N > & | b | ||
) |
Definition at line 110 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Dual<Scalar, N> matrix::operator+ | ( | const Dual< Scalar, N > & | a, |
Scalar | b | ||
) |
Definition at line 122 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Dual<Scalar, N> matrix::operator+ | ( | Scalar | a, |
const Dual< Scalar, N > & | b | ||
) |
Definition at line 134 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Dual<Scalar, N> matrix::operator- | ( | const Dual< Scalar, N > & | a | ) |
Definition at line 104 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Dual<Scalar, N> matrix::operator/ | ( | const Dual< Scalar, N > & | a, |
const Dual< Scalar, N > & | b | ||
) |
Definition at line 164 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Dual<Scalar, N> matrix::operator/ | ( | Scalar | a, |
const Dual< Scalar, N > & | b | ||
) |
Definition at line 178 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Definition at line 279 of file Dual.hpp.
References cos(), matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Referenced by matrix::AxisAngle< Type >::AxisAngle(), cos(), matrix::Dcm< float >::Dcm(), FloatTest::doublePrecisionTests(), GPSHelper::ECEF2lla(), f(), matrix::Quaternion< Type >::from_axis_angle(), get_bearing_to_next_waypoint(), get_distance_to_arc(), get_distance_to_next_waypoint(), get_distance_to_point_global_wgs84(), get_vector_to_next_waypoint(), main(), map_projection_init_timestamped(), map_projection_project(), map_projection_reproject(), matrix::Quaternion< Type >::Quaternion(), MicroBenchMath::MicroBenchMath::time_double_precision_float_trig(), and waypoint_from_heading_and_distance().
Definition at line 188 of file Dual.hpp.
References matrix::Dual< Scalar, N >::derivative, and matrix::Dual< Scalar, N >::value.
Referenced by acos(), asin(), control::blockRandGaussTest(), cholesky(), GPSHelper::ECEF2lla(), get_distance_to_next_waypoint(), get_distance_to_point_global_wgs84(), insert_values_around_mean(), matrix::LeastSquaresSolver< Type, M, N >::LeastSquaresSolver(), main(), map_projection_reproject(), matrix::Vector< Type, 3 >::norm(), matrix::Slice< Type, P, Q, M, N >::norm(), matrix::Vector< Type, 3 >::sqrt(), MicroBenchMath::MicroBenchMath::time_double_precision_float(), and MicroBenchMath::MicroBenchMath::time_double_precision_float_trig().
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().
Type matrix::wrap | ( | Type | x, |
Type | low, | ||
Type | high | ||
) |
Wrap value to stay in range [low, high)
x | input possibly outside of the range |
low | lower limit of the allowed range |
high | upper limit of the allowed range |
Definition at line 51 of file helper_functions.hpp.
References floor().
Referenced by main(), TEST_F(), wrap_2pi(), and wrap_pi().
Type matrix::wrap_2pi | ( | Type | x | ) |
Wrap value in range [0, 2π)
Definition at line 76 of file helper_functions.hpp.
References M_TWOPI, and wrap().
Referenced by CollisionPrevention::_adaptSetpointDirection(), CollisionPrevention::_addDistanceSensorData(), CollisionPrevention::_calculateConstrainedSetpoint(), create_waypoint_from_line_and_dist(), MavlinkReceiver::handle_message_hil_gps(), main(), MavlinkMissionManager::parse_mavlink_mission_item(), MavlinkStreamVFRHUD::send(), MavlinkStreamGPSRawInt::send(), MavlinkStreamGPS2Raw::send(), MavlinkStreamGlobalPositionInt::send(), TEST_F(), waypoint_from_heading_and_distance(), MavlinkStreamHighLatency2::write_attitude_sp(), MavlinkStreamHighLatency2::write_global_position(), and MavlinkStreamHighLatency2::write_wind_estimate().
Type matrix::wrap_pi | ( | Type | x | ) |
Wrap value in range [-π, π)
Definition at line 67 of file helper_functions.hpp.
Referenced by FlightTaskAuto::_compute_heading_from_2D_vector(), vmount::OutputBase::_handle_position_update(), FlightTaskAuto::_limitYawRate(), ECL_WheelController::control_attitude(), FixedwingPositionControl::control_landing(), Ekf::fuseGpsAntYaw(), Ekf::fuseHeading(), MulticopterAttitudeControl::generate_attitude_setpoint(), get_bearing_to_next_waypoint(), get_distance_to_arc(), get_distance_to_line(), Mission::heading_sp_update(), MatrixTest::helperTests(), MissionBlock::is_mission_item_reached(), main(), ECL_L1_Pos_Controller::nav_bearing(), ECL_L1_Pos_Controller::navigate_heading(), FollowTarget::on_active(), Ekf::resetGpsAntYaw(), GPS::run(), matrix::Quaternion< Type >::to_axis_angle(), AttitudeEstimatorQ::update(), and Standard::update_mc_state().
Matrix<Type, M, N> matrix::zeros | ( | ) |
Definition at line 544 of file Matrix.hpp.
References matrix::Matrix< Type, M, N >::setZero().