MRPT
2.0.1
|
Math C++ library: vectors and matrices, probability distributions, statistics, geometry, etc.
[New in MRPT 2.0.0]
This library is part of MRPT and can be installed in Debian-based systems with:
sudo apt install libmrpt-math-dev
See: Using MRPT from your CMake project
The main classes and concepts associated with this library:
Other important elements:
Classes | |
class | mrpt::math::CAtan2LookUpTable |
A look-up-table (LUT) of atan values for any (x,y) value in a square/rectangular grid of predefined resolution. More... | |
class | mrpt::math::CAtan2LookUpTableMultiRes |
Like CAtan2LookUpTable but with a multiresolution grid for increasingly better accuracy in points nearer to the origin. More... | |
class | mrpt::math::CBinaryRelation< T, U, UIsObject > |
This class models a binary relation through the elements of any given set. More... | |
class | mrpt::math::CHistogram |
This class provides an easy way of computing histograms for unidimensional real valued variables. More... | |
class | mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM > |
An implementation of the Levenberg-Marquardt algorithm for least-square minimization. More... | |
class | mrpt::math::CMatrixB |
This class is a "CSerializable" wrapper for "CMatrixBool". More... | |
class | mrpt::math::CMatrixD |
This class is a "CSerializable" wrapper for "CMatrixDynamic<double>". More... | |
class | mrpt::math::CMatrixDynamic< T > |
This template class provides the basic functionality for a general 2D any-size, resizable container of numerical or non-numerical elements. More... | |
class | mrpt::math::CMatrixF |
This class is a "CSerializable" wrapper for "CMatrixFloat". More... | |
class | mrpt::math::CMatrixFixed< T, ROWS, COLS > |
A compile-time fixed-size numeric matrix container. More... | |
class | mrpt::math::CMonteCarlo< T, NUM, OTHER > |
Montecarlo simulation for experiments in 1D. More... | |
class | mrpt::math::CProbabilityDensityFunction< TDATA, STATE_LEN > |
A generic template for probability density distributions (PDFs). More... | |
class | mrpt::math::CQuaternion< T > |
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector , or alternatively, q = r + ix + jy + kz. More... | |
class | mrpt::math::CSparseMatrix |
A sparse matrix structure, wrapping T. More... | |
class | mrpt::math::CSparseMatrixTemplate< T > |
A sparse matrix container (with cells of any type), with iterators. More... | |
class | mrpt::math::CVectorDynamic< T > |
Template for column vectors of dynamic size, compatible with Eigen. More... | |
class | mrpt::math::KDTreeCapable< Derived, num_t, metric_t > |
A generic adaptor class for providing Nearest Neighbor (NN) lookup via the nanoflann library. More... | |
struct | mrpt::math::matrix_size_t |
Auxiliary class used in CMatrixDynamic:size(), CMatrixDynamic::resize(), CMatrixFixed::size(), CMatrixFixed::resize(), to mimic the behavior of STL-containers. More... | |
class | mrpt::math::MatrixBase< Scalar, Derived > |
Base CRTP class for all MRPT matrices. More... | |
struct | mrpt::math::MatrixBlockSparseCols< Scalar, NROWS, NCOLS, INFO, HAS_REMAP, INDEX_REMAP_MAP_IMPL > |
A templated column-indexed efficient storage of block-sparse Jacobian or Hessian matrices, together with other arbitrary information. More... | |
class | mrpt::math::MatrixVectorBase< Scalar, Derived > |
Base CRTP class for all MRPT vectors and matrices. More... | |
struct | mrpt::math::RobustKernel< KERNEL_TYPE, T > |
struct | mrpt::math::RobustKernel< rkLeastSquares, T > |
No robust kernel, use standard least squares: rho(r) = r^2. More... | |
struct | mrpt::math::RobustKernel< rkPseudoHuber, T > |
Pseudo-huber robust kernel: rho(r) = 2 * delta^2 * ( -1+sqrt( 1+ r^2/delta^2 ) ) More... | |
Namespaces | |
mrpt::math | |
This base provides a set of functions for maths stuff. | |
Modules | |
Lightweight SE(2)/SE(3) types, geometry functions. | |
Lightweight SE(2)/SE(3) data types, geometry functions, etc. | |
Vectors, matrices, linear Algebra | |
Dynamic and fixed-size vectors and matrices, basic linear Algebra. | |
Custom I/O for math containers | |
Statistics functions, probability distributions | |
Filtering algorithms | |
Fourier transform functions | |
Fresnel integrals (`#include | |
<mrpt/math/fresnel.h>`) | |
Interpolation, least-squares fit, splines | |
KD-Trees | |
Vector and matrices mathematical operations | |
and other utilities | |
Find polynomial roots (`#include | |
<mrpt/math/poly_roots.h>`) | |
RANSAC and other model fitting algorithms | |
Gaussian PDF transformation functions | |
Helper functions for MEX & MATLAB | |
Enumerations | |
enum | mrpt::math::TMatrixTextFileFormat { mrpt::math::MATRIX_FORMAT_ENG = 0, mrpt::math::MATRIX_FORMAT_FIXED = 1, mrpt::math::MATRIX_FORMAT_INT = 2 } |
enum | mrpt::math::TRobustKernelType { mrpt::math::rkLeastSquares = 0, mrpt::math::rkPseudoHuber } |
The different types of kernels for usage within a robustified least-squares estimator. More... | |
Functions | |
void | mrpt::math::setEpsilon (double nE) |
Changes the value of the geometric epsilon (default = 1e-5) More... | |
double | mrpt::math::getEpsilon () |
Gets the value of the geometric epsilon (default = 1e-5) More... | |
template<class Derived > | |
const Derived & | mrpt::math::mat2eig (const Eigen::EigenBase< Derived > &m) |
Returns an Eigen-compatible type, despite its argument already is an Eigen matrix, or an mrpt-math matrix/vector. More... | |
template<class VECTORLIKE , class VECTORLIKE2 , class VECTORLIKE3 , class MATRIXLIKE , class USERPARAM > | |
void | mrpt::math::estimateJacobian (const VECTORLIKE &x, const std::function< void(const VECTORLIKE &x, const USERPARAM &y, VECTORLIKE3 &out)> &functor, const VECTORLIKE2 &increments, const USERPARAM &userParam, MATRIXLIKE &out_Jacobian) |
Estimate the Jacobian of a multi-dimensional function around a point "x", using finite differences of a given size in each input dimension. More... | |
Selection of the number format in MatrixVectorBase::saveToTextFile()
Enumerator | |
---|---|
MATRIX_FORMAT_ENG | engineering format 'e' |
MATRIX_FORMAT_FIXED | fixed floating point 'f' |
MATRIX_FORMAT_INT | intergers 'i' |
Definition at line 34 of file MatrixVectorBase.h.
The different types of kernels for usage within a robustified least-squares estimator.
Enumerator | |
---|---|
rkLeastSquares | No robust kernel, use standard least squares: rho(r)= 1/2 * r^2. |
rkPseudoHuber | Pseudo-huber robust kernel. |
Definition at line 23 of file robust_kernels.h.
void mrpt::math::estimateJacobian | ( | const VECTORLIKE & | x, |
const std::function< void(const VECTORLIKE &x, const USERPARAM &y, VECTORLIKE3 &out)> & | functor, | ||
const VECTORLIKE2 & | increments, | ||
const USERPARAM & | userParam, | ||
MATRIXLIKE & | out_Jacobian | ||
) |
Estimate the Jacobian of a multi-dimensional function around a point "x", using finite differences of a given size in each input dimension.
The template argument USERPARAM is for the data can be passed to the functor. If it is not required, set to "int" or any other basic type.
This is a generic template which works with: VECTORLIKE: vector_float, CVectorDouble, CVectorFixed<>, double [N], ... MATRIXLIKE: CMatrixDynamic, CMatrixFixed
Definition at line 31 of file num_jacobian.h.
References ASSERT_, MRPT_END, and MRPT_START.
Referenced by Pose3DTests::check_jacob_expe_e_at_0(), Pose3DTests::check_jacob_LnT_T(), mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute(), mrpt::vision::recompute_errors_and_Jacobians(), mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >::runOneKalmanIteration(), Pose3DQuatTests::test_composePointJacob(), Pose3DTests::test_composePointJacob(), Pose3DTests::test_composePointJacob_se3(), Pose3DQuatTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob_se3(), Pose3DTests::test_Jacob_dAexpeD_de(), Pose3DTests::test_Jacob_dDexpe_de(), Pose3DTests::test_Jacob_dexpeD_de(), SE_traits_tests< POSE_TYPE >::test_jacobs_AB(), SE_traits_tests< POSE_TYPE >::test_jacobs_DinvP1InvP2(), Pose3DQuatTests::test_normalizeJacob(), Pose3DQuatTests::test_sphericalCoords(), Pose3DPDFGaussTests::testCompositionJacobian(), Pose3DQuatPDFGaussTests::testCompositionJacobian(), and mrpt::math::transform_gaussian_linear().
double mrpt::math::getEpsilon | ( | ) |
Gets the value of the geometric epsilon (default = 1e-5)
Definition at line 34 of file geometry.cpp.
References geometryEpsilon.
Referenced by mrpt::math::TLine3D::contains(), mrpt::math::TPolygon3D::contains(), mrpt::math::TLine2D::contains(), mrpt::math::TPlane::contains(), mrpt::math::TSegment3D::contains(), mrpt::math::TSegment2D::contains(), mrpt::math::TPolygon3D::createRegularPolygon(), mrpt::math::TPolygon2D::createRegularPolygon(), mrpt::math::TPlane::distance(), mrpt::math::TLine2D::getAsPose2D(), mrpt::math::TPlane::getAsPose3D(), getHeight(), mrpt::math::TPlane::getUnitaryNormalVector(), mrpt::math::TPolygon2D::isConvex(), mrpt::math::removeRepVertices(), mrpt::math::removeUnusedVertices(), solveEqn(), TEST(), mrpt::math::TLine2D::TLine2D(), mrpt::math::TLine3D::TLine3D(), mrpt::math::TPlane::TPlane(), mrpt::opengl::CCylinder::traceRay(), and mrpt::math::vectorsAreParallel3D().
const Derived& mrpt::math::mat2eig | ( | const Eigen::EigenBase< Derived > & | m | ) |
Returns an Eigen-compatible type, despite its argument already is an Eigen matrix, or an mrpt-math matrix/vector.
Definition at line 20 of file mat2eig.h.
Referenced by mrpt::math::multiply_HCHt(), mrpt::math::multiply_HCHt_scalar(), and mrpt::math::multiply_HtCH_scalar().
void mrpt::math::setEpsilon | ( | double | nE | ) |
Changes the value of the geometric epsilon (default = 1e-5)
Definition at line 35 of file geometry.cpp.
References eps, and geometryEpsilon.
Referenced by TEST().
Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020 |