Main MRPT website > C++ reference for MRPT 1.9.9
Namespaces | Files | Functions
Vector and matrices mathematical operations

Detailed Description

and other utilities

Collaboration diagram for Vector and matrices mathematical operations:

Namespaces

 mrpt
 This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
 

Files

file  ops_containers.h
 This file implements several operations that operate element-wise on individual or pairs of containers.
 

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::utils::CStreammrpt::math::operator<< (mrpt::utils::CStream &ostrm, const CArrayNumeric< T, N > &a)
 Binary dump of a CArrayNumeric<T,N> to a stream. More...
 
template<typename T , size_t N>
mrpt::utils::CStreammrpt::math::operator>> (mrpt::utils::CStream &istrm, CArrayNumeric< T, N > &a)
 Binary read of a CArrayNumeric<T,N> from a stream. More...
 
bool mrpt::math::loadVector (utils::CFileStream &f, std::vector< int > &d)
 Loads one row of a text file as a numerical std::vector. More...
 
bool mrpt::math::loadVector (utils::CFileStream &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<class T >
mrpt::math::round2up (T val)
 Round up to the nearest power of two of a given number. 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])
 
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 >
mrpt::math::wrapTo2Pi (T a)
 Modifies the given angle to translate it into the [0,2pi[ range. More...
 
template<class 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 >
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::utils::CStreammrpt::math::operator>> (mrpt::utils::CStream &in, CMatrixFixedNumeric< float, NROWS, NCOLS > &M)
 Read operator from a CStream. More...
 
template<size_t NROWS, size_t NCOLS>
mrpt::utils::CStreammrpt::math::operator>> (mrpt::utils::CStream &in, CMatrixFixedNumeric< double, NROWS, NCOLS > &M)
 Read operator from a CStream. More...
 
template<size_t NROWS, size_t NCOLS>
mrpt::utils::CStreammrpt::math::operator<< (mrpt::utils::CStream &out, const CMatrixFixedNumeric< float, NROWS, NCOLS > &M)
 Write operator for writing into a CStream. More...
 
template<size_t NROWS, size_t NCOLS>
mrpt::utils::CStreammrpt::math::operator<< (mrpt::utils::CStream &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...
 

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)
 

Function Documentation

◆ angDistance()

template<class T >
T mrpt::math::angDistance ( from,
to 
)
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;

Note
Take care of not instancing this template for integer numbers, since it only works for float, double and long double.
See also
wrapToPi, wrapTo2Pi

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ extractColumnFromVectorOfVectors()

template<class VECTOR_OF_VECTORS , class VECTORLIKE >
void mrpt::math::extractColumnFromVectorOfVectors ( const size_t  colIndex,
const VECTOR_OF_VECTORS &  data,
VECTORLIKE &  out_column 
)
inline

Extract a column from a vector of vectors, and store it in another vector.

  • Input data can be: std::vector<mrpt::math::CVectorDouble>, std::deque<std::list<double> >, std::list<CArrayDouble<5> >, etc. etc.
  • Output is the sequence: data[0][idx],data[1][idx],data[2][idx], etc..

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 140 of file base/include/mrpt/math/utils.h.

◆ factorial()

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 1024 of file math.cpp.

Referenced by cos_Asymptotic_Series(), Power_Series_C(), Power_Series_S(), and sin_Asymptotic_Series().

Here is the caller graph for this function:

◆ factorial64()

uint64_t mrpt::math::factorial64 ( unsigned int  n)

Computes the factorial of an integer number and returns it as a 64-bit integer number.

Definition at line 1012 of file math.cpp.

◆ linspace()

template<typename T , typename VECTOR >
void mrpt::math::linspace ( first,
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.

See also
sequence

Definition at line 80 of file base/include/mrpt/math/utils.h.

Referenced by mrpt::math::CHistogram::getHistogram(), mrpt::math::CHistogram::getHistogramNormalized(), and mrpt::tfest::se3_l2_robust().

Here is the caller graph for this function:

◆ loadVector() [1/4]

bool mrpt::math::loadVector ( utils::CFileStream f,
std::vector< int > &  d 
)

Loads one row of a text file as a numerical std::vector.

Returns
false on EOF or invalid format. The body of the function is implemented in MATH.cpp

◆ loadVector() [2/4]

bool mrpt::math::loadVector ( utils::CFileStream f,
std::vector< double > &  d 
)

Loads one row of a text file as a numerical std::vector.

Returns
false on EOF or invalid format. The body of the function is implemented in MATH.cpp

◆ loadVector() [3/4]

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).

const double numbers[] = { 1,2,3,5,6,7,8,9,10 };
loadVector( v, numbers );
Note
This operator performs the appropiate type castings, if required.

Definition at line 213 of file base/include/mrpt/math/utils.h.

References MRPT_COMPILE_TIME_ASSERT.

◆ loadVector() [4/4]

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.

Definition at line 224 of file base/include/mrpt/math/utils.h.

References MRPT_COMPILE_TIME_ASSERT.

◆ medianFilter()

void mrpt::mrpt::math::medianFilter ( const std::vector< double > &  inV,
std::vector< double > &  outV,
const int &  winSize,
const int &  numberOfSigmas = 2 
)

Definition at line 1999 of file math.cpp.

References ASSERT_, min, and MRPT_UNUSED_PARAM.

◆ normalize()

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.

If the vector has a null norm, the output is a null vector.

Definition at line 116 of file base/include/mrpt/math/utils.h.

References mrpt::math::square().

Here is the call graph for this function:

◆ operator!()

template<class Derived >
Eigen::MatrixBase<Derived>::PlainObject mrpt::math::operator! ( const Eigen::MatrixBase< Derived > &  m)
inline

Unary inversion operator.

Definition at line 41 of file ops_matrices.h.

◆ operator*()

template<typename T1 , typename T2 >
std::vector<T1> mrpt::math::operator* ( const std::vector< T1 > &  a,
const std::vector< T2 > &  b 
)
inline

a*b (element-wise multiplication)

Definition at line 62 of file ops_vectors.h.

References ASSERT_EQUAL_.

◆ operator*=() [1/2]

template<typename T1 , typename T2 >
std::vector<T1>& mrpt::math::operator*= ( std::vector< T1 > &  a,
const std::vector< T2 > &  b 
)
inline

a*=b (element-wise multiplication)

Definition at line 43 of file ops_vectors.h.

References ASSERT_EQUAL_.

◆ operator*=() [2/2]

template<typename T1 >
std::vector<T1>& mrpt::math::operator*= ( std::vector< T1 > &  a,
const T1  b 
)
inline

a*=k (multiplication by a constant)

Definition at line 53 of file ops_vectors.h.

◆ operator+()

template<typename T1 , typename T2 >
std::vector<T1> mrpt::math::operator+ ( const std::vector< T1 > &  a,
const std::vector< T2 > &  b 
)
inline

a+b (element-wise sum)

Definition at line 93 of file ops_vectors.h.

References ASSERT_EQUAL_.

◆ operator+=() [1/2]

template<typename T1 , typename T2 >
std::vector<T1>& mrpt::math::operator+= ( std::vector< T1 > &  a,
const std::vector< T2 > &  b 
)
inline

a+=b (element-wise sum)

Definition at line 74 of file ops_vectors.h.

References ASSERT_EQUAL_.

◆ operator+=() [2/2]

template<typename T1 >
std::vector<T1>& mrpt::math::operator+= ( std::vector< T1 > &  a,
const T1  b 
)
inline

a+=b (sum a constant)

Definition at line 84 of file ops_vectors.h.

◆ operator-()

template<typename T1 , typename T2 >
std::vector<T1> mrpt::math::operator- ( const std::vector< T1 > &  v1,
const std::vector< T2 > &  v2 
)
inline

Definition at line 104 of file ops_vectors.h.

References ASSERT_EQUAL_.

◆ operator<<() [1/7]

template<size_t NROWS, size_t NCOLS>
mrpt::utils::CStream& mrpt::math::operator<< ( mrpt::utils::CStream 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 68 of file matrix_serialization.h.

References mrpt::utils::CStream::WriteObject().

Here is the call graph for this function:

◆ operator<<() [2/7]

template<size_t NROWS, size_t NCOLS>
mrpt::utils::CStream& mrpt::math::operator<< ( mrpt::utils::CStream 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 79 of file matrix_serialization.h.

References mrpt::utils::CStream::WriteObject().

Here is the call graph for this function:

◆ operator<<() [3/7]

template<typename T , size_t NROWS, size_t NCOLS>
std::ostream& mrpt::math::operator<< ( std::ostream &  s,
const CMatrixFixedNumeric< T, NROWS, NCOLS > &  m 
)
inline

Dumps the matrix to a text ostream, adding a final "\n" to Eigen's default output.

Definition at line 96 of file matrix_serialization.h.

◆ operator<<() [4/7]

template<typename T >
std::ostream& mrpt::math::operator<< ( std::ostream &  s,
const CMatrixTemplateNumeric< T > &  m 
)
inline

Dumps the matrix to a text ostream, adding a final "\n" to Eigen's default output.

Definition at line 107 of file matrix_serialization.h.

◆ operator<<() [5/7]

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.

Definition at line 118 of file ops_vectors.h.

◆ operator<<() [6/7]

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.

Definition at line 133 of file ops_vectors.h.

◆ operator<<() [7/7]

template<typename T , size_t N>
mrpt::utils::CStream& mrpt::math::operator<< ( mrpt::utils::CStream ostrm,
const CArrayNumeric< T, N > &  a 
)

Binary dump of a CArrayNumeric<T,N> to a stream.

Definition at line 147 of file ops_vectors.h.

References mrpt::utils::CStream::WriteBufferFixEndianness().

Here is the call graph for this function:

◆ operator>>() [1/3]

template<size_t NROWS, size_t NCOLS>
mrpt::utils::CStream& mrpt::math::operator>> ( mrpt::utils::CStream 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_, and mrpt::format().

Here is the call graph for this function:

◆ operator>>() [2/3]

template<size_t NROWS, size_t NCOLS>
mrpt::utils::CStream& mrpt::math::operator>> ( mrpt::utils::CStream in,
CMatrixFixedNumeric< double, NROWS, NCOLS > &  M 
)

Read operator from a CStream.

The format is compatible with that of CMatrix & CMatrixD

Definition at line 50 of file matrix_serialization.h.

References ASSERTMSG_, and mrpt::format().

Here is the call graph for this function:

◆ operator>>() [3/3]

template<typename T , size_t N>
mrpt::utils::CStream& mrpt::math::operator>> ( mrpt::utils::CStream istrm,
CArrayNumeric< T, N > &  a 
)

Binary read of a CArrayNumeric<T,N> from a stream.

Definition at line 157 of file ops_vectors.h.

References ASSERTMSG_, mrpt::format(), and mrpt::utils::CStream::ReadBufferFixEndianness().

Here is the call graph for this function:

◆ operator~()

template<class Derived >
const Eigen::MatrixBase<Derived>::AdjointReturnType mrpt::math::operator~ ( const Eigen::MatrixBase< Derived > &  m)
inline

Transpose operator for matrices.

Definition at line 33 of file ops_matrices.h.

◆ round2up()

template<class T >
T mrpt::math::round2up ( val)

Round up to the nearest power of two of a given number.

Definition at line 162 of file base/include/mrpt/math/utils.h.

References THROW_EXCEPTION, and val.

Referenced by mrpt::math::cross_correlation_FFT(), mrpt::utils::CImage::cross_correlation_FFT(), mrpt::math::dft2_complex(), mrpt::math::idft2_complex(), and mrpt::math::idft2_real().

Here is the caller graph for this function:

◆ sequenceStdVec()

template<class T , T STEP>
std::vector<T> mrpt::math::sequenceStdVec ( first,
size_t  length 
)
inline

Generates a sequence of values [first,first+STEP,first+2*STEP,...].

See also
linspace, sequence

Definition at line 99 of file base/include/mrpt/math/utils.h.

◆ unwrap2PiSequence()

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.

See also
wrapToPi

Definition at line 74 of file wrap2pi.h.

References M_PI, and mrpt::math::wrapToPiInPlace().

Referenced by mrpt::poses::CPoseInterpolatorBase< 3 >::impl_interpolation().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wrapTo2Pi()

template<class T >
T mrpt::math::wrapTo2Pi ( a)
inline

Modifies the given angle to translate it into the [0,2pi[ range.

Note
Take care of not instancing this template for integer numbers, since it only works for float, double and long double.
See also
wrapToPi, wrapTo2Pi, unwrap2PiSequence

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wrapTo2PiInPlace()

template<class T >
void mrpt::math::wrapTo2PiInPlace ( T &  a)
inline

Modifies the given angle to translate it into the [0,2pi[ range.

Note
Take care of not instancing this template for integer numbers, since it only works for float, double and long double.
See also
wrapToPi, wrapTo2Pi, unwrap2PiSequence

Definition at line 28 of file wrap2pi.h.

References M_PI.

Referenced by mrpt::nav::CPTG_DiffDrive_C::inverseMap_WS2TP(), and mrpt::math::wrapTo2Pi().

Here is the caller graph for this function:

◆ wrapToPi()

template<class T >
T mrpt::math::wrapToPi ( a)
inline

Modifies the given angle to translate it into the ]-pi,pi] range.

Note
Take care of not instancing this template for integer numbers, since it only works for float, double and long double.
See also
wrapTo2Pi, wrapToPiInPlace, unwrap2PiSequence

Definition at line 53 of file wrap2pi.h.

References M_PI, and mrpt::math::wrapTo2Pi().

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::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::slam::CRangeBearingKFSLAM2D::OnObservationModel(), mrpt::math::TPose2D::operator+(), mrpt::math::TPose2D::operator-(), 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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wrapToPiInPlace()

template<class T >
void mrpt::math::wrapToPiInPlace ( T &  a)
inline



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019