This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Copyright (C) 2010 Hauke Strasdat Imperial College London Copyright (c) 2005-2018, Individual contributors, see AUTHORS file See: http://www.mrpt.org/Authors - All rights reserved.
bundle_adjuster.h is part of RobotVision.
RobotVision is free software: you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation, either version 3 of the License, or any later version.
RobotVision is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.
You should have received a copy of the GNU General Public License and the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.
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 | |
io | |
kinematics | |
maps | |
math | |
This base provides a set of functions for maths stuff. | |
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 | |
This namespace provides a OS-independent interface to many useful functions: filenames manipulation, time and date, string parsing, file I/O, threading, memory allocation, etc. | |
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... | |
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 | 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_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_deque = std::deque< T, mrpt::aligned_allocator_cpp11< T > > |
template<class KEY , class VALUE > | |
using | aligned_std_map = std::map< KEY, VALUE, std::less< KEY >, mrpt::aligned_allocator_cpp11< std::pair< const KEY, VALUE > >> |
template<class KEY , class VALUE > | |
using | aligned_std_multimap = std::multimap< KEY, VALUE, std::less< KEY >, mrpt::aligned_allocator_cpp11< std::pair< const KEY, VALUE > >> |
template<class T > | |
using | aligned_std_vector = std::vector< T, mrpt::aligned_allocator_cpp11< T > > |
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 | |
void * | aligned_malloc (size_t size, size_t alignment) |
void * | aligned_realloc (void *ptr, size_t size, size_t alignment) |
void | aligned_free (void *ptr) |
void * | aligned_calloc (size_t bytes, size_t alignment) |
Identical to aligned_malloc, but it zeroes the reserved memory block. More... | |
template<typename T , class... Args> | |
std::shared_ptr< T > | make_aligned_shared (Args &&... args) |
Creates a shared_ptr with aligned memory via aligned_allocator_cpp11<>. More... | |
template<class T > | |
T | square (const T x) |
Inline function for the square of a number. More... | |
template<class T > | |
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 > | |
T | lowestPositive (const T a, const T b) |
Returns the lowest, possitive among two numbers. More... | |
template<typename T > | |
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 > | |
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 > | |
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 | 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<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 > | |
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 | |
std::string | MRPT_GLOBAL_UNITTEST_SRC_DIR |
using mrpt::aligned_std_deque = typedef std::deque<T, mrpt::aligned_allocator_cpp11<T> > |
Definition at line 15 of file aligned_std_deque.h.
using mrpt::aligned_std_map = typedef std::map<KEY, VALUE, std::less<KEY>, mrpt::aligned_allocator_cpp11<std::pair<const KEY, VALUE> >> |
Definition at line 17 of file aligned_std_map.h.
using mrpt::aligned_std_multimap = typedef std::multimap<KEY, VALUE, std::less<KEY>, mrpt::aligned_allocator_cpp11<std::pair<const KEY, VALUE> >> |
Definition at line 22 of file aligned_std_map.h.
using mrpt::aligned_std_vector = typedef std::vector<T, mrpt::aligned_allocator_cpp11<T> > |
Definition at line 15 of file aligned_std_vector.h.
using mrpt::pimpl = typedef spimpl::impl_ptr<T> |
using mrpt::void_ptr = typedef safe_ptr_basic<void> |
Definition at line 357 of file safe_pointers.h.
using mrpt::void_ptr_noncopy = typedef non_copiable_ptr_basic<void> |
Definition at line 358 of file safe_pointers.h.
|
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().
|
inline |
Identical to aligned_malloc, but it zeroes the reserved memory block.
Definition at line 15 of file aligned_malloc.cpp.
References aligned_malloc().
Definition at line 31 of file aligned_malloc.cpp.
Referenced by mrpt::aligned_allocator_cpp11< T, AligmentBytes >::deallocate(), and mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::realloc().
void * mrpt::aligned_malloc | ( | size_t | size, |
size_t | alignment | ||
) |
Definition at line 21 of file aligned_malloc.cpp.
Referenced by aligned_calloc(), mrpt::aligned_allocator_cpp11< T, AligmentBytes >::allocate(), and mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::realloc().
Definition at line 39 of file aligned_malloc.cpp.
Referenced by mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::realloc().
|
inline |
Degrees to radians.
Definition at line 42 of file core/include/mrpt/core/bits_math.h.
References M_PI.
Referenced by addBar_A(), ICPTests::align2scans(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::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(), SE_traits_tests< POSE_TYPE >::do_all_jacobs_test(), mrpt::obs::CObservation3DRangeScan::doDepthAndIntensityCamerasCoincide(), mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::poses::CPose2D::fromString(), mrpt::math::TPose2D::fromString(), mrpt::poses::CPose3D::fromString(), mrpt::math::TPose3D::fromString(), mrpt::math::TTwist2D::fromString(), mrpt::math::TTwist3D::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::vision::relocalizeMultiDesc(), 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::obs::CActionRobotMovement3D::TMotionModelOptions::TMotionModelOptions(), mrpt::obs::CActionRobotMovement2D::TMotionModelOptions::TMotionModelOptions(), 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().
|
inline |
Degrees to radians.
Definition at line 44 of file core/include/mrpt/core/bits_math.h.
References M_PI.
|
inline |
Degrees to radians.
Definition at line 46 of file core/include/mrpt/core/bits_math.h.
References M_PI.
|
inline |
Degrees to radians.
Definition at line 56 of file core/include/mrpt/core/bits_math.h.
References M_PIl.
|
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().
std::string mrpt::format | ( | const char * | fmt, |
... | |||
) |
A std::string version of C sprintf.
You can call this to obtain a std::string using printf-like syntax.
Definition at line 16 of file format.cpp.
References vsnprintf.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::_execGraphSlamStep(), mrpt::rtti::CClassRegistry::Add(), mrpt::graphslam::detail::CEdgeCounter::addEdge(), mrpt::graphslam::detail::CEdgeCounter::addEdgeType(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::graphslam::TUncertaintyPath< GRAPH_T >::assertIsBetweenNodeIDs(), mrpt::system::TCallStackBackTrace::asString(), mrpt::kinematics::CVehicleVelCmd::asString(), mrpt::poses::CPoint< CPoint3D >::asString(), mrpt::math::TPoint2D::asString(), mrpt::poses::CPose2D::asString(), mrpt::poses::CPose3DQuat::asString(), mrpt::math::TPose2D::asString(), mrpt::poses::CPose3DRotVec::asString(), mrpt::math::TPoint3D::asString(), mrpt::poses::CPose3D::asString(), mrpt::math::TPose3D::asString(), mrpt::math::TPose3DQuat::asString(), mrpt::math::TTwist2D::asString(), mrpt::math::TTwist3D::asString(), mrpt::maps::CGasConcentrationGridMap2D::build_Gaussian_Wind_Grid(), mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::hwdrivers::CRovio::captureImageAsync(), mrpt::graphs::CDijkstra< TYPE_GRAPH, MAPS_IMPLEMENTATION >::CDijkstra(), mrpt::img::CImage::changeSize(), mrpt::vision::checkerBoardCameraCalibration(), mrpt::vision::checkerBoardStereoCalibration(), mrpt::graphslam::apps::TUserOptionsChecker< mrpt::graphs::CNetworkOfPoses2DInf >::checkRegistrationDeciderExists(), mrpt::hwdrivers::CImageGrabber_dc1394::CImageGrabber_dc1394(), mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::CMatrixTemplate(), mrpt::io::zip::compress_gz_data_block(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::computeDominantEigenVector(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::computeMap(), mrpt::bayes::CParticleFilterCapable::computeResampling(), mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::comms::CClientTCPSocket::connect(), mrpt::hwdrivers::COpenNI2Generic::COpenNI2Generic(), mrpt::math::CQuaternion< T >::CQuaternion(), mrpt::system::createDirectory(), cvFindChessboardCorners3(), mrpt::system::dateTimeLocalToString(), mrpt::system::dateTimeToString(), mrpt::system::dateToString(), mrpt::nav::CParameterizedTrajectoryGenerator::debugDumpInFiles(), mrpt::nav::CMultiObjectiveMotionOptimizerBase::decide(), mrpt::rtti::TRuntimeClassId::derivedFrom(), mrpt::config::simpleini::MRPT_IniFileParser::do_parse(), mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::img::CImage::drawChessboardCorners(), mrpt::img::CCanvas::drawFeatures(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, mrpt::graphs::detail::TMRSlamNodeAnnotations, mrpt::graphs::detail::edge_annotations_empty >::drawNodeCorners(), mrpt::hmtslam::CLocalMetricHypothesis::dumpAsText(), mrpt::hmtslam::CHierarchicalMHMap::dumpAsXMLfile(), mrpt::graphslam::apps::TUserOptionsChecker< mrpt::graphs::CNetworkOfPoses2DInf >::dumpRegistrarsToConsole(), mrpt::hmtslam::CHMTSLAM::TMessageLSLAMfromAA::dumpToConsole(), mrpt::tfest::TMatchingPairList::dumpToFile(), mrpt::obs::gnss::Message_NMEA_GGA::dumpToStream(), mrpt::obs::gnss::Message_TOPCON_PZS::dumpToStream(), mrpt::obs::gnss::Message_TOPCON_SATS::dumpToStream(), mrpt::obs::gnss::Message_NMEA_GLL::dumpToStream(), mrpt::obs::gnss::Message_NMEA_RMC::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::dumpToStream(), mrpt::obs::gnss::Message_NMEA_VTG::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::dumpToStream(), mrpt::obs::gnss::Message_NMEA_ZDA::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_VERSION::dumpToStream(), mrpt::slam::TKLDParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderICP::TConfigParams::dumpToTextStream(), mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CGasConcentrationGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions::dumpToTextStream(), mrpt::hmtslam::CTopLCDetector_FabMap::TOptions::dumpToTextStream(), mrpt::hmtslam::CTopLCDetector_GridMatching::TOptions::dumpToTextStream(), mrpt::graphslam::TUncertaintyPath< GRAPH_T >::dumpToTextStream(), mrpt::maps::CReflectivityGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::graphslam::TSlidingWindow::dumpToTextStream(), mrpt::bayes::TKF_options::dumpToTextStream(), mrpt::slam::CGridMapAligner::TConfigParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions::dumpToTextStream(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams::dumpToTextStream(), mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TInsertionOptions::dumpToTextStream(), mrpt::vision::CFeatureExtraction::TOptions::dumpToTextStream(), mrpt::maps::CHeightGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CBeaconMap::TLikelihoodOptions::dumpToTextStream(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::dumpToTextStream(), mrpt::maps::CMultiMetricMapPDF::TPredictionParams::dumpToTextStream(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::maps::CBeaconMap::TInsertionOptions::dumpToTextStream(), mrpt::maps::CRandomFieldGridMap3D::TInsertionOptions::dumpToTextStream(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::slam::CRangeBearingKFSLAM::TOptions::dumpToTextStream(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::dumpToTextStream(), mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TLikelihoodOptions::dumpToTextStream(), mrpt::maps::CLandmarksMap::TInsertionOptions::dumpToTextStream(), mrpt::vision::TStereoSystemParams::dumpToTextStream(), mrpt::vision::CFeature::dumpToTextStream(), mrpt::maps::TSetOfMetricMapInitializers::dumpToTextStream(), mrpt::maps::CLandmarksMap::TLikelihoodOptions::dumpToTextStream(), mrpt::hmtslam::CHMTSLAM::TOptions::dumpToTextStream(), mrpt::vision::TMatchingOptions::dumpToTextStream(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams::dumpToTextStream(), mrpt::maps::COccupancyGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions::dumpToTextStream(), mrpt::vision::TMultiResDescMatchOptions::dumpToTextStream(), mrpt::vision::TMultiResDescOptions::dumpToTextStream(), mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CHeightGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CLandmarksMap::TMapDefinition::dumpToTextStream_map_specific(), mrpt::config::CLoadableOptions::dumpVar_bool(), mrpt::config::CLoadableOptions::dumpVar_double(), mrpt::config::CLoadableOptions::dumpVar_float(), mrpt::config::CLoadableOptions::dumpVar_int(), mrpt::config::CLoadableOptions::dumpVar_string(), mrpt::nav::CAbstractPTGBasedReactive::enableLogFile(), mrpt::hwdrivers::CImageGrabber_dc1394::enumerateCameras(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::evalPWConsistenciesMatrix(), mrpt::math::RANSAC_Template< NUMTYPE >::execute(), mrpt::bayes::CParticleFilter::executeOn(), mrpt::img::CImage::extract_patch(), mrpt::vision::CFeatureExtraction::extractFeaturesSIFT(), find_chessboard_corners_multiple(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::findPathByEnds(), mrpt::system::formatTimeInterval(), mrpt::rtti::CListOfClasses::fromString(), mrpt::hwdrivers::CRovio::general_command(), mrpt::hwdrivers::CSICKTim561Eth::generateCmd(), mrpt::hwdrivers::CLMS100Eth::generateCmd(), mrpt::hmtslam::CHMTSLAM::generateLogFiles(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::generateReportFiles(), mrpt::hmtslam::CHMTSLAM::generateUniqueAreaLabel(), generic_dump_BESTPOS(), generic_dump_MARKTIME(), generic_getFieldValues_MARKTIME(), mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::get_unsafe(), mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::get_unsafe_row(), mrpt::obs::gnss::Message_NMEA_GGA::getAllFieldValues(), mrpt::obs::gnss::Message_NMEA_GLL::getAllFieldValues(), mrpt::obs::gnss::Message_NMEA_RMC::getAllFieldValues(), mrpt::obs::gnss::Message_NMEA_VTG::getAllFieldValues(), mrpt::obs::gnss::Message_NMEA_ZDA::getAllFieldValues(), mrpt::slam::CRangeBearingKFSLAM2D::getAs3DObject(), mrpt::maps::CBeacon::getAs3DObject(), mrpt::slam::CRangeBearingKFSLAM::getAs3DObject(), mrpt::kinematics::CKinematicChain::getAs3DObject(), mrpt::maps::CLandmarksMap::getAs3DObject(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::slam::CIncrementalMapPartitioner::getAs3DScene(), mrpt::nav::TWaypointSequence::getAsOpenglVisualization(), mrpt::nav::TWaypointStatusSequence::getAsOpenglVisualization(), mrpt::graphslam::detail::TNodeProps< GRAPH_T >::getAsString(), mrpt::topography::TCoords::getAsString(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams::getAsString(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::getAsString(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TGetICPEdgeAdParams::getAsString(), mrpt::nav::CWaypointsNavigator::TNavigationParamsWaypoints::getAsText(), mrpt::nav::TWaypoint::getAsText(), mrpt::nav::TWaypointSequence::getAsText(), mrpt::nav::CAbstractNavigator::TargetInfo::getAsText(), mrpt::nav::TWaypointStatus::getAsText(), mrpt::nav::TWaypointStatusSequence::getAsText(), mrpt::hwdrivers::COpenNI2Generic::getConnectedDevices(), mrpt::nav::CPTG_Holo_Blend::getDescription(), mrpt::nav::CPTG_DiffDrive_C::getDescription(), mrpt::obs::CObservationWirelessPower::getDescriptionAsText(), mrpt::obs::CObservationOdometry::getDescriptionAsText(), mrpt::obs::CObservationBatteryState::getDescriptionAsText(), mrpt::obs::CObservationBeaconRanges::getDescriptionAsText(), mrpt::obs::CObservationCANBusJ1939::getDescriptionAsText(), mrpt::obs::CObservationImage::getDescriptionAsText(), mrpt::obs::CObservationRange::getDescriptionAsText(), mrpt::obs::CObservationGasSensors::getDescriptionAsText(), mrpt::obs::CObservationStereoImagesFeatures::getDescriptionAsText(), mrpt::obs::CObservationBearingRange::getDescriptionAsText(), mrpt::obs::CObservationStereoImages::getDescriptionAsText(), mrpt::obs::CObservationIMU::getDescriptionAsText(), mrpt::graphs::CNetworkOfPoses< CPOSE, MAPS_IMPLEMENTATION, NODE_ANNOTATIONS, EDGE_ANNOTATIONS >::getEdgeSquareError(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getFC2version(), mrpt::graphslam::deciders::CRangeScanOps< typename mrpt::graphs::CNetworkOfPoses2DInf >::getICPEdge(), mrpt::hwdrivers::CJoystick::getJoystickPosition(), mrpt::hwdrivers::CJoystick::getJoysticksCount(), mrpt::comms::net::getLastSocketErrorStr(), mrpt::hwdrivers::CVelodyneScanner::TModelPropertiesFactory::getListKnownModels(), mrpt::hwdrivers::CSwissRanger3DCamera::getMesaLibVersion(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::getMinUncertaintyPath(), mrpt::obs::CObservationGPS::getMsgByClass(), mrpt::obs::CObservationGPS::getMsgByType(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::hwdrivers::COpenNI2Generic::getNextFrameD(), mrpt::hwdrivers::COpenNI2Generic::getNextFrameRGB(), mrpt::hwdrivers::COpenNI2Generic::getNextFrameRGBD(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CImpinjRFID::getObservation(), mrpt::poses::internal::getPoseFromString(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::getPropsOfNodeID(), mrpt::system::CTimeLogger::getStatsAsText(), mrpt::gui::CDisplayWindow3D::grabImageGetNextFile(), mrpt::graphs::detail::graph_ops< graph_t >::graph_of_poses_dijkstra_init(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::graphslam::TUncertaintyPath< GRAPH_T >::hasLowerUncertaintyThan(), mrpt::comms::net::http_request(), mrpt::graphs::HypothesisNotFoundException::HypothesisNotFoundException(), mrpt::gui::CDisplayWindowPlots::image(), CAboutBoxBase::information(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::initEstimatedTrajectoryVisualization(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::initGTVisualization(), mrpt::hwdrivers::CRovio::initialize(), mrpt::hwdrivers::CNTRIPEmitter::initialize(), mrpt::hwdrivers::COpenNI2Sensor::initialize(), mrpt::hwdrivers::CCameraSensor::initialize(), mrpt::hwdrivers::CVelodyneScanner::initialize(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::initializeVisuals(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::initOdometryVisualization(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::initResultsFile(), mrpt::vision::CFeatureExtraction::internal_computeSpinImageDescriptors(), mrpt::maps::CRandomFieldGridMap2D::TInsertionOptionsCommon::internal_dumpToTextStream_common(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), mrpt::nav::PlannerTPS_VirtualBase::internal_initialize_PTG(), mrpt::nav::PlannerTPS_VirtualBase::internal_loadConfig_PTG(), mrpt::gui::CDisplayWindowPlots::internal_plot(), mrpt::hwdrivers::CVelodyneScanner::internal_receive_UDP_packet(), mrpt::hwdrivers::CVelodyneScanner::internal_send_http_post(), mrpt::system::intervalFormat(), mrpt::hwdrivers::CGPSInterface::JAVAD_sendMessage(), mrpt::hwdrivers::CGPSInterface::legacy_topcon_setup_commands(), mrpt::hwdrivers::CSickLaserSerial::LMS_waitACK(), mrpt::nav::TWaypointSequence::load(), mrpt::maps::CGasConcentrationGridMap2D::load_Gaussian_Wind_Grid_From_File(), mrpt::graphs::detail::graph_ops< graph_t >::load_graph_of_poses_from_text_file(), mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::hwdrivers::CBoardSonars::loadConfig_sensorSpecific(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::loadConfig_sensorSpecific(), mrpt::hwdrivers::CVelodyneScanner::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::CNationalInstrumentsDAQ::loadConfig_sensorSpecific(), mrpt::nav::CReactiveNavigationSystem::loadConfigFile(), mrpt::nav::CReactiveNavigationSystem3D::loadConfigFile(), mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase::loadFromConfigFile(), mrpt::nav::CHolonomicFullEval::TOptions::loadFromConfigFile(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::loadFromConfigFile(), mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile(), mrpt::maps::CLandmarksMap::TMapDefinition::loadFromConfigFile_map_specific(), mrpt::vision::CFeatureList::loadFromTextFile(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::loadParams(), mrpt::nav::CPTG_RobotShape_Polygonal::loadShapeFromConfigFile(), mrpt::opengl::CTexturedObject::loadTextureInOpenGL(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hwdrivers::TCaptureOptions_DUO3D::m_camera_ext_params_from_yml(), mrpt::hwdrivers::TCaptureOptions_DUO3D::m_camera_int_params_from_yml(), mrpt::hwdrivers::TCaptureOptions_DUO3D::m_rectify_map_from_yml(), mrpt::math::MATLAB_plotCovariance2D(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::monitorNodeRegistration(), mrpt::system::MRPT_getCompilationDate(), mrpt::hwdrivers::COpenNI2Generic::open(), mrpt::hwdrivers::CNTRIPClient::open(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::open(), mrpt::hwdrivers::COpenNI2Generic::openDevicesBySerialNum(), mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::operator()(), mrpt::img::CImage::operator()(), mrpt::comms::operator<<(), mrpt::vision::CVideoFileWriter::operator<<(), mrpt::poses::operator<<(), mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::operator=(), mrpt::math::operator>>(), mrpt::serialization::operator>>(), mrpt::graphslam::optimize_graph_spa_levmarq(), mrpt::config::simpleini::MRPT_IniFileParser::parse_process_var_eval(), mrpt::hwdrivers::CRovio::path_management(), mrpt::hwdrivers::CRovio::pathRename(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::nav::CAbstractNavigator::performNavigationStepNavigating(), mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal(), mrpt::gui::CDisplayWindowPlots::plotEllipse(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::hwdrivers::CNTRIPClient::private_ntrip_thread(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), mrpt::slam::CMetricMapBuilderICP::processObservation(), CGraphSlamHandler< GRAPH_T >::readConfigFname(), mrpt::poses::readFileWithPoses(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::readGTFile(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::readGTFileRGBD_TUM(), mrpt::serialization::CArchive::ReadObject(), mrpt::config::CConfigFile::readString(), mrpt::config::CConfigFileMemory::readString(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), mrpt::graphs::CGraphPartitioner< GRAPH_MATRIX, num_t >::RecursiveSpectralPartition(), mrpt::graphslam::deciders::CNodeRegistrationDecider< typename mrpt::graphs::CNetworkOfPoses2DInf >::registerNewNodeAtEnd(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CColorBar::render_dl(), mrpt::poses::CPoint2D::resize(), mrpt::poses::CPoint3D::resize(), mrpt::poses::CPose2D::resize(), mrpt::poses::CPose3DQuat::resize(), mrpt::poses::CPose3DRotVec::resize(), mrpt::poses::CPose3D::resize(), mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >::runOneKalmanIteration(), mrpt::nav::TWaypointSequence::save(), mrpt::maps::CGasConcentrationGridMap2D::save_Gaussian_Wind_Grid_To_File(), mrpt::obs::CObservationGasSensors::CMOSmodel::save_log_map(), mrpt::maps::COccupancyGridMap2D::saveAsBitmapFileWithLandmarks(), mrpt::maps::CRandomFieldGridMap3D::saveAsCSV(), mrpt::obs::CObservationStereoImagesFeatures::saveFeaturesToTextFile(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveInterpolatedToTextFile(), mrpt::maps::CMultiMetricMap::saveMetricMapRepresentationToFile(), mrpt::poses::CPosePDFParticles::saveParzenPDFToTextFile(), mrpt::img::TCamera::saveToConfigFile(), mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase::saveToConfigFile(), mrpt::nav::CHolonomicND::TOptions::saveToConfigFile(), mrpt::nav::CHolonomicFullEval::TOptions::saveToConfigFile(), mrpt::nav::CPTG_RobotShape_Polygonal::saveToConfigFile(), mrpt::system::CTimeLogger::saveToCSVFile(), mrpt::containers::internal::dynamic_grid_txt_saver::saveToTextFile(), mrpt::poses::CPosePDFGrid::saveToTextFile(), mrpt::poses::CPosePDFParticles::saveToTextFile(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveToTextFile(), mrpt::pbmap::PlaneInferredInfo::searchTheFloor(), mrpt::hwdrivers::CRovio::send_cmd_action(), mrpt::nav::CLogFileRecord::serializeFrom(), mrpt::math::CMatrixTemplate< mrpt::math::TPoint3D >::set_unsafe(), mrpt::hwdrivers::CGPSInterface::setJAVAD_AIM_mode(), mrpt::hwdrivers::CVelodyneScanner::setLidarOnOff(), mrpt::hwdrivers::CVelodyneScanner::setLidarReturnType(), mrpt::hwdrivers::CVelodyneScanner::setLidarRPM(), mrpt::comms::CServerTCPSocket::setupSocket(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), mrpt::nav::PlannerTPS_VirtualBase::spaceTransformer(), mrpt::nav::PlannerTPS_VirtualBase::spaceTransformerOneDirectionOnly(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::splitPartitionToGroups(), mrpt::system::sprintf_container(), mrpt::containers::sprintf_vector(), mrpt::nav::CReactiveNavigationSystem::STEP1_InitPTGs(), mrpt::nav::CReactiveNavigationSystem3D::STEP1_InitPTGs(), TEST(), mrpt::hwdrivers::CCameraSensor::thread_save_images(), mrpt::hwdrivers::CRovio::thread_video(), throw_stacked_exception_custom_msg2(), mrpt::system::timeLocalToString(), mrpt::system::timeToString(), mrpt::system::unitsFormat(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::updateMapPartitionsVisualization(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateState(), mrpt::hwdrivers::CCANBusReader::waitACK(), mrpt::hwdrivers::CCANBusReader::waitContinuousSampleFrame(), mrpt::hwdrivers::CSickLaserUSB::waitContinuousSampleFrame(), mrpt::hwdrivers::CSickLaserSerial::waitContinuousSampleFrame(), mrpt::gui::CPanelCameraSelection::writeConfigFromVideoSourcePanel(), mrpt::vision::CVideoFileWriter::writeImage(), mrpt::system::COutputLogger::writeLogToFile(), mrpt::config::CConfigFileBase::writeString(), and mrpt::hmtslam::CHMTSLAM::~CHMTSLAM().
|
inline |
Faster version of std::hypot(), to use when overflow is not an issue and we prefer fast code.
Definition at line 26 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().
|
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::vision::ba_initial_estimate(), mrpt::vision::bundle_adj_full(), mrpt::nav::CHolonomicND::calcRepresentativeSectorForGap(), mrpt::opengl::CFrustum::CFrustum(), mrpt::nav::CMultiObjectiveMotionOptimizerBase::decide(), mrpt::system::CTimeLogger::do_leave(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, mrpt::graphs::detail::TMRSlamNodeAnnotations, mrpt::graphs::detail::edge_annotations_empty >::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::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::math::TPolygon2D::getBoundingBox(), mrpt::vision::TSimpleFeatureList_templ< TSimpleFeature >::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().
|
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, mrpt::graphs::detail::TMRSlamNodeAnnotations, mrpt::graphs::detail::edge_annotations_empty >::drawGroundGrid(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), find_chessboard_corners_multiple(), mrpt::nav::CHolonomicND::gapsEstimator(), mrpt::slam::CIncrementalMapPartitioner::getAs3DScene(), 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::math::TPolygon2D::getBoundingBox(), mrpt::maps::CHeightGridMap2D_Base::getMinMaxHeight(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), 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::vision::detail::trackFeatures_addNewFeats_simple_list(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), mrpt::opengl::CMesh::updateColorsMatrix(), and mrpt::nav::CPTG_Holo_Blend::updateTPObstacleSingle().
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.
|
inline |
|
inline |
Definition at line 108 of file core/include/mrpt/core/bits_math.h.
Referenced by mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), and mrpt::img::rgb2hsv().
|
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().
|
inline |
Radians to degrees.
Definition at line 48 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::poses::CPose2D::asString(), mrpt::math::TPose2D::asString(), mrpt::poses::CPose3D::asString(), mrpt::math::TPose3D::asString(), mrpt::math::TTwist2D::asString(), mrpt::math::TTwist3D::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(), mrpt::obs::CActionRobotMovement2D::TMotionModelOptions::TMotionModelOptions(), mrpt::hwdrivers::CHokuyoURG::turnOn(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().
|
inline |
Radians to degrees.
Definition at line 50 of file core/include/mrpt/core/bits_math.h.
References M_PI.
|
inline |
Radians to degrees.
Definition at line 58 of file core/include/mrpt/core/bits_math.h.
References M_PIl.
|
inline |
Reverse the order of the bytes of a given type (useful for transforming btw little/big endian)
Definition at line 33 of file reverse_bytes.h.
References reverseBytesInPlace().
Referenced by get_binary_item(), and TEST().
void mrpt::reverseBytesInPlace | ( | bool & | v_in_out | ) |
Reverse the order of the bytes of a given type (useful for transforming btw little/big endian)
Definition at line 93 of file reverse_bytes.cpp.
Referenced by mrpt::serialization::CArchive::ReadBufferFixEndianness(), mrpt::hwdrivers::CVelodyneScanner::receivePackets(), reverseBytes(), and TEST().
void mrpt::reverseBytesInPlace | ( | double & | v_in_out | ) |
Definition at line 142 of file reverse_bytes.cpp.
References reverseBytesInPlace_8b().
void mrpt::reverseBytesInPlace | ( | float & | v_in_out | ) |
Definition at line 137 of file reverse_bytes.cpp.
References reverseBytesInPlace_4b().
Definition at line 112 of file reverse_bytes.cpp.
References reverseBytesInPlace_2b().
Definition at line 122 of file reverse_bytes.cpp.
References reverseBytesInPlace_4b().
Definition at line 132 of file reverse_bytes.cpp.
References reverseBytesInPlace_8b().
Definition at line 102 of file reverse_bytes.cpp.
void mrpt::reverseBytesInPlace | ( | long double & | v_in_out | ) |
Definition at line 107 of file reverse_bytes.cpp.
References reverseBytesInPlace_2b().
Definition at line 117 of file reverse_bytes.cpp.
References reverseBytesInPlace_4b().
Definition at line 127 of file reverse_bytes.cpp.
References reverseBytesInPlace_8b().
Definition at line 98 of file reverse_bytes.cpp.
T mrpt::round2up | ( | T | 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::img::CImage::cross_correlation_FFT(), mrpt::math::dft2_complex(), mrpt::math::idft2_complex(), mrpt::math::idft2_real(), and TEST().
|
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().
|
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().
|
inline |
Returns the sign of X as "1" or "-1".
Definition at line 68 of file core/include/mrpt/core/bits_math.h.
Referenced by mrpt::opengl::CAngularObservationMesh::TDoubleRange::amount(), mrpt::opengl::CAngularObservationMesh::TDoubleRange::aperture(), mrpt::opengl::CAngularObservationMesh::TDoubleRange::finalValue(), mrpt::math::getAngle(), mrpt::kinematics::CVehicleSimul_Holo::internal_simulControlStep(), mrpt::math::intersect(), mrpt::nav::CPTG_DiffDrive_C::inverseMap_WS2TP(), myGeneralDFT(), mrpt::opengl::CAngularObservationMesh::TDoubleRange::negToPos(), mrpt::math::pointIntoQuadrangle(), mrpt::nav::CPTG_DiffDrive_C::ptgDiffDriveSteeringFunction(), signWithZero(), mrpt::math::splitInConvexComponents(), and TEST().
|
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().
|
inline |
Inline function for the square of a number.
Definition at line 18 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::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< CPoint3D >::distance2DToSquare(), mrpt::poses::CPoseOrPoint< CPoint3D >::distance3DToSquare(), mrpt::math::distanceBetweenPoints(), mrpt::poses::CPose3D::distanceEuclidean6D(), mrpt::math::distanceSqrBetweenPoints(), mrpt::math::TPoint3D::distanceTo(), mrpt::vision::CCamModel::distort_a_point(), mrpt::poses::dVinvt_dR(), mrpt::bayes::CParticleFilterDataImpl< CMultiMetricMapPDF, mrpt::bayes::CParticleFilterData< CRBPFParticleData >::CParticleList >::ESS(), mrpt::poses::CPointPDFSOG::ESS(), 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::filterBadCorrsByDistance(), 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::vision::getDispersion(), mrpt::opengl::CPolyhedron::getDual(), mrpt::vision::CCamModel::getFullInverseModelWithJacobian(), mrpt::vision::CCamModel::getFullJacobianT(), getHeight(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::getLargestDistanceFromOrigin(), mrpt::maps::CPointsMap::getLargestDistanceFromOrigin(), mrpt::vision::CCamModel::getTemporaryVariablesForTransform(), 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::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::vision::CCamModel::jacob_undistor(), mrpt::vision::CCamModel::jacobian_project_with_distortion(), mrpt::vision::CCamModel::jacobian_unproject_with_distortion(), mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(), mrpt::img::CCanvas::line(), mrpt::poses::CPose3D::ln_jacob(), mrpt::math::CQuaternion< T >::ln_noresize(), mrpt::poses::CPose3D::ln_rot_jacob(), 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::vision::matchMultiResolutionFeatures(), mrpt::math::meanAndCovMat(), mrpt::math::meanAndCovVec(), mrpt::math::meanAndStd(), meanAndStd(), meanAndStdAll(), mrpt::math::minDistBetweenLines(), mrpt::nav::CHolonomicFullEval::navigate(), mrpt::math::ncc_vector(), mrpt::math::noncentralChi2CDF(), mrpt::math::TPoint2D::norm(), mrpt::poses::CPoseOrPoint< CPoint3D >::norm(), mrpt::math::TPoint3D::norm(), mrpt::math::TPose3D::norm(), mrpt::math::TPose3DQuat::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::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), mrpt::maps::CRandomFieldGridMap2D::predictMeasurement(), mrpt::poses::CPoint2DPDFGaussian::productIntegralNormalizedWith(), mrpt::poses::CPointPDFGaussian::productIntegralNormalizedWith(), mrpt::poses::CPointPDFGaussian::productIntegralNormalizedWith2D(), mrpt::vision::CCamModel::project_3D_point(), 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_CC::PTG_IsIntoDomain(), mrpt::nav::CPTG_DiffDrive_CS::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::poses::CPoseOrPoint< CPoint3D >::sqrDistanceTo(), mrpt::math::TPoint3D::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::vision::CCamModel::unproject_3D_point(), mrpt::topography::UTMToGeodetic(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().
|
inline |
|
inline |
Definition at line 42 of file format.h.
Referenced by to_string().
|
inline |
std::string std::string mrpt::to_string | ( | T | v | ) |
Just like std::to_string(), but with an overloaded version for std::string arguments.
Definition at line 27 of file format.h.
References to_string().
Referenced by asrt_fail(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::comms::net::Ping(), mrpt::graphs::CDirectedGraph< CPOSE, mrpt::graphs::detail::edge_annotations_empty >::saveAsDot(), mrpt::io::CPipeBaseEndPoint::serialize(), TEST(), throw_stacked_exception(), throw_typed_exception(), mrpt::typemeta::TEnumType< ENUMTYPE >::value2name(), and mrpt::config::CConfigFileBase::write().
|
inline |
Like calling a std::vector<>'s clear() method, but really forcing deallocating the memory.
Definition at line 16 of file bits_mem.h.
Referenced by mrpt::maps::CSimplePointsMap::internal_clear(), mrpt::maps::CWeightedPointsMap::internal_clear(), mrpt::maps::CColouredPointsMap::internal_clear(), mrpt::obs::CObservation3DRangeScan::points3D_convertToExternalStorage(), mrpt::obs::CObservation3DRangeScan::resizePoints3DVectors(), and mrpt::obs::CObservation3DRangeScan::unload().
std::string mrpt::MRPT_GLOBAL_UNITTEST_SRC_DIR |
Definition at line 25 of file CLogFileRecord_unittest.cpp.
Referenced by run_test_pf_localization(), and TEST().
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 |