MRPT  1.9.9
mrpt Namespace Reference

Detailed Description

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

Namespaces

 bayes
 The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorithms.
 
 comms
 Serial and networking devices and utilities.
 
 config
 
 containers
 
 db
 
 detectors
 
 expr
 
 global_settings
 Global variables to change the run-time behaviour of some MRPT classes within mrpt-base.
 
 graphs
 Abstract graph and tree data structures, plus generic graph algorithms.
 
 graphslam
 SLAM methods related to graphs of pose constraints.
 
 gui
 Classes for creating GUI windows for 2D and 3D visualization.
 
 hmtslam
 Classes related to the implementation of Hybrid Metric Topological (HMT) SLAM.
 
 hwdrivers
 Contains classes for various device interfaces.
 
 img
 
 internal
 
 io
 
 kinematics
 
 maps
 
 math
 This base provides a set of functions for maths stuff.
 
 mrpt
 
 nav
 
 obs
 This namespace contains representation of robot actions and observations.
 
 opengl
 The namespace for 3D scene representation and rendering.
 
 pbmap
 
 poses
 Classes for 2D/3D geometry representation, both of single values and probability density distributions (PDFs) in many forms.
 
 random
 A namespace of pseudo-random numbers generators of diferent distributions.
 
 rtti
 
 serialization
 
 slam
 
 system
 
 tfest
 Functions for estimating the optimal transformation between two frames of references given measurements of corresponding points.
 
 topography
 This namespace provides topography helper functions, coordinate transformations.
 
 typemeta
 
 utils
 
 vision
 Classes for computer vision, detectors, features, etc.
 

Classes

class  aligned_allocator_cpp11
 Aligned allocator that is compatible with C++11. More...
 
class  Clock
 Clock that is compatible with MRPT TTimeStamp representation. More...
 
struct  copiable_NULL_ptr
 A wrapper class for pointers that, if copied with the "=" operator, should be set to nullptr in the new copy. More...
 
struct  copiable_NULL_ptr_basic
 A wrapper class for pointers that, if copied with the "=" operator, should be set to nullptr in the copy. More...
 
struct  enable_if_t<(sizeof(T) > 0)> >
 
struct  ignored_copy_ptr
 A wrapper class for pointers whose copy operations from other objects of the same type are ignored, that is, doing "a=b;" has no effect neiter on "a" or "b". More...
 
struct  int_select_by_bytecount
 Usage: int_select_by_bytecount<N>type var; allows defining var as a signed integer with, at least, N bytes. More...
 
struct  int_select_by_bytecount< 1 >
 
struct  int_select_by_bytecount< 2 >
 
struct  int_select_by_bytecount< 3 >
 
struct  int_select_by_bytecount< 4 >
 
struct  int_select_by_bytecount< 8 >
 
struct  is_defined
 Checks if type is defined (fails for forward declarations). More...
 
struct  is_shared_ptr
 This is useful for checking ::Ptr types. More...
 
struct  is_shared_ptr< std::shared_ptr< T > >
 
struct  non_copiable_ptr
 A wrapper class for pointers that can NOT be copied with "=" operator, raising an exception at runtime if a copy is attempted. More...
 
struct  non_copiable_ptr_basic
 A wrapper class for pointers that can NOT be copied with "=" operator, raising an exception at runtime if a copy is attempted. More...
 
struct  ptr_cast
 Converts a polymorphic smart pointer Base::Ptr to Derived::Ptr, in a way compatible with MRPT >=1.5.4 and MRPT 2.x series. More...
 
struct  safe_ptr
 A wrapper class for pointers that can be safely copied with "=" operator without problems. More...
 
struct  safe_ptr_basic
 A wrapper class for pointers that can be safely copied with "=" operator without problems. More...
 
struct  uint_select_by_bytecount
 Usage: uint_select_by_bytecount<N>type var; allows defining var as a unsigned integer with, at least, N bytes. More...
 
struct  uint_select_by_bytecount< 1 >
 
struct  uint_select_by_bytecount< 2 >
 
struct  uint_select_by_bytecount< 3 >
 
struct  uint_select_by_bytecount< 4 >
 
struct  uint_select_by_bytecount< 8 >
 

Typedefs

template<class T >
using aligned_std_basicstring = std::basic_string< T, std::char_traits< T >, mrpt::aligned_allocator_cpp11< T > >
 
template<class T >
using aligned_std_vector = std::vector< T, mrpt::aligned_allocator_cpp11< T > >
 
template<class T >
using optional_ref = std::optional< std::reference_wrapper< T > >
 Shorter name for std::optional<std::reference_wrapper<T>> More...
 
template<typename T >
using pimpl = spimpl::impl_ptr< T >
 
using void_ptr = safe_ptr_basic< void >
 
using void_ptr_noncopy = non_copiable_ptr_basic< void >
 

Functions

template<class Visitor , class... T>
void visit_each (const Visitor &vis, T &&... t)
 
voidaligned_malloc (size_t size, size_t alignment)
 
voidaligned_realloc (void *ptr, size_t size, size_t alignment)
 
void aligned_free (void *ptr)
 
voidaligned_calloc (size_t bytes, size_t alignment)
 Identical to aligned_malloc, but it zeroes the reserved memory block. More...
 
template<class T >
square (const T x)
 Inline function for the square of a number. More...
 
template<class T >
hypot_fast (const T x, const T y)
 Faster version of std::hypot(), to use when overflow is not an issue and we prefer fast code. More...
 
double DEG2RAD (const double x)
 Degrees to radians. More...
 
float DEG2RAD (const float x)
 Degrees to radians. More...
 
double DEG2RAD (const int x)
 Degrees to radians. More...
 
double RAD2DEG (const double x)
 Radians to degrees. More...
 
float RAD2DEG (const float x)
 Radians to degrees. More...
 
long double DEG2RAD (const long double x)
 Degrees to radians. More...
 
long double RAD2DEG (const long double x)
 Radians to degrees. More...
 
template<typename T >
int sign (T x)
 Returns the sign of X as "1" or "-1". More...
 
template<typename T >
int signWithZero (T x)
 Returns the sign of X as "0", "1" or "-1". More...
 
template<typename T >
lowestPositive (const T a, const T b)
 Returns the lowest, possitive among two numbers. More...
 
template<typename T >
abs_diff (const T a, const T b)
 Efficient and portable evaluation of the absolute difference of two unsigned integer values (but will also work for signed and floating point types) More...
 
template<typename T >
const T min3 (const T &A, const T &B, const T &C)
 
template<typename T >
const T max3 (const T &A, const T &B, const T &C)
 
template<typename T >
int fix (T x)
 Rounds toward zero. More...
 
template<typename T , typename K >
void keep_min (T &var, const K test_val)
 If the second argument is below the first one, set the first argument to this lower value. More...
 
template<typename T , typename K >
void keep_max (T &var, const K test_val)
 If the second argument is above the first one, set the first argument to this higher value. More...
 
template<typename T >
void saturate (T &var, const T sat_min, const T sat_max)
 Saturate the value of var (the variable gets modified) so it does not get out of [min,max]. More...
 
template<typename T >
saturate_val (const T &value, const T sat_min, const T sat_max)
 Like saturate() but it returns the value instead of modifying the variable. More...
 
template<class T >
round2up (T val)
 Round up to the nearest power of two of a given number. More...
 
template<class VECTOR_T >
void vector_strong_clear (VECTOR_T &v)
 Like calling a std::vector<>'s clear() method, but really forcing deallocating the memory. More...
 
std::string exception_to_str (const std::exception &e)
 Builds a nice textual representation of a nested exception, which if generated using MRPT macros (THROW_EXCEPTION,...) in between MRPT_START/MRPT_END macros, will contain function names and line numbers across the call stack at the original throw point. More...
 
std::string format (const char *fmt,...) MRPT_printf_format_check(1
 A std::string version of C sprintf. More...
 
template<typename T >
std::string std::string to_string (T v)
 Just like std::to_string(), but with an overloaded version for std::string arguments. More...
 
template<>
std::string to_string (std::string v)
 
template<>
std::string to_string (bool v)
 
template<>
std::string to_string (const char *s)
 
template<typename T >
from_string (const std::string &s, const T &defValue=T{}, bool throw_on_error=true)
 Converts from string to any data type that supports reading (>>) from a text stream. More...
 
template<class T >
get_env (const std::string &varname, const T &defValue=T())
 Reads an environment variable, with a default value if not present. More...
 
template<class T , class... Args>
pimpl< T > make_impl (Args &&... args)
 
void reverseBytesInPlace (bool &v_in_out)
 Reverse the order of the bytes of a given type (useful for transforming btw little/big endian) More...
 
void reverseBytesInPlace (uint8_t &v_in_out)
 
void reverseBytesInPlace (int8_t &v_in_out)
 
void reverseBytesInPlace (uint16_t &v_in_out)
 
void reverseBytesInPlace (int16_t &v_in_out)
 
void reverseBytesInPlace (uint32_t &v_in_out)
 
void reverseBytesInPlace (int32_t &v_in_out)
 
void reverseBytesInPlace (uint64_t &v_in_out)
 
void reverseBytesInPlace (int64_t &v_in_out)
 
void reverseBytesInPlace (float &v_in_out)
 
void reverseBytesInPlace (double &v_in_out)
 
void reverseBytesInPlace (long double &v_in_out)
 
template<class T >
void reverseBytes (const T &v_in, T &v_out)
 Reverse the order of the bytes of a given type (useful for transforming btw little/big endian) More...
 
template<typename T >
int round (const T value)
 Returns the closer integer (int) to x. More...
 
template<typename T >
long round_long (const T value)
 Returns the closer integer (long) to x. More...
 
template<class T >
round_10power (T val, int power10)
 Round a decimal number up to the given 10'th power (eg, to 1000,100,10, and also fractions) power10 means round up to: 1 -> 10, 2 -> 100, 3 -> 1000, ... More...
 

Variables

template<class T >
constexpr bool is_defined_v = is_defined<T>::value
 

Typedef Documentation

◆ aligned_std_basicstring

template<class T >
using mrpt::aligned_std_basicstring = typedef std::basic_string<T, std::char_traits<T>, mrpt::aligned_allocator_cpp11<T> >

Definition at line 16 of file aligned_std_basicstring.h.

◆ aligned_std_vector

template<class T >
using mrpt::aligned_std_vector = typedef std::vector<T, mrpt::aligned_allocator_cpp11<T> >

Definition at line 15 of file aligned_std_vector.h.

◆ pimpl

template<typename T >
using mrpt::pimpl = typedef spimpl::impl_ptr<T>

Definition at line 15 of file pimpl.h.

◆ void_ptr

Definition at line 357 of file safe_pointers.h.

◆ void_ptr_noncopy

Definition at line 358 of file safe_pointers.h.

Function Documentation

◆ abs_diff()

template<typename T >
T mrpt::abs_diff ( const T  a,
const T  b 
)
inline

Efficient and portable evaluation of the absolute difference of two unsigned integer values (but will also work for signed and floating point types)

Definition at line 97 of file core/include/mrpt/core/bits_math.h.

References min.

Referenced by mrpt::nav::CHolonomicND::calcRepresentativeSectorForGap(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), and mrpt::nav::CHolonomicND::evaluateGaps().

Here is the caller graph for this function:

◆ aligned_calloc()

void * mrpt::aligned_calloc ( size_t  bytes,
size_t  alignment 
)
inline

Identical to aligned_malloc, but it zeroes the reserved memory block.

Definition at line 16 of file aligned_malloc.cpp.

References aligned_malloc().

Here is the call graph for this function:

◆ aligned_free()

void mrpt::aligned_free ( void ptr)

Definition at line 40 of file aligned_malloc.cpp.

Referenced by mrpt::aligned_allocator_cpp11< T, AligmentBytes >::deallocate().

Here is the caller graph for this function:

◆ aligned_malloc()

void * mrpt::aligned_malloc ( size_t  size,
size_t  alignment 
)

Definition at line 22 of file aligned_malloc.cpp.

Referenced by aligned_calloc(), and mrpt::aligned_allocator_cpp11< T, AligmentBytes >::allocate().

Here is the caller graph for this function:

◆ aligned_realloc()

void * mrpt::aligned_realloc ( void ptr,
size_t  size,
size_t  alignment 
)

Definition at line 48 of file aligned_malloc.cpp.

◆ DEG2RAD() [1/4]

double mrpt::DEG2RAD ( const double  x)
inline

Degrees to radians.

Examples:
serialization_json_example/test.cpp.

Definition at line 43 of file core/include/mrpt/core/bits_math.h.

References M_PI.

Referenced by addBar_A(), ICPTests::align2scans(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::alignOpticalWithMRPTFrame(), mrpt::slam::CGridMapAligner::AlignPDF_correlation(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), atan2_lut_test(), mrpt::obs::carmen_log_parse_line(), mrpt::opengl::CFrustum::CFrustum(), GraphSlamLevMarqTest< my_graph_t >::create_ring_path(), mrpt::obs::CObservation3DRangeScan::doDepthAndIntensityCamerasCoincide(), mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), mrpt::math::TTwist2D::fromString(), mrpt::math::TPose2D::fromString(), mrpt::math::TTwist3D::fromString(), mrpt::math::TPose3D::fromString(), mrpt::poses::CPose2D::fromString(), mrpt::poses::CPose3D::fromString(), generate_points(), ICPTests::generateObjects(), mrpt::maps::CBeacon::generateRingSOG(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getAlignCmd(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::opengl::stock_objects::Househam_Sprayer(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::obs::VelodyneCalibration::internal_loadFromXMLNode(), mrpt::kinematics::CVehicleSimul_Holo::internal_simulControlStep(), mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::hwdrivers::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserUSB::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUIntersense::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSkeletonTracker::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGyroKVHDSP3000::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboPeakLidar::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIbeoLuxETH::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSICKTim561Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserSerial::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardSonars::loadConfig_sensorSpecific(), mrpt::hwdrivers::CLMS100Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CVelodyneScanner::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2_RGBD360::loadConfig_sensorSpecific(), mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), mrpt::nav::CPTG_Holo_Blend::loadDefaultParams(), mrpt::nav::CPTG_DiffDrive_alpha::loadDefaultParams(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::loadDefaultParams(), mrpt::slam::CICP::TConfigParams::loadFromConfigFile(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::loadFromConfigFile(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_TBI(), mrpt::slam::CRangeBearingKFSLAM2D::OnPreComputingPredictions(), mrpt::slam::CRangeBearingKFSLAM::OnPreComputingPredictions(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), mrpt::hwdrivers::CSkeletonTracker::processPreviewNone(), ransac_data_assoc_run(), mrpt::opengl::CRenderizable::readFromStreamRender(), mrpt::opengl::COpenGLViewport::render(), mrpt::hwdrivers::CNTRIPClient::retrieveListOfMountpoints(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), run_rnav_test(), run_test_pf_localization(), mrpt::tfest::se2_l2_robust(), mrpt::opengl::CFrustum::setHorzFOV(), mrpt::opengl::CFrustum::setHorzFOVAsymmetric(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::opengl::CFrustum::setVertFOV(), mrpt::opengl::CFrustum::setVertFOVAsymmetric(), mrpt::maps::COccupancyGridMap2D::sonarSimulator(), mrpt::topography::TDatum10Params::TDatum10Params(), mrpt::topography::TDatum7Params::TDatum7Params(), mrpt::topography::TDatumHelmert2D::TDatumHelmert2D(), mrpt::topography::TDatumHelmert3D::TDatumHelmert3D(), mrpt::topography::TDatumTransfInterpolation::TDatumTransfInterpolation(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), TEST(), TEST_F(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::TOptions(), mrpt::hmtslam::CHMTSLAM::TOptions::TOptions(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::updateLaserScansVisualization(), mrpt::gui::CGlCanvasBase::updatePan(), mrpt::gui::CGlCanvasBase::updateRotate(), and mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateVisuals().

Here is the caller graph for this function:

◆ DEG2RAD() [2/4]

float mrpt::DEG2RAD ( const float  x)
inline

Degrees to radians.

Definition at line 45 of file core/include/mrpt/core/bits_math.h.

References M_PI.

◆ DEG2RAD() [3/4]

double mrpt::DEG2RAD ( const int  x)
inline

Degrees to radians.

Definition at line 47 of file core/include/mrpt/core/bits_math.h.

References M_PI.

◆ DEG2RAD() [4/4]

long double mrpt::DEG2RAD ( const long double  x)
inline

Degrees to radians.

Definition at line 57 of file core/include/mrpt/core/bits_math.h.

References M_PIl.

◆ fix()

template<typename T >
int mrpt::fix ( x)
inline

Rounds toward zero.

Definition at line 115 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::topography::GeodeticToUTM(), and mrpt::topography::geodeticToUTM().

Here is the caller graph for this function:

◆ hypot_fast()

template<class T >
T mrpt::hypot_fast ( const T  x,
const T  y 
)
inline

Faster version of std::hypot(), to use when overflow is not an issue and we prefer fast code.

Definition at line 27 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CPTG_RobotShape_Polygonal::evalClearanceToRobotShape(), mrpt::nav::CPTG_RobotShape_Circular::evalClearanceToRobotShape(), mrpt::nav::CPTG_RobotShape_Circular::isPointInsideRobotShape(), and mrpt::math::TPose2D::norm().

Here is the caller graph for this function:

◆ keep_max()

template<typename T , typename K >
void mrpt::keep_max ( T &  var,
const K  test_val 
)
inline

If the second argument is above the first one, set the first argument to this higher value.

Definition at line 131 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CHolonomicND::calcRepresentativeSectorForGap(), mrpt::opengl::CFrustum::CFrustum(), mrpt::nav::CMultiObjectiveMotionOptimizerBase::decide(), mrpt::system::CTimeLogger::do_leave(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::nav::CPTG_RobotShape_Polygonal::evalClearanceToRobotShape(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), mrpt::math::MatrixBlockSparseCols< Scalar, NROWS, NCOLS, INFO, HAS_REMAP, INDEX_REMAP_MAP_IMPL >::findCurrentNumberOfRows(), mrpt::nav::CHolonomicND::gapsEstimator(), mrpt::slam::CIncrementalMapPartitioner::getAs3DScene(), mrpt::math::TPolygon2D::getBoundingBox(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::poses::CPoseInterpolatorBase< 3 >::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CSetOfLines::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::vision::TKeyPointList_templ< TKeyPoint >::getMaxID(), mrpt::vision::CFeatureList::getMaxID(), mrpt::maps::CHeightGridMap2D_Base::getMinMaxHeight(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::vision::matchFeatures(), mrpt::math::maximum(), mrpt::math::minimum_maximum(), mrpt::opengl::COctreePointRenderer< CPointCloudColoured >::octree_recursive_render(), mrpt::graphslam::optimize_graph_spa_levmarq(), mrpt::hwdrivers::CGPSInterface::parseBuffer(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfAuxiliaryPFOptimal(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::system::CTimeLogger::registerUserMeasure(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::render_dl(), mrpt::nav::PlannerTPS_VirtualBase::renderMoveTree(), mrpt::opengl::CFrustum::setHorzFOV(), mrpt::opengl::CFrustum::setHorzFOVAsymmetric(), mrpt::nav::CPTG_RobotShape_Polygonal::setRobotShape(), mrpt::opengl::CFrustum::setVertFOV(), mrpt::opengl::CFrustum::setVertFOVAsymmetric(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), mrpt::opengl::CMesh::updateColorsMatrix(), and mrpt::vision::CMatchedFeatureList::updateMaxID().

Here is the caller graph for this function:

◆ keep_min()

template<typename T , typename K >
void mrpt::keep_min ( T &  var,
const K  test_val 
)
inline

If the second argument is below the first one, set the first argument to this lower value.

Definition at line 124 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CHolonomicND::calcRepresentativeSectorForGap(), mrpt::opengl::CFrustum::CFrustum(), mrpt::maps::COccupancyGridMap2D::computeLikelihoodField_Thrun(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::system::CTimeLogger::do_leave(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), find_chessboard_corners_multiple(), mrpt::nav::CHolonomicND::gapsEstimator(), mrpt::slam::CIncrementalMapPartitioner::getAs3DScene(), mrpt::math::TPolygon2D::getBoundingBox(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::poses::CPoseInterpolatorBase< 3 >::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CSetOfLines::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::maps::CHeightGridMap2D_Base::getMinMaxHeight(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihoodPointCloud3D(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_TPObsDistancePostprocess(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), mrpt::math::minimum(), mrpt::math::minimum_maximum(), mrpt::opengl::COctreePointRenderer< CPointCloudColoured >::octree_recursive_render(), mrpt::system::CTimeLogger::registerUserMeasure(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::render_dl(), mrpt::opengl::CFrustum::setHorzFOV(), mrpt::opengl::CFrustum::setHorzFOVAsymmetric(), mrpt::opengl::CFrustum::setVertFOV(), mrpt::opengl::CFrustum::setVertFOVAsymmetric(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), TEST(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), mrpt::opengl::CMesh::updateColorsMatrix(), and mrpt::nav::CPTG_Holo_Blend::updateTPObstacleSingle().

Here is the caller graph for this function:

◆ lowestPositive()

template<typename T >
T mrpt::lowestPositive ( const T  a,
const T  b 
)

Returns the lowest, possitive among two numbers.

If both are non-positive (<=0), the lowest one is returned.

Definition at line 83 of file core/include/mrpt/core/bits_math.h.

◆ make_impl()

template<class T , class... Args>
pimpl<T> mrpt::make_impl ( Args &&...  args)
inline

Definition at line 18 of file pimpl.h.

◆ max3()

template<typename T >
const T mrpt::max3 ( const T &  A,
const T &  B,
const T &  C 
)
inline

Definition at line 108 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::maps::COccupancyGridMap3D::insertRay(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), and mrpt::img::rgb2hsv().

Here is the caller graph for this function:

◆ min3()

template<typename T >
const T mrpt::min3 ( const T &  A,
const T &  B,
const T &  C 
)
inline

Definition at line 103 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CHolonomicND::evaluateGaps(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), and mrpt::img::rgb2hsv().

Here is the caller graph for this function:

◆ RAD2DEG() [1/3]

double mrpt::RAD2DEG ( const double  x)
inline

Radians to degrees.

Definition at line 49 of file core/include/mrpt/core/bits_math.h.

References M_PI.

Referenced by mrpt::slam::CGridMapAligner::AlignPDF_correlation(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::math::TTwist2D::asString(), mrpt::math::TPose2D::asString(), mrpt::math::TTwist3D::asString(), mrpt::math::TPose3D::asString(), mrpt::poses::CPose2D::asString(), mrpt::poses::CPose3D::asString(), mrpt::obs::CObservationBearingRange::debugPrintOut(), mrpt::hmtslam::CLocalMetricHypothesis::dumpAsText(), mrpt::slam::TKLDParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderICP::TConfigParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions::dumpToTextStream(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::vision::TMultiResDescMatchOptions::dumpToTextStream(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams::getAsString(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::getAsString(), mrpt::nav::TWaypoint::getAsText(), mrpt::nav::CPTG_DiffDrive_alpha::getDescription(), mrpt::obs::CObservationRange::getDescriptionAsText(), mrpt::obs::CObservationBearingRange::getDescriptionAsText(), mrpt::obs::CObservationIMU::getDescriptionAsText(), mrpt::opengl::CFrustum::getHorzFOV(), mrpt::opengl::CFrustum::getHorzFOVLeft(), mrpt::opengl::CFrustum::getHorzFOVRight(), mrpt::opengl::CRenderizable::getPosePitch(), mrpt::opengl::CRenderizable::getPoseRoll(), mrpt::opengl::CRenderizable::getPoseYaw(), mrpt::opengl::CFrustum::getVertFOV(), mrpt::opengl::CFrustum::getVertFOVDown(), mrpt::opengl::CFrustum::getVertFOVUp(), mrpt::slam::CICP::TConfigParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_TBI(), mrpt::poses::operator<<(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), mrpt::hwdrivers::CNTRIPClient::retrieveListOfMountpoints(), mrpt::nav::CPTG_Holo_Blend::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_alpha::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::saveToConfigFile(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::hwdrivers::CServoeNeck::setAngle(), TEST(), mrpt::hwdrivers::CHokuyoURG::turnOn(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().

Here is the caller graph for this function:

◆ RAD2DEG() [2/3]

float mrpt::RAD2DEG ( const float  x)
inline

Radians to degrees.

Definition at line 51 of file core/include/mrpt/core/bits_math.h.

References M_PI.

◆ RAD2DEG() [3/3]

long double mrpt::RAD2DEG ( const long double  x)
inline

Radians to degrees.

Definition at line 59 of file core/include/mrpt/core/bits_math.h.

References M_PIl.

◆ round2up()

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

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

Definition at line 156 of file core/include/mrpt/core/bits_math.h.

References val.

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

Here is the caller graph for this function:

◆ saturate()

template<typename T >
void mrpt::saturate ( T &  var,
const T  sat_min,
const T  sat_max 
)
inline

Saturate the value of var (the variable gets modified) so it does not get out of [min,max].

Definition at line 138 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::maps::CRandomFieldGridMap2D::getAsMatrix(), and mrpt::maps::CRandomFieldGridMap2D::updateMapEstimation_GMRF().

Here is the caller graph for this function:

◆ saturate_val()

template<typename T >
T mrpt::saturate_val ( const T &  value,
const T  sat_min,
const T  sat_max 
)
inline

Like saturate() but it returns the value instead of modifying the variable.

Definition at line 146 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::maps::CRandomFieldGridMap2D::getAs3DObject(), and mrpt::maps::CRandomFieldGridMap2D::saveAsMatlab3DGraph().

Here is the caller graph for this function:

◆ sign()

◆ signWithZero()

template<typename T >
int mrpt::signWithZero ( x)
inline

Returns the sign of X as "0", "1" or "-1".

Definition at line 75 of file core/include/mrpt/core/bits_math.h.

References sign().

Referenced by mrpt::nav::CPTG_Holo_Blend::directionToMotionCommand(), mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getAlignCmd(), and mrpt::nav::CPTG_Holo_Blend::getPathPose().

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

◆ square()

template<class T >
T mrpt::square ( const T  x)
inline

Inline function for the square of a number.

Definition at line 19 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::opengl::CPolyhedron::TPolyhedronFace::area(), mrpt::poses::CPosePDFGaussian::assureMinCovariance(), aux_projectPoint_with_distortion(), mrpt::graphs::detail::graph_ops< graph_t >::auxEuclid2Dist(), mrpt::graphs::detail::graph_ops< graph_t >::auxMaha2Dist(), mrpt::poses::CPointPDFSOG::bayesianFusion(), mrpt::maps::CGasConcentrationGridMap2D::build_Gaussian_Wind_Grid(), mrpt::vision::CDifodo::calculateDepthDerivatives(), mrpt::vision::checkerBoardCameraCalibration(), mrpt::maps::CPointsMap::clipOutOfRange(), mrpt::math::closestSquareDistanceFromPointToLine(), mrpt::nav::collision_free_dist_segment_circ_robot(), mrpt::poses::CPose3DQuat::composePoint(), mrpt::maps::CLandmarksMap::compute3DMatchingRatio(), mrpt::maps::COccupancyGridMap2D::computeClearance(), mrpt::maps::CRandomFieldGridMap2D::computeConfidenceCellValue_DM_DMV(), mrpt::obs::CActionRobotMovement2D::computeFromOdometry_modelGaussian(), mrpt::graphslam::computeJacobiansAndErrors(), mrpt::poses::CPointPDFParticles::computeKurtosis(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::COccupancyGridMap2D::computeLikelihoodField_II(), mrpt::maps::COccupancyGridMap2D::computeLikelihoodField_Thrun(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::maps::CRandomFieldGridMap2D::computeMeanCellValue_DM_DMV(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::nav::PlannerSimple2D::computePath(), mrpt::maps::COccupancyGridMap2D::computePathCost(), mrpt::maps::CRandomFieldGridMap2D::computeVarCellValue_DM_DMV(), mrpt::vision::CDifodo::computeWeights(), mrpt::obs::detail::cost_func(), mrpt::opengl::CPolyhedron::CreateIcosahedron(), mrpt::opengl::CPolyhedron::CreateJohnsonSolidWithConstantBase(), mrpt::opengl::CPolyhedron::CreateRhombicuboctahedron(), mrpt::math::cross_correlation_FFT(), mrpt::img::CImage::cross_correlation_FFT(), mrpt::vision::CFeature::descriptorBLDDistanceTo(), mrpt::vision::CFeature::descriptorLATCHDistanceTo(), mrpt::vision::CFeature::descriptorSIFTDistanceTo(), mrpt::vision::CFeature::descriptorSpinImgDistanceTo(), mrpt::vision::CFeature::descriptorSURFDistanceTo(), mrpt::maps::CPointsMap::determineMatching2D(), mrpt::maps::COccupancyGridMap2D::determineMatching2D(), mrpt::maps::CPointsMap::determineMatching3D(), mrpt::nav::PoseDistanceMetric< TNodeSE2 >::distance(), mrpt::poses::CPose2D::distance2DFrobeniusTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance2DToSquare(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance3DToSquare(), mrpt::poses::CPose3D::distanceEuclidean6D(), mrpt::math::distanceSqrBetweenPoints(), mrpt::math::TPoint3D::distanceTo(), mrpt::bayes::CParticleFilterDataImpl< CMultiMetricMapPDF, mrpt::bayes::CParticleFilterData< CRBPFParticleData >::CParticleList >::ESS(), mrpt::poses::CPointPDFSOG::ESS(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::evalPWConsistenciesMatrix(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), mrpt::nav::CHolonomicND::evaluateGaps(), mrpt::poses::CPosePDFParticles::evaluatePDF_parzen(), mrpt::obs::CObservation2DRangeScanWithUncertainty::evaluateScanLikelihood(), mrpt::bayes::CParticleFilter::executeOn(), mrpt::maps::CPointsMap::extractCylinder(), mrpt::math::fft_real(), mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::vision::frameJac(), mrpt::maps::CPointsMap::fuseWith(), mrpt::math::generateAxisBaseFromDirection(), mrpt::maps::CBeacon::generateRingSOG(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::GeodeticToUTM(), mrpt::math::getAngleBisector(), mrpt::maps::COccupancyGridMap2D::getArea(), mrpt::maps::CRandomFieldGridMap2D::getAs3DObject(), mrpt::poses::CPointPDFParticles::getCovarianceAndMean(), mrpt::poses::CPose3DPDFParticles::getCovarianceAndMean(), mrpt::poses::CPosePDFParticles::getCovarianceAndMean(), mrpt::opengl::CPolyhedron::getDual(), getHeight(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::getLargestDistanceFromOrigin(), mrpt::maps::CPointsMap::getLargestDistanceFromOrigin(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::slam::CICP::ICP_Method_LM(), insertCupola(), mrpt::maps::CRandomFieldGridMap2D::insertIndividualReading(), mrpt::maps::CRandomFieldGridMap2D::insertObservation_KernelDM_DMV(), mrpt::maps::CRandomFieldGridMap2D::insertObservation_KF(), mrpt::maps::CRandomFieldGridMap2D::insertObservation_KF2(), mrpt::maps::CRandomFieldGridMap2D::internal_clear(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), mrpt::maps::CReflectivityGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihoodPointCloud3D(), mrpt::vision::CFeatureExtraction::internal_computeSpinImageDescriptors(), mrpt::maps::CLandmarksMap::internal_CreateFromMapDefinition(), mrpt::vision::CFeature::internal_distanceBetweenPolarImages(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::CWirelessPowerGridMap2D::internal_insertObservation(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::vision::CGenericFeatureTracker::internal_trackFeatures(), mrpt::poses::CPose3DQuat::inverseComposePoint(), mrpt::nav::CPTG_Holo_Blend::inverseMap_WS2TP(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(), mrpt::img::CCanvas::line(), mrpt::math::CQuaternion< T >::ln_noresize(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_TBI(), mrpt::math::meanAndCovMat(), mrpt::math::meanAndCovVec(), mrpt::math::meanAndStd(), mrpt::math::meanAndStdColumns(), mrpt::math::minDistBetweenLines(), mrpt::math::minimumDistanceFromPointToSegment(), mrpt::nav::CHolonomicFullEval::navigate(), mrpt::math::ncc_vector(), mrpt::math::noncentralChi2CDF(), mrpt::math::TPose3DQuat::norm(), mrpt::math::TPose3D::norm(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::norm(), mrpt::math::normalize(), mrpt::math::normalPDF(), mrpt::math::CQuaternion< T >::normSqr(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetObservationNoise(), mrpt::slam::CRangeBearingKFSLAM::OnGetObservationNoise(), mrpt::slam::CRangeBearingKFSLAM::OnNormalizeStateVector(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationJacobians(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationModel(), mrpt::slam::CRangeBearingKFSLAM2D::OnTransitionNoise(), mrpt::slam::CRangeBearingKFSLAM::OnTransitionNoise(), mrpt::graphslam::optimize_graph_spa_levmarq(), mrpt::topography::path_from_rtk_gps(), mrpt::vision::CDifodo::performWarping(), mrpt::vision::pointJac(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::maps::CRandomFieldGridMap2D::predictMeasurement(), mrpt::poses::CPoint2DPDFGaussian::productIntegralNormalizedWith(), mrpt::poses::CPointPDFGaussian::productIntegralNormalizedWith(), mrpt::poses::CPointPDFGaussian::productIntegralNormalizedWith2D(), project_point(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_with_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::nav::CPTG_DiffDrive_CCS::PTG_IsIntoDomain(), mrpt::nav::CPTG_DiffDrive_CS::PTG_IsIntoDomain(), mrpt::nav::CPTG_DiffDrive_CC::PTG_IsIntoDomain(), mrpt::nav::CPTG_DiffDrive_CS::ptgDiffDriveSteeringFunction(), mrpt::nav::CPTG_DiffDrive_alpha::ptgDiffDriveSteeringFunction(), quickSolveEqn(), ransac_data_assoc_run(), mrpt::obs::CObservation3DRangeScan::recoverCameraCalibrationParameters(), mrpt::opengl::CArrow::render_dl(), mrpt::opengl::CVectorField3D::render_dl(), reprojectionResidualsElement(), mrpt::maps::CRandomFieldGridMap2D::resize(), mrpt::math::CQuaternion< T >::rpy_and_jacobian(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_observationLikelihood(), mrpt::maps::CBeaconMap::saveToTextFile(), mrpt::tfest::se2_l2(), mrpt::tfest::se2_l2_robust(), se3_l2_internal(), mrpt::tfest::se3_l2_robust(), mrpt::maps::CRandomFieldGridMap2D::setMeanAndSTD(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::math::TSegment2D::signedDistance(), mrpt::maps::CGasConcentrationGridMap2D::simulateAdvection(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), mrpt::math::slerp(), mrpt::math::TPose3D::SO3_to_yaw_pitch_roll(), solveEqn(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), mrpt::math::TPoint3D::sqrDistanceTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::sqrDistanceTo(), mrpt::maps::CPointsMap::squareDistanceToClosestCorrespondence(), mrpt::tfest::TMatchingPairList::squareErrorVector(), mrpt::math::squareNorm(), mrpt::vision::StereoObs2BRObs(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), TEST(), Pose3DQuatTests::test_invComposePointJacob(), mrpt::opengl::CCylinder::traceRay(), mrpt::opengl::CEllipsoid::traceRay(), mrpt::vision::detail::trackFeatures_addNewFeats< CFeatureList >(), mrpt::slam::COccupancyGridMapFeatureExtractor::uncached_extractFeatures(), mrpt::topography::UTMToGeodetic(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().

◆ to_string() [1/3]

template<>
std::string mrpt::to_string ( std::string  v)
inline

Definition at line 35 of file format.h.

◆ to_string() [2/3]

template<>
std::string mrpt::to_string ( bool  v)
inline

Definition at line 40 of file format.h.

◆ to_string() [3/3]

template<>
std::string mrpt::to_string ( const char *  s)
inline

Definition at line 45 of file format.h.

Referenced by to_string().

Here is the caller graph for this function:

Variable Documentation

◆ is_defined_v

template<class T >
constexpr bool mrpt::is_defined_v = is_defined<T>::value
inline

Definition at line 30 of file is_defined.h.




Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019