MRPT
2.0.1
|
Base CRTP class for all MRPT vectors and matrices.
Template methods whose implementation is not in this header file are explicitly instantiated and exported for these derived types:
Scalar
: float
, double
Scalar
: float
, double
, and sizes from 2x2 to 6x6 and 2 to 6, respectively.Definition at line 56 of file MatrixVectorBase.h.
#include <mrpt/math/MatrixVectorBase.h>
Public Member Functions | |
Derived & | mvbDerived () |
const Derived & | mvbDerived () const |
Operations that DO require `#include <Eigen/Dense>` in user code | |
template<int BLOCK_ROWS, int BLOCK_COLS> | |
auto | block (int start_row, int start_col) |
non-const block(): Returns an Eigen::Block reference to the block More... | |
auto | block (int start_row, int start_col, int BLOCK_ROWS, int BLOCK_COLS) |
auto | block (int start_row, int start_col, int BLOCK_ROWS, int BLOCK_COLS) const |
auto | transpose () |
auto | transpose () const |
auto | array () |
auto | array () const |
auto | operator- () const |
template<typename S2 , class D2 > | |
auto | operator+ (const MatrixVectorBase< S2, D2 > &m2) const |
template<typename S2 , class D2 > | |
void | operator+= (const MatrixVectorBase< S2, D2 > &m2) |
template<typename S2 , class D2 > | |
auto | operator- (const MatrixVectorBase< S2, D2 > &m2) const |
template<typename S2 , class D2 > | |
void | operator-= (const MatrixVectorBase< S2, D2 > &m2) |
template<typename S2 , class D2 > | |
auto | operator* (const MatrixVectorBase< S2, D2 > &m2) const |
auto | operator* (const Scalar s) const |
template<int N> | |
CMatrixFixed< Scalar, N, 1 > | tail () const |
template<int N> | |
CMatrixFixed< Scalar, N, 1 > | head () const |
Initialization methods | |
void | fill (const Scalar &val) |
void | setConstant (const Scalar value) |
void | setConstant (size_t nrows, size_t ncols, const Scalar value) |
void | setConstant (size_t nrows, const Scalar value) |
void | assign (const std::size_t N, const Scalar value) |
void | setZero () |
void | setZero (size_t nrows, size_t ncols) |
void | setZero (size_t nrows) |
static Derived | Constant (const Scalar value) |
static Derived | Constant (size_t nrows, size_t ncols, const Scalar value) |
static Derived | Zero () |
static Derived | Zero (size_t nrows, size_t ncols) |
Standalone operations (do NOT require `#include <Eigen/Dense>`) | |
Scalar & | coeffRef (int r, int c) |
const Scalar & | coeff (int r, int c) const |
Scalar | minCoeff () const |
Minimum value in the matrix/vector. More... | |
Scalar | minCoeff (std::size_t &outIndexOfMin) const |
Scalar | minCoeff (std::size_t &rowIdx, std::size_t &colIdx) const |
Scalar | maxCoeff () const |
Maximum value in the matrix/vector. More... | |
Scalar | maxCoeff (std::size_t &outIndexOfMax) const |
Scalar | maxCoeff (std::size_t &rowIdx, std::size_t &colIdx) const |
bool | isSquare () const |
returns true if matrix is NxN More... | |
bool | empty () const |
returns true if matrix/vector has size=0 More... | |
Scalar | norm_inf () const |
Compute the norm-infinite of a vector ($f[ ||{v}||_ $f]), ie the maximum absolute value of the elements. More... | |
Scalar | norm () const |
Compute the L2 norm of a vector/array/matrix (the Euclidean distance to the origin, taking all the elements as a single vector). More... | |
void | operator+= (Scalar s) |
void | operator-= (Scalar s) |
void | operator*= (Scalar s) |
CMatrixDynamic< Scalar > | operator* (const CMatrixDynamic< Scalar > &v) |
Derived | operator+ (const Derived &m2) const |
void | operator+= (const Derived &m2) |
Derived | operator- (const Derived &m2) const |
void | operator-= (const Derived &m2) |
Derived | operator* (const Derived &m2) const |
Scalar | dot (const CVectorDynamic< Scalar > &v) const |
dot product of this \cdot v More... | |
Scalar | dot (const MatrixVectorBase< Scalar, Derived > &v) const |
void | matProductOf_Ab (const CMatrixDynamic< Scalar > &A, const CVectorDynamic< Scalar > &b) |
this = A * b , with A and b a dynamic matrix & vector More... | |
void | matProductOf_Atb (const CMatrixDynamic< Scalar > &A, const CVectorDynamic< Scalar > &b) |
this = AT * b , with A and b a dynamic matrix & vector More... | |
Scalar | sum () const |
Sum of all elements in matrix/vector. More... | |
Scalar | sum_abs () const |
Sum of the absolute value of all elements in matrix/vector. More... | |
std::string | asString () const |
Returns a string representation of the vector/matrix, using Eigen's default settings. More... | |
bool | fromMatlabStringFormat (const std::string &s, mrpt::optional_ref< std::ostream > dump_errors_here=std::nullopt) |
Reads a matrix from a string in Matlab-like format, for example: "[1 0 2; 0 4 -1]" The string must start with '[' and end with ']'. More... | |
std::string | inMatlabFormat (const std::size_t decimal_digits=6) const |
Exports the matrix as a string compatible with Matlab/Octave. More... | |
void | saveToTextFile (const std::string &file, mrpt::math::TMatrixTextFileFormat fileFormat=mrpt::math::MATRIX_FORMAT_ENG, bool appendMRPTHeader=false, const std::string &userHeader=std::string()) const |
Saves the vector/matrix to a file compatible with MATLAB/Octave text format. More... | |
void | loadFromTextFile (std::istream &f) |
Loads a vector/matrix from a text file, compatible with MATLAB text format. More... | |
void | loadFromTextFile (const std::string &file) |
template<typename OTHERMATVEC > | |
bool | operator== (const OTHERMATVEC &o) const |
template<typename OTHERMATVEC > | |
bool | operator!= (const OTHERMATVEC &o) const |
Derived | impl_op_add (const Derived &m2) const |
void | impl_op_selfadd (const Derived &m2) |
Derived | impl_op_subs (const Derived &m2) const |
void | impl_op_selfsubs (const Derived &m2) |
|
inline |
Definition at line 170 of file MatrixVectorBase.h.
Referenced by mrpt::vision::checkerBoardStereoCalibration(), mrpt::slam::CRangeBearingKFSLAM::computeOffDiagonalBlocksApproximationError(), mrpt::random::CRandomGenerator::drawGaussianMultivariate(), mrpt::obs::CActionRobotMovement2D::prepareFastDrawSingleSample_modelGaussian(), mrpt::maps::CLandmarksMap::saveToMATLABScript2D(), and TEST().
|
inline |
Definition at line 175 of file MatrixVectorBase.h.
|
inline |
Definition at line 106 of file MatrixVectorBase.h.
Referenced by mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::obs::CActionRobotMovement2D::fastDrawSingleSample_modelGaussian(), mrpt::slam::CRangeBearingKFSLAM2D::reset(), and mrpt::slam::CRangeBearingKFSLAM::reset().
std::string mrpt::math::MatrixVectorBase< Scalar, Derived >::asString | ( | ) | const |
Returns a string representation of the vector/matrix, using Eigen's default settings.
Definition at line 337 of file MatrixVectorBase_impl.h.
Referenced by mrpt::math::operator<<(), and quat_vs_YPR().
|
inline |
non-const block(): Returns an Eigen::Block reference to the block
Definition at line 138 of file MatrixVectorBase.h.
Referenced by mrpt::poses::CPosePDFSOG::changeCoordinatesReference(), mrpt::poses::CPosePDFGaussian::copyFrom(), mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::math::MatrixBlockSparseCols< Scalar, NROWS, NCOLS, INFO, HAS_REMAP, INDEX_REMAP_MAP_IMPL >::getAsDense(), mrpt::math::TPose3D::getHomogeneousMatrix(), mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(), mrpt::poses::CPointPDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPose3D::serializeFrom(), Pose3DTests::test_composePointJacob(), Pose3DQuatTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob(), Pose3DQuatTests::test_normalizeJacob(), Pose3DQuatTests::test_sphericalCoords(), Pose3DPDFGaussTests::testCompositionJacobian(), and Pose3DQuatPDFGaussTests::testCompositionJacobian().
|
inline |
Definition at line 145 of file MatrixVectorBase.h.
|
inline |
Definition at line 151 of file MatrixVectorBase.h.
|
inline |
Definition at line 244 of file MatrixVectorBase.h.
Referenced by mrpt::obs::detail::do_project_3d_pointcloud(), mrpt::obs::TRangeImageFilter::do_range_filter(), and mrpt::obs::CObservation3DRangeScan::rangeImageAsImage().
|
inline |
Definition at line 243 of file MatrixVectorBase.h.
Referenced by mrpt::obs::detail::do_project_3d_pointcloud(), mrpt::obs::detail::do_project_3d_pointcloud_SSE2(), mrpt::img::CImage::getAsMatrix(), mrpt::img::CImage::getAsRGBMatrices(), and mrpt::vision::CFeature::getFirstDescriptorAsMatrix().
|
inlinestatic |
Definition at line 89 of file MatrixVectorBase.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::Zero().
|
inlinestatic |
Definition at line 99 of file MatrixVectorBase.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::dot | ( | const CVectorDynamic< Scalar > & | v | ) | const |
dot product of this \cdot v
Definition at line 511 of file MatrixVectorBase_impl.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::dot | ( | const MatrixVectorBase< Scalar, Derived > & | v | ) | const |
Definition at line 524 of file MatrixVectorBase_impl.h.
|
inline |
returns true if matrix/vector has size=0
Definition at line 260 of file MatrixVectorBase.h.
|
inline |
Fill all the elements with a given value (Note: named "fillAll" since "fill" will be used by child classes)
Definition at line 70 of file MatrixVectorBase.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::assign(), mrpt::poses::CPose3DQuat::assign(), mrpt::maps::CRandomFieldGridMap2D::exist_relation_between2cells(), mrpt::vision::CFeatureExtraction::extractFeaturesFAST(), mrpt::vision::CFeatureExtraction::extractFeaturesORB(), fillSampleObs(), mrpt::ros1bridge::fromROS(), mrpt::vision::projectMatchedFeatures(), mrpt::obs::CObservation3DRangeScan::recoverCameraCalibrationParameters(), mrpt::obs::CObservationImage::serializeFrom(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::setConstant(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::setZero(), TEST(), TestLevMarq(), and PosePDFGaussTests::testPoseInverse().
bool mrpt::math::MatrixVectorBase< Scalar, Derived >::fromMatlabStringFormat | ( | const std::string & | s, |
mrpt::optional_ref< std::ostream > | dump_errors_here = std::nullopt |
||
) |
Reads a matrix from a string in Matlab-like format, for example: "[1 0 2; 0 4 -1]" The string must start with '[' and end with ']'.
Rows are separated by semicolons ';' and columns in each row by one or more whitespaces ' ' or tabs ''. Commas ',' between elements are NOT allowed.
This format is also used for CConfigFile::read_matrix.
Definition at line 24 of file MatrixVectorBase_impl.h.
Referenced by mrpt::poses::CPoint< CPoint3D, 3 >::fromString(), mrpt::math::TTwist2D::fromString(), mrpt::math::TPose3DQuat::fromString(), mrpt::math::TPose2D::fromString(), mrpt::math::TTwist3D::fromString(), mrpt::math::TPose3D::fromString(), mrpt::poses::CPose3DQuat::fromString(), mrpt::poses::CPose2D::fromString(), mrpt::poses::CPose3D::fromString(), mrpt::nav::PlannerTPS_VirtualBase::internal_loadConfig_PTG(), quat_vs_YPR(), and TEST().
|
inline |
Definition at line 232 of file MatrixVectorBase.h.
|
private |
Definition at line 446 of file MatrixVectorBase_impl.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator+().
|
private |
Definition at line 453 of file MatrixVectorBase_impl.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator+=().
|
private |
Definition at line 465 of file MatrixVectorBase_impl.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator-=().
|
private |
Definition at line 458 of file MatrixVectorBase_impl.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator-().
std::string mrpt::math::MatrixVectorBase< Scalar, Derived >::inMatlabFormat | ( | const std::size_t | decimal_digits = 6 | ) | const |
Exports the matrix as a string compatible with Matlab/Octave.
Definition at line 141 of file MatrixVectorBase_impl.h.
Referenced by mrpt::obs::gnss::Message_TOPCON_PZS::dumpToStream(), mrpt::obs::CObservation6DFeatures::getDescriptionAsText(), mrpt::obs::CObservationStereoImagesFeatures::getDescriptionAsText(), and mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA().
|
inline |
returns true if matrix is NxN
Definition at line 257 of file MatrixVectorBase.h.
Referenced by mrpt::slam::data_association_full_covariance(), mrpt::math::mahalanobisDistance2(), mrpt::math::mahalanobisDistance2AndLogPDF(), mrpt::math::normalPDF(), and op_dense_multiply_AB().
void mrpt::math::MatrixVectorBase< Scalar, Derived >::loadFromTextFile | ( | std::istream & | f | ) |
Loads a vector/matrix from a text file, compatible with MATLAB text format.
Lines starting with '' or '#' are interpreted as comments and ignored.
std::runtime_error | On format error. |
Definition at line 238 of file MatrixVectorBase_impl.h.
Referenced by mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::obs::CObservation3DRangeScan::load(), mrpt::poses::CPoseInterpolatorBase< 3 >::loadFromTextFile(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), and TEST().
void mrpt::math::MatrixVectorBase< Scalar, Derived >::loadFromTextFile | ( | const std::string & | file | ) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 326 of file MatrixVectorBase_impl.h.
void mrpt::math::MatrixVectorBase< Scalar, Derived >::matProductOf_Ab | ( | const CMatrixDynamic< Scalar > & | A, |
const CVectorDynamic< Scalar > & | b | ||
) |
this = A * b , with A
and b
a dynamic matrix & vector
Definition at line 485 of file MatrixVectorBase_impl.h.
void mrpt::math::MatrixVectorBase< Scalar, Derived >::matProductOf_Atb | ( | const CMatrixDynamic< Scalar > & | A, |
const CVectorDynamic< Scalar > & | b | ||
) |
this = AT * b , with A
and b
a dynamic matrix & vector
Definition at line 492 of file MatrixVectorBase_impl.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::maxCoeff | ( | ) | const |
Maximum value in the matrix/vector.
Definition at line 363 of file MatrixVectorBase_impl.h.
Referenced by mrpt::slam::CGridMapAligner::AlignPDF_correlation(), do_matrix_op_test(), and mrpt::obs::CObservation3DRangeScan::rangeImageAsImage().
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::maxCoeff | ( | std::size_t & | outIndexOfMax | ) | const |
Definition at line 384 of file MatrixVectorBase_impl.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::maxCoeff | ( | std::size_t & | rowIdx, |
std::size_t & | colIdx | ||
) | const |
Definition at line 409 of file MatrixVectorBase_impl.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::minCoeff | ( | ) | const |
Minimum value in the matrix/vector.
Definition at line 357 of file MatrixVectorBase_impl.h.
Referenced by mrpt::vision::CFeature::internal_distanceBetweenPolarImages().
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::minCoeff | ( | std::size_t & | outIndexOfMin | ) | const |
Definition at line 369 of file MatrixVectorBase_impl.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::minCoeff | ( | std::size_t & | rowIdx, |
std::size_t & | colIdx | ||
) | const |
Definition at line 398 of file MatrixVectorBase_impl.h.
|
inline |
Definition at line 59 of file MatrixVectorBase.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::array(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::assign(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::block(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::coeff(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::coeffRef(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::dot(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::empty(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::fill(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::head(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::isSquare(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator*(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator+(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator+=(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator-(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator-=(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::operator==(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::setConstant(), mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::tail(), and mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::transpose().
|
inline |
Definition at line 60 of file MatrixVectorBase.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::norm | ( | ) | const |
Compute the L2 norm of a vector/array/matrix (the Euclidean distance to the origin, taking all the elements as a single vector).
Definition at line 505 of file MatrixVectorBase_impl.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::norm_inf | ( | ) | const |
Compute the norm-infinite of a vector ($f[ ||{v}||_ $f]), ie the maximum absolute value of the elements.
Definition at line 499 of file MatrixVectorBase_impl.h.
|
inline |
Definition at line 432 of file MatrixVectorBase.h.
|
inline |
Definition at line 214 of file MatrixVectorBase.h.
|
inline |
Definition at line 219 of file MatrixVectorBase.h.
CMatrixDynamic< Scalar > mrpt::math::MatrixVectorBase< Scalar, Derived >::operator* | ( | const CMatrixDynamic< Scalar > & | v | ) |
Definition at line 438 of file MatrixVectorBase_impl.h.
Derived mrpt::math::MatrixVectorBase< Scalar, Derived >::operator* | ( | const Derived & | m2 | ) | const |
Definition at line 470 of file MatrixVectorBase_impl.h.
void mrpt::math::MatrixVectorBase< Scalar, Derived >::operator*= | ( | Scalar | s | ) |
Definition at line 432 of file MatrixVectorBase_impl.h.
|
inline |
Definition at line 188 of file MatrixVectorBase.h.
|
inline |
Definition at line 279 of file MatrixVectorBase.h.
|
inline |
Definition at line 194 of file MatrixVectorBase.h.
void mrpt::math::MatrixVectorBase< Scalar, Derived >::operator+= | ( | Scalar | s | ) |
Definition at line 420 of file MatrixVectorBase_impl.h.
|
inline |
Definition at line 294 of file MatrixVectorBase.h.
|
inline |
Definition at line 181 of file MatrixVectorBase.h.
|
inline |
Definition at line 201 of file MatrixVectorBase.h.
|
inline |
Definition at line 309 of file MatrixVectorBase.h.
|
inline |
Definition at line 207 of file MatrixVectorBase.h.
void mrpt::math::MatrixVectorBase< Scalar, Derived >::operator-= | ( | Scalar | s | ) |
Definition at line 426 of file MatrixVectorBase_impl.h.
|
inline |
Definition at line 324 of file MatrixVectorBase.h.
|
inline |
Definition at line 422 of file MatrixVectorBase.h.
void mrpt::math::MatrixVectorBase< Scalar, Derived >::saveToTextFile | ( | const std::string & | file, |
mrpt::math::TMatrixTextFileFormat | fileFormat = mrpt::math::MATRIX_FORMAT_ENG , |
||
bool | appendMRPTHeader = false , |
||
const std::string & | userHeader = std::string() |
||
) | const |
Saves the vector/matrix to a file compatible with MATLAB/Octave text format.
file | The target filename. |
fileFormat | See TMatrixTextFileFormat. The format of the numbers in the text file. |
appendMRPTHeader | Insert this header to the file "% File generated by MRPT. Load with MATLAB with: VAR=load(FILENAME);" |
userHeader | Additional text to be written at the head of the file. Typically MALAB comments "% This file blah blah". Final end-of-line is not needed. |
Definition at line 159 of file MatrixVectorBase_impl.h.
Referenced by mrpt::vision::build_linear_system(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), kfslam_traits< CRangeBearingKFSLAM >::doPartitioningExperiment(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::drawSingleSample(), mrpt::poses::CPosePDFGaussianInf::drawSingleSample(), mrpt::obs::CObservation3DRangeScan::points3D_convertToExternalStorage(), mrpt::obs::CObservation3DRangeScan::rangeImage_convertToExternalStorage(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), mrpt::maps::CRandomFieldGridMap2D::saveMetricMapRepresentationToFile(), mrpt::maps::COccupancyGridMap2D::saveMetricMapRepresentationToFile(), mrpt::math::CSparseMatrix::saveToTextFile_dense(), mrpt::math::MatrixBlockSparseCols< Scalar, NROWS, NCOLS, INFO, HAS_REMAP, INDEX_REMAP_MAP_IMPL >::saveToTextFileAsDense(), and TestLevMarq().
|
inline |
Definition at line 75 of file MatrixVectorBase.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::setConstant(), and mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::setZero().
|
inline |
Definition at line 76 of file MatrixVectorBase.h.
|
inline |
Definition at line 81 of file MatrixVectorBase.h.
|
inline |
Definition at line 112 of file MatrixVectorBase.h.
Referenced by mrpt::vision::build_linear_system(), mrpt::opengl::TRenderMatrices::computeProjectionMatrix(), mrpt::poses::CPose3DPDFGaussianInf::copyFrom(), mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::poses::CPointPDFGaussian::CPointPDFGaussian(), mrpt::poses::CPosePDFGaussian::CPosePDFGaussian(), mrpt::math::CSparseMatrix::cs2dense(), mrpt::poses::CPoseRandomSampler::do_sample_2D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), fillSampleObs(), mrpt::math::generateAxisBaseFromDirectionAndAxis(), mrpt::poses::CPointPDFParticles::getCovarianceAndMean(), mrpt::poses::CPose3DPDFParticles::getCovarianceAndMean(), mrpt::poses::CPosePDFParticles::getCovarianceAndMean(), mrpt::poses::CPointPDFSOG::getCovarianceAndMean(), mrpt::poses::CPosePDFSOG::getCovarianceAndMean(), mrpt::vision::CFeatureExtraction::internal_computeSpinImageDescriptors(), mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hwdrivers::TCaptureOptions_DUO3D::m_camera_int_params_from_yml(), mrpt::graphslam::optimize_graph_spa_levmarq(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::renderUpdateBuffers(), mrpt::slam::CRangeBearingKFSLAM2D::reset(), mrpt::slam::CRangeBearingKFSLAM::reset(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::maps::CLandmarksMap::saveToMATLABScript2D(), mrpt::img::TCamera::setIntrinsicParamsFromValues(), and mrpt::graphs::ScalarFactorGraph::updateEstimation().
|
inline |
Definition at line 113 of file MatrixVectorBase.h.
|
inline |
Definition at line 117 of file MatrixVectorBase.h.
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::sum | ( | ) | const |
Sum of all elements in matrix/vector.
Definition at line 345 of file MatrixVectorBase_impl.h.
Referenced by mrpt::vision::CFeature::internal_distanceBetweenPolarImages(), and TEST().
Scalar mrpt::math::MatrixVectorBase< Scalar, Derived >::sum_abs | ( | ) | const |
Sum of the absolute value of all elements in matrix/vector.
Definition at line 351 of file MatrixVectorBase_impl.h.
|
inline |
Definition at line 226 of file MatrixVectorBase.h.
|
inline |
Definition at line 159 of file MatrixVectorBase.h.
Referenced by mrpt::poses::CPointPDFGaussian::changeCoordinatesReference(), mrpt::poses::CPosePDFGaussian::composePoint(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::poses::CPosePDFGaussian::inverse(), mrpt::poses::CPosePDFGaussianInf::inverse(), mrpt::vision::projectMatchedFeatures(), mrpt::maps::CLandmarksMap::saveToMATLABScript2D(), and TEST().
|
inline |
Definition at line 164 of file MatrixVectorBase.h.
|
inlinestatic |
Definition at line 125 of file MatrixVectorBase.h.
Referenced by mrpt::vision::build_linear_system(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::setCovMatrix(), and mrpt::obs::TPixelLabelInfo< BYTES_REQUIRED_ >::setSize().
|
inlinestatic |
Definition at line 126 of file MatrixVectorBase.h.
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 |