and other utilities
Namespaces | |
mrpt | |
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries. | |
Files | |
file | ops_containers.h |
Functions | |
template<class Derived > | |
const Eigen::MatrixBase< Derived >::AdjointReturnType | mrpt::math::operator~ (const Eigen::MatrixBase< Derived > &m) |
Transpose operator for matrices. More... | |
template<class Derived > | |
Eigen::MatrixBase< Derived >::PlainObject | mrpt::math::operator! (const Eigen::MatrixBase< Derived > &m) |
Unary inversion operator. More... | |
template<class T > | |
std::ostream & | mrpt::math::operator<< (std::ostream &out, const std::vector< T > &d) |
A template function for printing out the contents of a std::vector variable. More... | |
template<class T > | |
std::ostream & | mrpt::math::operator<< (std::ostream &out, std::vector< T > *d) |
A template function for printing out the contents of a std::vector variable. More... | |
template<typename T , size_t N> | |
mrpt::serialization::CArchive & | mrpt::math::operator<< (mrpt::serialization::CArchive &ostrm, const CArrayNumeric< T, N > &a) |
Binary dump of a CArrayNumeric<T,N> to a stream. More... | |
template<typename T , size_t N> | |
mrpt::serialization::CArchive & | mrpt::math::operator>> (mrpt::serialization::CArchive &istrm, CArrayNumeric< T, N > &a) |
Binary read of a CArrayNumeric<T,N> from a stream. More... | |
bool | mrpt::math::loadVector (std::istream &f, std::vector< int > &d) |
Loads one row of a text file as a numerical std::vector. More... | |
bool | mrpt::math::loadVector (std::istream &f, std::vector< double > &d) |
Loads one row of a text file as a numerical std::vector. More... | |
void | mrpt::math::medianFilter (const std::vector< double > &inV, std::vector< double > &outV, const int &winSize, const int &numberOfSigmas=2) |
template<typename T , typename VECTOR > | |
void | mrpt::math::linspace (T first, T last, size_t count, VECTOR &out_vector) |
Generates an equidistant sequence of numbers given the first one, the last one and the desired number of points. More... | |
template<class T , T STEP> | |
std::vector< T > | mrpt::math::sequenceStdVec (T first, size_t length) |
Generates a sequence of values [first,first+STEP,first+2*STEP,...]. More... | |
template<class VEC1 , class VEC2 > | |
void | mrpt::math::normalize (const VEC1 &v, VEC2 &out_v) |
Normalize a vector, such as its norm is the unity. More... | |
template<class VECTOR_OF_VECTORS , class VECTORLIKE > | |
void | mrpt::math::extractColumnFromVectorOfVectors (const size_t colIndex, const VECTOR_OF_VECTORS &data, VECTORLIKE &out_column) |
Extract a column from a vector of vectors, and store it in another vector. More... | |
uint64_t | mrpt::math::factorial64 (unsigned int n) |
Computes the factorial of an integer number and returns it as a 64-bit integer number. More... | |
double | mrpt::math::factorial (unsigned int n) |
Computes the factorial of an integer number and returns it as a double value (internally it uses logarithms for avoiding overflow). More... | |
template<typename EIGEN_VECTOR , typename At , size_t N> | |
EIGEN_VECTOR & | mrpt::math::loadVector (EIGEN_VECTOR &v, At(&theArray)[N]) |
Assignment operator for initializing a std::vector from a C array (The vector will be automatically set to the correct size). More... | |
template<typename T , typename At , size_t N> | |
std::vector< T > & | mrpt::math::loadVector (std::vector< T > &v, At(&theArray)[N]) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. More... | |
template<class T > | |
void | mrpt::math::wrapTo2PiInPlace (T &a) |
Modifies the given angle to translate it into the [0,2pi[ range. More... | |
template<class T > | |
T | mrpt::math::wrapTo2Pi (T a) |
Modifies the given angle to translate it into the [0,2pi[ range. More... | |
template<class T > | |
T | mrpt::math::wrapToPi (T a) |
Modifies the given angle to translate it into the ]-pi,pi] range. More... | |
template<class T > | |
void | mrpt::math::wrapToPiInPlace (T &a) |
Modifies the given angle to translate it into the ]-pi,pi] range. More... | |
template<class VECTOR > | |
void | mrpt::math::unwrap2PiSequence (VECTOR &x) |
Modify a sequence of angle values such as no consecutive values have a jump larger than PI in absolute value. More... | |
template<class T > | |
T | mrpt::math::angDistance (T from, T to) |
Computes the shortest angular increment (or distance) between two planar orientations, such that it is constrained to [-pi,pi] and is correct for any combination of angles (e.g. More... | |
Operators for binary streaming of MRPT matrices | |
template<size_t NROWS, size_t NCOLS> | |
mrpt::serialization::CArchive & | mrpt::math::operator>> (mrpt::serialization::CArchive &in, CMatrixFixedNumeric< float, NROWS, NCOLS > &M) |
Read operator from a CStream. More... | |
template<size_t NROWS, size_t NCOLS> | |
mrpt::serialization::CArchive & | mrpt::math::operator>> (mrpt::serialization::CArchive &in, CMatrixFixedNumeric< double, NROWS, NCOLS > &M) |
Read operator from a CStream. More... | |
template<size_t NROWS, size_t NCOLS> | |
mrpt::serialization::CArchive & | mrpt::math::operator<< (mrpt::serialization::CArchive &out, const CMatrixFixedNumeric< float, NROWS, NCOLS > &M) |
Write operator for writing into a CStream. More... | |
template<size_t NROWS, size_t NCOLS> | |
mrpt::serialization::CArchive & | mrpt::math::operator<< (mrpt::serialization::CArchive &out, const CMatrixFixedNumeric< double, NROWS, NCOLS > &M) |
Write operator for writing into a CStream. More... | |
Operators for text streaming of MRPT matrices | |
template<typename T , size_t NROWS, size_t NCOLS> | |
std::ostream & | mrpt::math::operator<< (std::ostream &s, const CMatrixFixedNumeric< T, NROWS, NCOLS > &m) |
Dumps the matrix to a text ostream, adding a final "\n" to Eigen's default output. More... | |
template<typename T > | |
std::ostream & | mrpt::math::operator<< (std::ostream &s, const CMatrixTemplateNumeric< T > &m) |
Dumps the matrix to a text ostream, adding a final "\n" to Eigen's default output. More... | |
template<typename MAT > | |
void | mrpt::math::deserializeSymmetricMatrixFrom (MAT &m, mrpt::serialization::CArchive &in) |
Binary serialization of symmetric matrices, saving the space of duplicated values. More... | |
template<typename MAT > | |
void | mrpt::math::serializeSymmetricMatrixTo (MAT &m, mrpt::serialization::CArchive &out) |
Binary serialization of symmetric matrices, saving the space of duplicated values. More... | |
Generic std::vector element-wise operations | |
template<typename T1 , typename T2 > | |
std::vector< T1 > & | mrpt::math::operator*= (std::vector< T1 > &a, const std::vector< T2 > &b) |
a*=b (element-wise multiplication) More... | |
template<typename T1 > | |
std::vector< T1 > & | mrpt::math::operator*= (std::vector< T1 > &a, const T1 b) |
a*=k (multiplication by a constant) More... | |
template<typename T1 , typename T2 > | |
std::vector< T1 > | mrpt::math::operator* (const std::vector< T1 > &a, const std::vector< T2 > &b) |
a*b (element-wise multiplication) More... | |
template<typename T1 , typename T2 > | |
std::vector< T1 > & | mrpt::math::operator+= (std::vector< T1 > &a, const std::vector< T2 > &b) |
a+=b (element-wise sum) More... | |
template<typename T1 > | |
std::vector< T1 > & | mrpt::math::operator+= (std::vector< T1 > &a, const T1 b) |
a+=b (sum a constant) More... | |
template<typename T1 , typename T2 > | |
std::vector< T1 > | mrpt::math::operator+ (const std::vector< T1 > &a, const std::vector< T2 > &b) |
a+b (element-wise sum) More... | |
template<typename T1 , typename T2 > | |
std::vector< T1 > | mrpt::math::operator- (const std::vector< T1 > &v1, const std::vector< T2 > &v2) |
|
inline |
Computes the shortest angular increment (or distance) between two planar orientations, such that it is constrained to [-pi,pi] and is correct for any combination of angles (e.g.
near +-pi) Examples: angDistance(0,pi) -> +pi; angDistance(pi,0) -> -pi; angDistance(-3.1,3.1) -> -0.08; angDistance(3.1,-3.1) -> +0.08;
Definition at line 98 of file wrap2pi.h.
References M_PI, and mrpt::math::wrapToPiInPlace().
Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::PoseDistanceMetric< TNodeSE2 >::distance(), mrpt::poses::CPoseInterpolatorBase< 3 >::impl_interpolation(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), TEST(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().
void mrpt::math::deserializeSymmetricMatrixFrom | ( | MAT & | m, |
mrpt::serialization::CArchive & | in | ||
) |
Binary serialization of symmetric matrices, saving the space of duplicated values.
Definition at line 120 of file matrix_serialization.h.
References ASSERT_EQUAL_.
Referenced by mrpt::poses::CPosePDFGaussian::serializeFrom(), mrpt::poses::CPointPDFSOG::serializeFrom(), mrpt::poses::CPosePDFSOG::serializeFrom(), mrpt::poses::CPose3DPDFGaussian::serializeFrom(), mrpt::poses::CPose3DPDFGaussianInf::serializeFrom(), and mrpt::poses::CPose3DQuatPDFGaussian::serializeFrom().
|
inline |
Extract a column from a vector of vectors, and store it in another vector.
For the sake of generality, this function does NOT check the limits in the number of column, unless it's implemented in the [] operator of each of the "rows".
Definition at line 142 of file math/include/mrpt/math/utils.h.
double mrpt::math::factorial | ( | unsigned int | n | ) |
Computes the factorial of an integer number and returns it as a double value (internally it uses logarithms for avoiding overflow).
Definition at line 68 of file math.cpp.
Referenced by cos_Asymptotic_Series(), Power_Series_C(), Power_Series_S(), and sin_Asymptotic_Series().
uint64_t mrpt::math::factorial64 | ( | unsigned int | n | ) |
void mrpt::math::linspace | ( | T | first, |
T | last, | ||
size_t | count, | ||
VECTOR & | out_vector | ||
) |
Generates an equidistant sequence of numbers given the first one, the last one and the desired number of points.
Definition at line 82 of file math/include/mrpt/math/utils.h.
Referenced by mrpt::math::CHistogram::getHistogram(), mrpt::math::CHistogram::getHistogramNormalized(), and mrpt::tfest::se3_l2_robust().
EIGEN_VECTOR& mrpt::math::loadVector | ( | EIGEN_VECTOR & | v, |
At(&) | theArray[N] | ||
) |
Assignment operator for initializing a std::vector from a C array (The vector will be automatically set to the correct size).
Definition at line 201 of file math/include/mrpt/math/utils.h.
References MRPT_COMPILE_TIME_ASSERT.
bool mrpt::math::loadVector | ( | std::istream & | f, |
std::vector< double > & | d | ||
) |
Loads one row of a text file as a numerical std::vector.
bool mrpt::math::loadVector | ( | std::istream & | f, |
std::vector< int > & | d | ||
) |
Loads one row of a text file as a numerical std::vector.
std::vector<T>& mrpt::math::loadVector | ( | std::vector< T > & | v, |
At(&) | theArray[N] | ||
) |
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 212 of file math/include/mrpt/math/utils.h.
References MRPT_COMPILE_TIME_ASSERT.
void mrpt::math::medianFilter | ( | const std::vector< double > & | inV, |
std::vector< double > & | outV, | ||
const int & | winSize, | ||
const int & | numberOfSigmas = 2 |
||
) |
Definition at line 460 of file math.cpp.
References ASSERT_, min, and MRPT_UNUSED_PARAM.
void mrpt::math::normalize | ( | const VEC1 & | v, |
VEC2 & | out_v | ||
) |
Normalize a vector, such as its norm is the unity.
If the vector has a null norm, the output is a null vector.
Definition at line 118 of file math/include/mrpt/math/utils.h.
References mrpt::square().
|
inline |
Unary inversion operator.
Definition at line 41 of file ops_matrices.h.
|
inline |
a*b (element-wise multiplication)
Definition at line 55 of file ops_vectors.h.
References ASSERT_EQUAL_.
|
inline |
a*=b (element-wise multiplication)
Definition at line 36 of file ops_vectors.h.
References ASSERT_EQUAL_.
|
inline |
a*=k (multiplication by a constant)
Definition at line 46 of file ops_vectors.h.
|
inline |
|
inline |
|
inline |
a+=b (sum a constant)
Definition at line 77 of file ops_vectors.h.
|
inline |
Definition at line 97 of file ops_vectors.h.
References ASSERT_EQUAL_.
mrpt::serialization::CArchive& mrpt::math::operator<< | ( | mrpt::serialization::CArchive & | ostrm, |
const CArrayNumeric< T, N > & | a | ||
) |
Binary dump of a CArrayNumeric<T,N> to a stream.
Definition at line 140 of file ops_vectors.h.
References mrpt::serialization::CArchive::WriteBufferFixEndianness().
mrpt::serialization::CArchive& mrpt::math::operator<< | ( | mrpt::serialization::CArchive & | out, |
const CMatrixFixedNumeric< double, NROWS, NCOLS > & | M | ||
) |
Write operator for writing into a CStream.
The format is compatible with that of CMatrix & CMatrixD
Definition at line 81 of file matrix_serialization.h.
References mrpt::serialization::CArchive::WriteObject().
mrpt::serialization::CArchive& mrpt::math::operator<< | ( | mrpt::serialization::CArchive & | out, |
const CMatrixFixedNumeric< float, NROWS, NCOLS > & | M | ||
) |
Write operator for writing into a CStream.
The format is compatible with that of CMatrix & CMatrixD
Definition at line 70 of file matrix_serialization.h.
References mrpt::serialization::CArchive::WriteObject().
std::ostream& mrpt::math::operator<< | ( | std::ostream & | out, |
const std::vector< T > & | d | ||
) |
A template function for printing out the contents of a std::vector variable.
Definition at line 111 of file ops_vectors.h.
std::ostream& mrpt::math::operator<< | ( | std::ostream & | out, |
std::vector< T > * | d | ||
) |
A template function for printing out the contents of a std::vector variable.
Definition at line 126 of file ops_vectors.h.
|
inline |
Dumps the matrix to a text ostream, adding a final "\n" to Eigen's default output.
Definition at line 98 of file matrix_serialization.h.
|
inline |
Dumps the matrix to a text ostream, adding a final "\n" to Eigen's default output.
Definition at line 109 of file matrix_serialization.h.
mrpt::serialization::CArchive& mrpt::math::operator>> | ( | mrpt::serialization::CArchive & | in, |
CMatrixFixedNumeric< double, NROWS, NCOLS > & | M | ||
) |
Read operator from a CStream.
The format is compatible with that of CMatrix & CMatrixD
Definition at line 51 of file matrix_serialization.h.
References ASSERTMSG_.
mrpt::serialization::CArchive& mrpt::math::operator>> | ( | mrpt::serialization::CArchive & | in, |
CMatrixFixedNumeric< float, NROWS, NCOLS > & | M | ||
) |
Read operator from a CStream.
The format is compatible with that of CMatrix & CMatrixD
Definition at line 33 of file matrix_serialization.h.
References ASSERTMSG_.
mrpt::serialization::CArchive& mrpt::math::operator>> | ( | mrpt::serialization::CArchive & | istrm, |
CArrayNumeric< T, N > & | a | ||
) |
Binary read of a CArrayNumeric<T,N> from a stream.
Definition at line 150 of file ops_vectors.h.
References ASSERTMSG_, mrpt::format(), and mrpt::serialization::CArchive::ReadBufferFixEndianness().
|
inline |
Transpose operator for matrices.
Definition at line 33 of file ops_matrices.h.
|
inline |
Generates a sequence of values [first,first+STEP,first+2*STEP,...].
Definition at line 101 of file math/include/mrpt/math/utils.h.
void mrpt::math::serializeSymmetricMatrixTo | ( | MAT & | m, |
mrpt::serialization::CArchive & | out | ||
) |
Binary serialization of symmetric matrices, saving the space of duplicated values.
Definition at line 139 of file matrix_serialization.h.
References ASSERT_EQUAL_.
Referenced by mrpt::poses::CPosePDFGaussian::serializeTo(), mrpt::poses::CPointPDFSOG::serializeTo(), mrpt::poses::CPosePDFSOG::serializeTo(), mrpt::poses::CPose3DPDFGaussian::serializeTo(), mrpt::poses::CPose3DPDFGaussianInf::serializeTo(), and mrpt::poses::CPose3DQuatPDFGaussian::serializeTo().
void mrpt::math::unwrap2PiSequence | ( | VECTOR & | x | ) |
Modify a sequence of angle values such as no consecutive values have a jump larger than PI in absolute value.
Definition at line 74 of file wrap2pi.h.
References M_PI, and mrpt::math::wrapToPiInPlace().
Referenced by mrpt::poses::CPoseInterpolatorBase< 3 >::impl_interpolation().
|
inline |
Modifies the given angle to translate it into the [0,2pi[ range.
Definition at line 41 of file wrap2pi.h.
References mrpt::math::wrapTo2PiInPlace().
Referenced by mrpt::nav::collision_free_dist_arc_circ_robot(), mrpt::obs::CObservation2DRangeScan::filterByExclusionAngles(), mrpt::math::operator!=(), mrpt::math::operator==(), and mrpt::math::wrapToPi().
|
inline |
Modifies the given angle to translate it into the [0,2pi[ range.
Definition at line 28 of file wrap2pi.h.
References M_PI.
Referenced by mrpt::nav::CPTG_DiffDrive_C::inverseMap_WS2TP(), and mrpt::math::wrapTo2Pi().
|
inline |
Modifies the given angle to translate it into the ]-pi,pi] range.
Definition at line 53 of file wrap2pi.h.
References M_PI, and mrpt::math::wrapTo2Pi().
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::accumulateAngleDiffs(), mrpt::nav::CParameterizedTrajectoryGenerator::alpha2index(), mrpt::graphs::detail::graph_ops< graph_t >::auxEuclid2Dist(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::checkRegistrationCondition(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::checkRegistrationCondition(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::checkRegistrationConditionPose(), mrpt::poses::CPose2D::composeFrom(), mrpt::obs::CActionRobotMovement2D::computeFromOdometry_modelThrun(), mrpt::math::covariancesAndMeanWeighted(), mrpt::nav::CHolonomicND::direction2sector(), mrpt::nav::CHolonomicFullEval::direction2sector(), mrpt::poses::CPose3D::distanceEuclidean6D(), mrpt::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::obs::CActionRobotMovement2D::drawSingleSample_modelThrun(), mrpt::poses::CPosePDFParticles::evaluatePDF_parzen(), mrpt::poses::CPose3DPDFParticles::getCovarianceAndMean(), mrpt::poses::CPosePDFParticles::getCovarianceAndMean(), mrpt::obs::CObservationBearingRange::getDescriptionAsText(), mrpt::slam::CICP::ICP3D_Method_Classic(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::slam::CICP::ICP_Method_LM(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::kinematics::CVehicleSimul_Holo::internal_simulControlStep(), mrpt::math::interpolate2points(), mrpt::poses::CPose2D::inverseComposeFrom(), mrpt::poses::CPose3D::isHorizontal(), mrpt::math::leastSquareLinearFit(), mrpt::poses::CPose2D::normalizePhi(), mrpt::math::TPose2D::normalizePhi(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationModel(), mrpt::math::TPose2D::operator+(), mrpt::math::TPose2D::operator-(), mrpt::math::pointIntoQuadrangle(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::processOneLMH(), mrpt::hwdrivers::CNTRIPClient::retrieveListOfMountpoints(), run_test_so2_avrg(), mrpt::tfest::se2_l2_robust(), mrpt::poses::CPose3D::setFromValues(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::math::spline(), and mrpt::math::wrapToPiInPlace().
|
inline |
Modifies the given angle to translate it into the ]-pi,pi] range.
Definition at line 64 of file wrap2pi.h.
References mrpt::math::wrapToPi().
Referenced by mrpt::math::angDistance(), mrpt::graphs::detail::graph_ops< graph_t >::auxMaha2Dist(), mrpt::poses::CPosePDFGaussian::drawManySamples(), mrpt::poses::CPosePDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPosePDFGaussianInf::mahalanobisDistanceTo(), mrpt::poses::CPosePDFSOG::mergeModes(), mrpt::slam::CRangeBearingKFSLAM2D::OnNormalizeStateVector(), mrpt::slam::CRangeBearingKFSLAM2D::OnSubstractObservationVectors(), mrpt::slam::CRangeBearingKFSLAM::OnSubstractObservationVectors(), mrpt::kinematics::CVehicleSimulVirtualBase::simulateOneTimeStep(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), and mrpt::math::unwrap2PiSequence().
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at mié 12 jul 2023 10:03:34 CEST |