MRPT
1.9.9
|
This class is a "CSerializable" wrapper for "CMatrixDynamic<double>".
Definition at line 23 of file CMatrixD.h.
#include <mrpt/math/CMatrixD.h>
Public Types | |
using | Base = CMatrixDynamic< double > |
Public Member Functions | |
CMatrixD () | |
Constructor. More... | |
CMatrixD (size_t row, size_t col) | |
Constructor. More... | |
CMatrixD (const Base &m) | |
Copy constructor. More... | |
CMatrixD (const CMatrixFloat &m) | |
Copy constructor. More... | |
template<typename Other > | |
CMatrixD & | operator= (const Other &other) |
template<class Other > | |
CMatrixD (const Other &other) | |
virtual mxArray * | writeToMatlab () const |
Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More... | |
void | swap (CMatrixDynamic< double > &o) |
Swap with another matrix very efficiently (just swaps a pointer and two integer values). More... | |
void | setFromMatrixLike (const MAT &m) |
size_type | rows () const |
Number of rows in the matrix. More... | |
size_type | cols () const |
Number of columns in the matrix. More... | |
matrix_size_t | size () const |
Get a 2-vector with [NROWS NCOLS] (as in MATLAB command size(x)) More... | |
void | setSize (size_t row, size_t col, bool zeroNewElements=false) |
Changes the size of matrix, maintaining the previous contents. More... | |
void | resize (size_t row, size_t col) |
void | resize (size_t vectorLen) |
Resizes as a Nx1 vector. More... | |
void | resize (const matrix_size_t &siz, bool zeroNewElements=false) |
Resize the matrix. More... | |
CMatrixDynamic & | derived () |
const CMatrixDynamic & | derived () const |
void | conservativeResize (size_t row, size_t col) |
const double * | data () const |
Return raw pointer to row-major data buffer. More... | |
double * | data () |
double & | operator() (size_t row, size_t col) |
Subscript operator to get/set individual elements. More... | |
const double & | operator() (size_t row, size_t col) const |
Subscript operator to get individual elements. More... | |
double & | operator[] (size_t ith) |
Subscript operator to get/set an individual element from a row or column matrix. More... | |
const double & | operator[] (size_t ith) const |
Subscript operator to get/set an individual element from a row or column matrix. More... | |
void | appendRow (const VECTOR &in) |
Appends a new row to the MxN matrix from a 1xN vector. More... | |
void | setRow (const Index row, const VECTOR &v) |
void | setCol (const Index col, const VECTOR &v) |
void | appendCol (const VECTOR &in) |
Appends a new column to the matrix from a vector. More... | |
void | asVector (VECTOR &out) const |
Returns a vector containing the matrix's values. More... | |
EIGEN_MAP | asEigen () |
Get as an Eigen-compatible Eigen::Map object. More... | |
EIGEN_MAP | asEigen () const |
CMatrixDynamic< float > | cast_float () const |
CMatrixDynamic< double > | cast_double () const |
CVectorDynamic< Scalar > | llt_solve (const CVectorDynamic< Scalar > &b) const |
Solves the linear system Ax=b, returns x, with A this symmetric matrix. More... | |
CVectorDynamic< Scalar > | lu_solve (const CVectorDynamic< Scalar > &b) const |
Solves the linear system Ax=b, returns x, with A this asymmetric matrix. More... | |
Derived & | mbDerived () |
const Derived & | mbDerived () const |
void | setDiagonal (const std::size_t N, const Scalar value) |
Resize to NxN, set all entries to zero, except the main diagonal which is set to value More... | |
void | setDiagonal (const Scalar value) |
Set all entries to zero, except the main diagonal which is set to value More... | |
void | setDiagonal (const std::vector< Scalar > &diags) |
Resizes to NxN, with N the length of the input vector, set all entries to zero, except the main diagonal which is set to values in the vector. More... | |
void | setIdentity () |
void | setIdentity (const std::size_t N) |
void | matProductOf_AB (const Derived &A, const Derived &B) |
this = A*B, with A & B of the same type of this. More... | |
Derived & | mvbDerived () |
const Derived & | mvbDerived () const |
RTTI classes and functions for polymorphic hierarchies | |
mrpt::rtti::CObject::Ptr | duplicateGetSmartPtr () const |
Makes a deep copy of the object and returns a smart pointer to it. More... | |
Operations that DO require `#include <Eigen/Dense>` in user code | |
auto | col (int colIdx) |
auto | col (int colIdx) const |
auto | row (int rowIdx) |
auto | row (int rowIdx) const |
template<typename VECTOR_LIKE > | |
void | extractRow (int rowIdx, VECTOR_LIKE &v) const |
template<typename VECTOR_LIKE > | |
VECTOR_LIKE | extractRow (int rowIdx) const |
template<typename VECTOR_LIKE > | |
void | extractColumn (int colIdx, VECTOR_LIKE &v) const |
template<typename VECTOR_LIKE > | |
VECTOR_LIKE | extractColumn (int colIdx) const |
Standalone operations (do NOT require `#include <Eigen/Dense>`) | |
Scalar | det () const |
Determinant of matrix. More... | |
Derived | inverse () const |
Returns the inverse of a general matrix using LU. More... | |
Derived | inverse_LLt () const |
Returns the inverse of a symmetric matrix using LLt. More... | |
int | rank (Scalar threshold=0) const |
Finds the rank of the matrix via LU decomposition. More... | |
bool | chol (Derived &U) const |
Cholesky M=UT * U decomposition for symmetric matrix (upper-half of the matrix is actually ignored. More... | |
bool | eig (Derived &eVecs, std::vector< Scalar > &eVals, bool sorted=true) const |
Computes the eigenvectors and eigenvalues for a square, general matrix. More... | |
bool | eig_symmetric (Derived &eVecs, std::vector< Scalar > &eVals, bool sorted=true) const |
Read: eig() More... | |
Scalar | maximumDiagonal () const |
Returns the maximum value in the diagonal. More... | |
Scalar | minimumDiagonal () const |
Returns the minimum value in the diagonal. More... | |
Scalar | trace () const |
Returns the trace of the matrix (not necessarily square). More... | |
void | unsafeRemoveColumns (const std::vector< std::size_t > &idxs) |
Removes columns of the matrix. More... | |
void | removeColumns (const std::vector< std::size_t > &idxsToRemove) |
Removes columns of the matrix. More... | |
void | unsafeRemoveRows (const std::vector< std::size_t > &idxs) |
Removes rows of the matrix. More... | |
void | removeRows (const std::vector< std::size_t > &idxsToRemove) |
Removes rows of the matrix. More... | |
template<typename OTHERMATVEC > | |
void | insertMatrix (const int row_start, const int col_start, const OTHERMATVEC &submat) |
Copies the given input submatrix/vector into this matrix/vector, starting at the given top-left coordinates. More... | |
template<typename OTHERMATVEC > | |
void | insertMatrixTransposed (const int row_start, const int col_start, const OTHERMATVEC &submat) |
Like insertMatrix(), but inserts ‘submat’` (transposed) More... | |
template<int BLOCK_ROWS, int BLOCK_COLS> | |
CMatrixFixed< Scalar, BLOCK_ROWS, BLOCK_COLS > | blockCopy (int start_row=0, int start_col=0) const |
const blockCopy(): Returns a copy of the given block More... | |
CMatrixDynamic< Scalar > | blockCopy (int start_row, int start_col, int BLOCK_ROWS, int BLOCK_COLS) const |
const blockCopy(): Returns a copy of the given block (non templated version, dynamic sizes) More... | |
template<int BLOCK_ROWS, int BLOCK_COLS> | |
CMatrixFixed< Scalar, BLOCK_ROWS, BLOCK_COLS > | extractMatrix (const int start_row=0, const int start_col=0) const |
CMatrixDynamic< Scalar > | extractMatrix (const int BLOCK_ROWS, const int BLOCK_COLS, const int start_row, const int start_col) const |
template<typename MAT_A > | |
void | matProductOf_AAt (const MAT_A &A) |
this = A * AT More... | |
template<typename MAT_A > | |
void | matProductOf_AtA (const MAT_A &A) |
this = AT * A More... | |
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 > | |
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 > | |
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 |
Standalone operations (do NOT require `#include <Eigen/Dense>`) | |
Derived | operator- (const Derived &m2) const |
Derived | operator+ (const Derived &m2) const |
void | operator+= (Scalar s) |
void | operator+= (const Derived &m2) |
void | operator-= (Scalar s) |
void | operator-= (const Derived &m2) |
CMatrixDynamic< Scalar > | operator* (const CMatrixDynamic< Scalar > &v) |
Derived | operator* (const Derived &m2) const |
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) |
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 |
Static Public Member Functions | |
static Derived | Identity () |
static Derived | Identity (const std::size_t N) |
Protected Member Functions | |
CSerializable virtual methods | |
uint8_t | serializeGetVersion () const override |
Must return the current versioning number of the object. More... | |
void | serializeTo (mrpt::serialization::CArchive &out) const override |
Serialize CSerializable Object to CSchemeArchiveBase derived object. More... | |
void | serializeFrom (mrpt::serialization::CArchive &in, uint8_t serial_version) override |
Serialize CSchemeArchiveBase derived object to CSerializable Object. More... | |
CSerializable virtual methods | |
virtual void | serializeTo (CSchemeArchiveBase &out) const |
Virtual method for writing (serializing) to an abstract schema based archive. More... | |
virtual void | serializeFrom (CSchemeArchiveBase &in) |
Virtual method for reading (deserializing) from an abstract schema based archive. More... | |
RTTI stuff | |
using | Ptr = std::shared_ptr< mrpt::math ::CMatrixD > |
using | ConstPtr = std::shared_ptr< const mrpt::math ::CMatrixD > |
using | UniquePtr = std::unique_ptr< mrpt::math ::CMatrixD > |
using | ConstUniquePtr = std::unique_ptr< const mrpt::math ::CMatrixD > |
static const mrpt::rtti::TRuntimeClassId | runtimeClassId |
static constexpr const char * | className = "mrpt::math" "::" "CMatrixD" |
static const mrpt::rtti::TRuntimeClassId * | _GetBaseClass () |
static constexpr auto | getClassName () |
static const mrpt::rtti::TRuntimeClassId & | GetRuntimeClassIdStatic () |
static std::shared_ptr< CObject > | CreateObject () |
template<typename... Args> | |
static Ptr | Create (Args &&... args) |
template<typename Alloc , typename... Args> | |
static Ptr | CreateAlloc (const Alloc &alloc, Args &&... args) |
template<typename... Args> | |
static UniquePtr | CreateUnique (Args &&... args) |
virtual const mrpt::rtti::TRuntimeClassId * | GetRuntimeClass () const override |
Returns information about the class of an object in runtime. More... | |
virtual mrpt::rtti::CObject * | clone () const override |
Returns a deep copy (clone) of the object, indepently of its class. More... | |
Matrix type definitions | |
using | value_type = double |
The type of the matrix elements. More... | |
using | Scalar = double |
using | Index = int |
using | reference = double & |
using | const_reference = const double & |
using | size_type = int |
using | difference_type = std::ptrdiff_t |
using | eigen_t = Eigen::Matrix< double, RowsAtCompileTime, ColsAtCompileTime, StorageOrder, RowsAtCompileTime, ColsAtCompileTime > |
static constexpr int | RowsAtCompileTime |
static constexpr int | ColsAtCompileTime |
static constexpr int | SizeAtCompileTime |
static constexpr int | is_mrpt_type |
static constexpr int | StorageOrder |
Iterators interface | |
using | iterator = typename vec_t::iterator |
using | const_iterator = typename vec_t::const_iterator |
iterator | begin () |
const_iterator | begin () const |
iterator | end () |
const_iterator | end () const |
const_iterator | cbegin () const |
const_iterator | cend () const |
Initialization methods | |
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) |
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) |
using mrpt::math::CMatrixD::Base = CMatrixDynamic<double> |
Definition at line 29 of file CMatrixD.h.
|
inherited |
Definition at line 74 of file CMatrixDynamic.h.
|
inherited |
Definition at line 58 of file CMatrixDynamic.h.
using mrpt::math::CMatrixD::ConstPtr = std::shared_ptr<const mrpt::math :: CMatrixD > |
Definition at line 26 of file CMatrixD.h.
using mrpt::math::CMatrixD::ConstUniquePtr = std::unique_ptr<const mrpt::math :: CMatrixD > |
Definition at line 26 of file CMatrixD.h.
|
inherited |
Definition at line 60 of file CMatrixDynamic.h.
|
inherited |
Definition at line 68 of file CMatrixDynamic.h.
|
inherited |
Definition at line 56 of file CMatrixDynamic.h.
|
inherited |
Definition at line 73 of file CMatrixDynamic.h.
using mrpt::math::CMatrixD::Ptr = std::shared_ptr< mrpt::math :: CMatrixD > |
A type for the associated smart pointer
Definition at line 26 of file CMatrixD.h.
|
inherited |
Definition at line 57 of file CMatrixDynamic.h.
|
inherited |
Definition at line 55 of file CMatrixDynamic.h.
|
inherited |
Definition at line 59 of file CMatrixDynamic.h.
using mrpt::math::CMatrixD::UniquePtr = std::unique_ptr< mrpt::math :: CMatrixD > |
Definition at line 26 of file CMatrixD.h.
|
inherited |
The type of the matrix elements.
Definition at line 54 of file CMatrixDynamic.h.
|
inline |
Constructor.
Definition at line 32 of file CMatrixD.h.
|
inline |
Constructor.
Definition at line 34 of file CMatrixD.h.
|
inlineexplicit |
Copy constructor.
Definition at line 37 of file CMatrixD.h.
|
inlineexplicit |
Copy constructor.
Definition at line 40 of file CMatrixD.h.
|
inlineexplicit |
Constructor from any other Eigen class
Definition at line 51 of file CMatrixD.h.
References mrpt::math::CMatrixDynamic< double >::operator=().
|
staticprotected |
|
inlineinherited |
Appends a new column to the matrix from a vector.
The length of the vector must match the number of rows of the matrix, unless it is (0,0).
std::exception | On size mismatch. |
Definition at line 510 of file CMatrixDynamic.h.
|
inlineinherited |
Appends a new row to the MxN matrix from a 1xN vector.
The lenght of the vector must match the width of the matrix, unless it's empty: in that case the matrix is resized to 1xN.
std::exception | On incorrect vector length. |
Definition at line 477 of file CMatrixDynamic.h.
|
inlineinherited |
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().
|
inlineinherited |
Definition at line 175 of file MatrixVectorBase.h.
|
inlineinherited |
Get as an Eigen-compatible Eigen::Map object.
Definition at line 540 of file CMatrixDynamic.h.
|
inlineinherited |
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 553 of file CMatrixDynamic.h.
|
inlineinherited |
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().
|
inherited |
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().
|
inlineinherited |
Returns a vector containing the matrix's values.
Definition at line 528 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 75 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 77 of file CMatrixDynamic.h.
|
inlineinherited |
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().
|
inlineinherited |
Definition at line 145 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 151 of file MatrixVectorBase.h.
|
inlineinherited |
const blockCopy(): Returns a copy of the given block
Definition at line 233 of file MatrixBase.h.
Referenced by mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::math::TPose3D::fromHomogeneousMatrix(), mrpt::slam::CRangeBearingKFSLAM2D::getAs3DObject(), mrpt::slam::CRangeBearingKFSLAM::getAs3DObject(), mrpt::slam::CRangeBearingKFSLAM2D::getCurrentRobotPose(), mrpt::slam::CRangeBearingKFSLAM::getCurrentRobotPose(), mrpt::slam::CRangeBearingKFSLAM2D::getCurrentState(), mrpt::slam::CRangeBearingKFSLAM::getCurrentState(), mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >::getLandmarkCov(), mrpt::opengl::CArrow::onUpdateBuffers_Triangles(), mrpt::poses::CPointPDFGaussian::productIntegralWith2D(), and mrpt::apps::RBPF_SLAM_App_Base::run().
|
inlineinherited |
const blockCopy(): Returns a copy of the given block (non templated version, dynamic sizes)
Definition at line 240 of file MatrixBase.h.
|
inherited |
Definition at line 26 of file CMatrixDynamic.cpp.
|
inherited |
Definition at line 19 of file CMatrixDynamic.cpp.
|
inlineinherited |
Definition at line 79 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 80 of file CMatrixDynamic.h.
|
inherited |
Cholesky M=UT * U decomposition for symmetric matrix (upper-half of the matrix is actually ignored.
Definition at line 165 of file MatrixBase_impl.h.
Referenced by mrpt::vision::projectMatchedFeatures(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::renderUpdateBuffers(), and TEST().
|
overridevirtual |
Returns a deep copy (clone) of the object, indepently of its class.
Implements mrpt::rtti::CObject.
|
inlineinherited |
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().
|
inlineinherited |
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().
|
inlineinherited |
Definition at line 89 of file MatrixBase.h.
Referenced by mrpt::math::generateAxisBaseFromDirection(), mrpt::vision::projectMatchedFeatures(), and se3_l2_internal().
|
inlineinherited |
Definition at line 94 of file MatrixBase.h.
|
inlineinherited |
Number of columns in the matrix.
Definition at line 340 of file CMatrixDynamic.h.
Referenced by serializeTo().
|
inlineinherited |
Definition at line 370 of file CMatrixDynamic.h.
|
inlinestaticinherited |
Definition at line 89 of file MatrixVectorBase.h.
Referenced by mrpt::math::MatrixVectorBase< T, CMatrixFixed< T, ROWS, COLS > >::Zero().
|
inlinestaticinherited |
Definition at line 99 of file MatrixVectorBase.h.
|
inlinestatic |
Definition at line 26 of file CMatrixD.h.
|
inlinestatic |
Definition at line 26 of file CMatrixD.h.
|
static |
|
inlinestatic |
Definition at line 26 of file CMatrixD.h.
|
inlineinherited |
Return raw pointer to row-major data buffer.
All matrix cells can be assumed to be stored contiguously in memory, i.e. row stride = column count.
Definition at line 375 of file CMatrixDynamic.h.
|
inlineinherited |
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 381 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 368 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 369 of file CMatrixDynamic.h.
|
inherited |
Determinant of matrix.
Definition at line 76 of file MatrixBase_impl.h.
Referenced by mrpt::poses::CPointPDFSOG::bayesianFusion(), mrpt::poses::CPosePDFSOG::bayesianFusion(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::graphslam::TUncertaintyPath< GRAPH_T >::getAsString(), mrpt::obs::CActionRobotMovement2D::getDescriptionAsText(), mrpt::graphslam::TUncertaintyPath< GRAPH_T >::getDeterminant(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::math::mahalanobisDistance2AndLogPDF(), mrpt::poses::CPosePDFSOG::mergeModes(), mrpt::math::normalPDF(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::renderUpdateBuffers(), and mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::updateCurrCovarianceVisualization().
|
inherited |
dot product of this \cdot v
Definition at line 511 of file MatrixVectorBase_impl.h.
|
inherited |
Definition at line 524 of file MatrixVectorBase_impl.h.
|
inlineinherited |
Makes a deep copy of the object and returns a smart pointer to it.
Definition at line 204 of file CObject.h.
References mrpt::rtti::CObject::clone().
Referenced by mrpt::obs::CRawlog::insert().
|
inherited |
Computes the eigenvectors and eigenvalues for a square, general matrix.
Use eig_symmetric() for symmetric matrices for better accuracy and performance. Eigenvectors are the columns of the returned matrix, and their order matches that of returned eigenvalues.
[in] | sorted | If true, eigenvalues (and eigenvectors) will be sorted in ascending order. |
[out] | eVecs | The container where eigenvectors will be stored. |
[out] | eVals | The container where eigenvalues will be stored. |
Definition at line 107 of file MatrixBase_impl.h.
Referenced by mrpt::detectors::CFaceDetection::checkIfFacePlaneCov(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::computeDominantEigenVector(), mrpt::math::MATLAB_plotCovariance2D(), and TEST().
|
inherited |
Read: eig()
Definition at line 131 of file MatrixBase_impl.h.
Referenced by mrpt::random::CRandomGenerator::drawGaussianMultivariate(), mrpt::random::CRandomGenerator::drawGaussianMultivariateMany(), mrpt::math::getRegressionLine(), mrpt::math::getRegressionPlane(), mrpt::obs::CActionRobotMovement2D::prepareFastDrawSingleSample_modelGaussian(), mrpt::maps::CLandmarksMap::saveToMATLABScript2D(), se3_l2_internal(), mrpt::poses::CPoseRandomSampler::setPosePDF(), and TEST().
|
inlineinherited |
returns true if matrix/vector has size=0
Definition at line 260 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 76 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 78 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 128 of file MatrixBase.h.
Referenced by mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::extractColumn().
|
inlineinherited |
Definition at line 136 of file MatrixBase.h.
|
inlineinherited |
Definition at line 247 of file MatrixBase.h.
Referenced by mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::blockCopy(), mrpt::slam::data_association_independent_predictions(), and mrpt::apps::CGridMapAlignerApp::run().
|
inlineinherited |
Definition at line 260 of file MatrixBase.h.
|
inlineinherited |
Definition at line 112 of file MatrixBase.h.
Referenced by mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::extractRow().
|
inlineinherited |
Definition at line 120 of file MatrixBase.h.
|
inlineinherited |
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().
|
inherited |
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().
|
inlinestatic |
Definition at line 26 of file CMatrixD.h.
|
overridevirtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::serialization::CSerializable.
|
static |
|
inlineinherited |
Definition at line 232 of file MatrixVectorBase.h.
|
inlinestaticinherited |
Definition at line 64 of file MatrixBase.h.
Referenced by mrpt::opengl::CSphere::regenerateBaseParams(), and mrpt::opengl::CText::render().
|
inlinestaticinherited |
Definition at line 74 of file MatrixBase.h.
|
inherited |
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().
|
inlineinherited |
Copies the given input submatrix/vector into this matrix/vector, starting at the given top-left coordinates.
Definition at line 210 of file MatrixBase.h.
Referenced by mrpt::bayes::detail::addNewLandmarks(), mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::slam::data_association_independent_predictions(), Pose3DQuatPDFGaussTests::testInverse(), Pose3DPDFGaussTests::testPoseComposition(), Pose3DQuatPDFGaussTests::testPoseComposition(), Pose3DPDFGaussTests::testPoseInverseComposition(), Pose3DQuatPDFGaussTests::testPoseInverseComposition(), and mrpt::obs::detail::unprojectInto().
|
inlineinherited |
Like insertMatrix(), but inserts ‘submat’` (transposed)
Definition at line 221 of file MatrixBase.h.
|
inherited |
Returns the inverse of a general matrix using LU.
Definition at line 183 of file MatrixBase_impl.h.
Referenced by mrpt::poses::CPosePDFGaussianInf::evaluatePDF(), mrpt::math::mahalanobisDistance2(), and mrpt::math::normalPDF().
|
inherited |
Returns the inverse of a symmetric matrix using LLt.
Definition at line 195 of file MatrixBase_impl.h.
Referenced by mrpt::graphs::detail::graph_ops< graph_t >::auxMaha2Dist(), mrpt::poses::CPointPDFGaussian::bayesianFusion(), mrpt::poses::CPosePDFGaussian::bayesianFusion(), mrpt::poses::CPosePDFGaussianInf::bayesianFusion(), mrpt::poses::CPointPDFSOG::bayesianFusion(), mrpt::poses::CPosePDFSOG::bayesianFusion(), mrpt::poses::CPose3DQuatPDFGaussianInf::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::compute3DMatchingRatio(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::poses::CPose3DQuatPDFGaussianInf::copyFrom(), mrpt::poses::CPosePDFGaussianInf::copyFrom(), mrpt::poses::CPose3DPDFGaussianInf::copyFrom(), kfslam_traits< CRangeBearingKFSLAM >::doPartitioningExperiment(), mrpt::poses::CPose3DQuatPDFGaussianInf::drawManySamples(), mrpt::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussianInf::drawManySamples(), mrpt::poses::CPose3DQuatPDFGaussianInf::drawSingleSample(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussianInf::evaluateNormalizedPDF(), mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute(), mrpt::poses::CPose3DQuatPDFGaussianInf::getCovarianceAndMean(), mrpt::poses::CPosePDFGaussianInf::getCovarianceAndMean(), mrpt::poses::CPose3DPDFGaussianInf::getCovarianceAndMean(), mrpt::math::CProbabilityDensityFunction< CPose2D, 3 >::getInformationMatrix(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::poses::CPose3DQuatPDFGaussianInf::inverse(), mrpt::poses::CPosePDFGaussianInf::inverseComposition(), mrpt::math::mahalanobisDistance2AndLogPDF(), mrpt::poses::CPointPDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPosePDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPosePDFGaussianInf::mahalanobisDistanceTo(), mrpt::poses::CPose3DPDFGaussianInf::mahalanobisDistanceTo(), mrpt::poses::CPose3DPDFGaussian::mahalanobisDistanceTo(), mrpt::math::normalPDF(), mrpt::poses::CPose3DQuatPDFGaussianInf::operator+=(), mrpt::poses::CPose3DPDFGaussianInf::operator+=(), mrpt::poses::CPosePDFGaussianInf::operator+=(), mrpt::poses::CPose3DPDFGaussianInf::operator-=(), mrpt::topography::path_from_rtk_gps(), mrpt::poses::CPointPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith2D(), and mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >::runOneKalmanIteration().
|
inlineinherited |
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().
|
inherited |
Solves the linear system Ax=b, returns x, with A this symmetric matrix.
Definition at line 34 of file CMatrixDynamic.cpp.
|
inherited |
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().
|
inherited |
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.
|
inherited |
Solves the linear system Ax=b, returns x, with A this asymmetric matrix.
Definition at line 40 of file CMatrixDynamic.cpp.
|
inlineinherited |
Definition at line 276 of file MatrixBase.h.
Referenced by mrpt::random::CRandomGenerator::drawDefinitePositiveMatrix(), PosePDFGaussTests::generateRandomPose2DPDF(), Pose3DPDFGaussTests::generateRandomPose3DPDF(), Pose3DQuatPDFGaussTests::generateRandomPose3DPDF(), mrpt::poses::CPose3DPDFSOG::getCovarianceAndMean(), mrpt::poses::CPosePDFSOG::getCovarianceAndMean(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::slam::CICP::ICP_Method_LM(), and mrpt::poses::CPosePDFSOG::mergeModes().
|
inherited |
this = A*B, with A & B of the same type of this.
For products of different matrix types, use the regular * operator (which requires the <Eigen/Dense>
header)
Definition at line 175 of file MatrixBase_impl.h.
Referenced by mrpt::poses::CPoseRandomSampler::setPosePDF().
|
inherited |
this = A * b , with A
and b
a dynamic matrix & vector
Definition at line 485 of file MatrixVectorBase_impl.h.
|
inlineinherited |
Definition at line 295 of file MatrixBase.h.
Referenced by mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute().
|
inherited |
this = AT * b , with A
and b
a dynamic matrix & vector
Definition at line 492 of file MatrixVectorBase_impl.h.
|
inherited |
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().
|
inherited |
Definition at line 384 of file MatrixVectorBase_impl.h.
|
inherited |
Definition at line 409 of file MatrixVectorBase_impl.h.
|
inherited |
Returns the maximum value in the diagonal.
Definition at line 207 of file MatrixBase_impl.h.
Referenced by mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute().
|
inlineinherited |
Definition at line 26 of file MatrixBase.h.
Referenced by mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::col(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::extractColumn(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::extractMatrix(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::extractRow(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::insertMatrix(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::insertMatrixTransposed(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::matProductOf_AAt(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::matProductOf_AtA(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::row(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::setDiagonal(), and mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::setIdentity().
|
inlineinherited |
Definition at line 27 of file MatrixBase.h.
|
inherited |
Minimum value in the matrix/vector.
Definition at line 357 of file MatrixVectorBase_impl.h.
Referenced by mrpt::vision::CFeature::internal_distanceBetweenPolarImages().
|
inherited |
Definition at line 369 of file MatrixVectorBase_impl.h.
|
inherited |
Definition at line 398 of file MatrixVectorBase_impl.h.
|
inherited |
Returns the minimum value in the diagonal.
Definition at line 213 of file MatrixBase_impl.h.
|
inlineinherited |
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().
|
inlineinherited |
Definition at line 60 of file MatrixVectorBase.h.
|
inherited |
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.
|
inherited |
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.
|
inlineinherited |
Definition at line 432 of file MatrixVectorBase.h.
|
inlineinherited |
Subscript operator to get/set individual elements.
Definition at line 389 of file CMatrixDynamic.h.
|
inlineinherited |
Subscript operator to get individual elements.
Definition at line 405 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 214 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 219 of file MatrixVectorBase.h.
|
inherited |
Definition at line 438 of file MatrixVectorBase_impl.h.
|
inherited |
Definition at line 470 of file MatrixVectorBase_impl.h.
|
inherited |
Definition at line 432 of file MatrixVectorBase_impl.h.
|
inlineinherited |
Definition at line 188 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 279 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 194 of file MatrixVectorBase.h.
|
inherited |
Definition at line 420 of file MatrixVectorBase_impl.h.
|
inlineinherited |
Definition at line 294 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 181 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 201 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 309 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 207 of file MatrixVectorBase.h.
|
inherited |
Definition at line 426 of file MatrixVectorBase_impl.h.
|
inlineinherited |
Definition at line 324 of file MatrixVectorBase.h.
|
inline |
Assignment operator from any other Eigen class
Definition at line 44 of file CMatrixD.h.
References mrpt::math::CMatrixDynamic< double >::operator=().
|
inlineinherited |
Definition at line 422 of file MatrixVectorBase.h.
|
inlineinherited |
Subscript operator to get/set an individual element from a row or column matrix.
std::exception | If the object is not a column or row matrix. |
Definition at line 423 of file CMatrixDynamic.h.
|
inlineinherited |
Subscript operator to get/set an individual element from a row or column matrix.
For non-vectors (NxM matrices), it returns the i-th matrix element, in RowMajor order.
std::exception | If the object is not a column or row matrix. |
Definition at line 454 of file CMatrixDynamic.h.
|
inherited |
Finds the rank of the matrix via LU decomposition.
Uses Eigen's default threshold unless threshold>0
.
Definition at line 156 of file MatrixBase_impl.h.
Referenced by mrpt::math::areAligned(), and mrpt::math::conformAPlane().
|
inherited |
Removes columns of the matrix.
Indices may be unsorted and duplicated
Definition at line 38 of file MatrixBase_impl.h.
|
inherited |
Removes rows of the matrix.
Indices may be unsorted and duplicated
Definition at line 65 of file MatrixBase_impl.h.
|
inlineinherited |
Definition at line 356 of file CMatrixDynamic.h.
|
inlineinherited |
Resizes as a Nx1 vector.
Definition at line 359 of file CMatrixDynamic.h.
|
inlineinherited |
Resize the matrix.
Definition at line 362 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 100 of file MatrixBase.h.
Referenced by mrpt::vision::projectMatchedFeatures().
|
inlineinherited |
Definition at line 105 of file MatrixBase.h.
|
inlineinherited |
Number of rows in the matrix.
Definition at line 337 of file CMatrixDynamic.h.
Referenced by serializeTo().
|
inherited |
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().
|
overrideprotectedvirtual |
Serialize CSchemeArchiveBase derived object to CSerializable Object.
Implements mrpt::serialization::CSerializable.
Definition at line 33 of file CMatrixD.cpp.
References MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, mrpt::serialization::CArchive::ReadAs(), mrpt::serialization::CArchive::ReadBufferFixEndianness(), and mrpt::math::CMatrixDynamic< double >::setSize().
|
inlineprotectedvirtualinherited |
Virtual method for reading (deserializing) from an abstract schema based archive.
Definition at line 74 of file CSerializable.h.
References mrpt::serialization::CSerializable::GetRuntimeClass(), and THROW_EXCEPTION.
|
overrideprotectedvirtual |
Must return the current versioning number of the object.
Start in zero for new classes, and increments each time there is a change in the stored format.
Implements mrpt::serialization::CSerializable.
Definition at line 22 of file CMatrixD.cpp.
|
overrideprotectedvirtual |
Serialize CSerializable Object to CSchemeArchiveBase derived object.
Implements mrpt::serialization::CSerializable.
Definition at line 23 of file CMatrixD.cpp.
References mrpt::math::CMatrixDynamic< double >::cols(), out, and mrpt::math::CMatrixDynamic< double >::rows().
|
inlineprotectedvirtualinherited |
Virtual method for writing (serializing) to an abstract schema based archive.
Definition at line 64 of file CSerializable.h.
References mrpt::serialization::CSerializable::GetRuntimeClass(), and THROW_EXCEPTION.
|
inlineinherited |
Definition at line 496 of file CMatrixDynamic.h.
|
inlineinherited |
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().
|
inlineinherited |
Definition at line 76 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 81 of file MatrixVectorBase.h.
|
inlineinherited |
Resize to NxN, set all entries to zero, except the main diagonal which is set to value
Definition at line 34 of file MatrixBase.h.
Referenced by mrpt::obs::CActionRobotMovement2D::prepareFastDrawSingleSample_modelGaussian(), mrpt::maps::CLandmarksMap::saveToMATLABScript2D(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::setDiagonal(), mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::setIdentity(), mrpt::poses::CPoseRandomSampler::setPosePDF(), and TEST().
|
inlineinherited |
Set all entries to zero, except the main diagonal which is set to value
Definition at line 43 of file MatrixBase.h.
|
inlineinherited |
Resizes to NxN, with N the length of the input vector, set all entries to zero, except the main diagonal which is set to values in the vector.
Definition at line 51 of file MatrixBase.h.
|
inlineinherited |
Definition at line 252 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 57 of file MatrixBase.h.
Referenced by mrpt::hmtslam::CHierarchicalMapMHPartition::computeGloballyConsistentNodeCoordinates(), mrpt::opengl::TRenderMatrices::computeOrthoProjectionMatrix(), GraphSlamLevMarqTest< my_graph_t >::create_ring_path(), do_test_init_to_unit(), mrpt::poses::CPose2D::getHomogeneousMatrix(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::getMinUncertaintyPath(), mrpt::poses::CPosePDFSOG::getMostLikelyCovarianceAndMean(), mrpt::poses::CPosePDF::jacobiansPoseComposition(), mrpt::graphs::detail::graph_ops< graph_t >::load_graph_of_poses_from_text_stream(), mrpt::opengl::COpenGLViewport::renderTextMessages(), mrpt::opengl::COpenGLViewport::renderViewportBorder(), TEST(), and mrpt::graphs::detail::graph_ops< graph_t >::write_EDGE_line().
|
inlineinherited |
Definition at line 62 of file MatrixBase.h.
|
inlineinherited |
Definition at line 489 of file CMatrixDynamic.h.
|
inlineinherited |
Changes the size of matrix, maintaining the previous contents.
Definition at line 352 of file CMatrixDynamic.h.
Referenced by serializeFrom().
|
inlineinherited |
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().
|
inlineinherited |
Definition at line 113 of file MatrixVectorBase.h.
|
inlineinherited |
Definition at line 117 of file MatrixVectorBase.h.
|
inlineinherited |
Get a 2-vector with [NROWS NCOLS] (as in MATLAB command size(x))
Definition at line 343 of file CMatrixDynamic.h.
|
inherited |
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().
|
inherited |
Sum of the absolute value of all elements in matrix/vector.
Definition at line 351 of file MatrixVectorBase_impl.h.
|
inlineinherited |
Swap with another matrix very efficiently (just swaps a pointer and two integer values).
Definition at line 141 of file CMatrixDynamic.h.
|
inlineinherited |
Definition at line 226 of file MatrixVectorBase.h.
|
inherited |
Returns the trace of the matrix (not necessarily square).
Definition at line 219 of file MatrixBase_impl.h.
Referenced by TEST().
|
inlineinherited |
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().
|
inlineinherited |
Definition at line 164 of file MatrixVectorBase.h.
|
inherited |
Removes columns of the matrix.
This "unsafe" version assumes indices sorted in ascending order.
Definition at line 22 of file MatrixBase_impl.h.
|
inherited |
Removes rows of the matrix.
This "unsafe" version assumes indices sorted in ascending order.
Definition at line 49 of file MatrixBase_impl.h.
|
inlinevirtualinherited |
Introduces a pure virtual method responsible for writing to a mxArray
Matlab object, typically a MATLAB struct
whose contents are documented in each derived class.
mxArray
(caller is responsible of memory freeing) or nullptr is class does not support conversion to MATLAB. Definition at line 90 of file CSerializable.h.
|
inlinestaticinherited |
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().
|
inlinestaticinherited |
Definition at line 126 of file MatrixVectorBase.h.
|
static |
Definition at line 26 of file CMatrixD.h.
|
staticinherited |
Definition at line 62 of file CMatrixDynamic.h.
|
staticinherited |
Definition at line 64 of file CMatrixDynamic.h.
|
staticinherited |
Definition at line 61 of file CMatrixDynamic.h.
|
staticprotected |
Definition at line 26 of file CMatrixD.h.
|
staticinherited |
Definition at line 63 of file CMatrixDynamic.h.
|
staticinherited |
Definition at line 65 of file CMatrixDynamic.h.
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020 |