MRPT  1.9.9
[mrpt-core]

Detailed Description

Core functions for MRPT.

Back to list of all libraries | See all modules

Library mrpt-core

[New in MRPT 2.0.0]

This library is part of MRPT and can be installed in Debian-based systems with:

    sudo apt install libmrpt-rtti-dev
Collaboration diagram for [mrpt-core]:

Classes

class  mrpt::Clock
 Clock that is compatible with MRPT TTimeStamp representation. More...
 
struct  mrpt::safe_ptr_basic< T >
 A wrapper class for pointers that can be safely copied with "=" operator without problems. More...
 
struct  mrpt::safe_ptr< T >
 A wrapper class for pointers that can be safely copied with "=" operator without problems. More...
 
struct  mrpt::non_copiable_ptr_basic< T >
 A wrapper class for pointers that can NOT be copied with "=" operator, raising an exception at runtime if a copy is attempted. More...
 
struct  mrpt::non_copiable_ptr< T >
 A wrapper class for pointers that can NOT be copied with "=" operator, raising an exception at runtime if a copy is attempted. More...
 
struct  mrpt::ignored_copy_ptr< T >
 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  mrpt::copiable_NULL_ptr_basic< T >
 A wrapper class for pointers that, if copied with the "=" operator, should be set to nullptr in the copy. More...
 
struct  mrpt::copiable_NULL_ptr< T >
 A wrapper class for pointers that, if copied with the "=" operator, should be set to nullptr in the new copy. More...
 

Modules

 Templates to declare integers by byte count (in
 #include <mrpt/core/integer_select.h>)
 
 Round functions (in #include <mrpt/core/round.h>)
 

Functions

std::string mrpt::format (const char *fmt,...) MRPT_printf_format_check(1
 A std::string version of C sprintf. More...
 
template<typename T >
std::string std::string mrpt::to_string (T v)
 Just like std::to_string(), but with an overloaded version for std::string arguments. More...
 
void mrpt::reverseBytesInPlace (bool &v_in_out)
 Reverse the order of the bytes of a given type (useful for transforming btw little/big endian) More...
 
void mrpt::reverseBytesInPlace (uint8_t &v_in_out)
 
void mrpt::reverseBytesInPlace (int8_t &v_in_out)
 
void mrpt::reverseBytesInPlace (uint16_t &v_in_out)
 
void mrpt::reverseBytesInPlace (int16_t &v_in_out)
 
void mrpt::reverseBytesInPlace (uint32_t &v_in_out)
 
void mrpt::reverseBytesInPlace (int32_t &v_in_out)
 
void mrpt::reverseBytesInPlace (uint64_t &v_in_out)
 
void mrpt::reverseBytesInPlace (int64_t &v_in_out)
 
void mrpt::reverseBytesInPlace (float &v_in_out)
 
void mrpt::reverseBytesInPlace (double &v_in_out)
 
void mrpt::reverseBytesInPlace (long double &v_in_out)
 
template<class T >
void mrpt::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...
 

Function Documentation

◆ format()

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< GRAPH_T >::_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< GRAPH_T >::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< GRAPH_T >::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, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawNodeCorners(), mrpt::hmtslam::CLocalMetricHypothesis::dumpAsText(), mrpt::hmtslam::CHierarchicalMHMap::dumpAsXMLfile(), mrpt::graphslam::apps::TUserOptionsChecker< GRAPH_T >::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_NMEA_VTG::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::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::slam::CGridMapAligner::TConfigParams::dumpToTextStream(), mrpt::bayes::TKF_options::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(), EXPLICIT_INST_ransac_detect_3D_planes(), mrpt::img::CImage::extract_patch(), mrpt::vision::CFeatureExtraction::extractFeaturesSIFT(), mrpt::graphs::CNetworkOfPoses< CPOSE, MAPS_IMPLEMENTATION, NODE_ANNOTATIONS, EDGE_ANNOTATIONS >::extractSubGraph(), 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::graphslam::deciders::CLoopCloserERD< GRAPH_T >::generateHypotsPool(), mrpt::hmtslam::CHMTSLAM::generateLogFiles(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::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< GRAPH_T >::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::graphs::CDijkstra< TYPE_GRAPH, MAPS_IMPLEMENTATION >::getTreeGraph(), mrpt::gui::CDisplayWindow3D::grabImageGetNextFile(), mrpt::graphs::detail::graph_ops< graph_t >::graph_edge_sqerror(), 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< GRAPH_T >::initEstimatedTrajectoryVisualization(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::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< GRAPH_T >::initOdometryVisualization(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::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_stream(), 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< GRAPH_T >::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::graphs::CNetworkOfPoses< CPOSE, MAPS_IMPLEMENTATION, NODE_ANNOTATIONS, EDGE_ANNOTATIONS >::mergeGraph(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::monitorNodeRegistration(), mrpt::system::MRPT_getCompilationDate(), mrpt::io::CFileGZOutputStream::open(), 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(), readFileWithPoses(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::readGTFile(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::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< GRAPH_t >::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().

◆ reverseBytes()

template<class T >
void mrpt::reverseBytes ( const T &  v_in,
T &  v_out 
)
inline

Reverse the order of the bytes of a given type (useful for transforming btw little/big endian)

Definition at line 36 of file reverse_bytes.h.

References mrpt::reverseBytesInPlace().

Referenced by get_binary_item(), and TEST().

◆ reverseBytesInPlace() [1/12]

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(), mrpt::reverseBytes(), and TEST().

◆ reverseBytesInPlace() [2/12]

void mrpt::reverseBytesInPlace ( uint8_t v_in_out)

Definition at line 98 of file reverse_bytes.cpp.

◆ reverseBytesInPlace() [3/12]

void mrpt::reverseBytesInPlace ( int8_t v_in_out)

Definition at line 102 of file reverse_bytes.cpp.

◆ reverseBytesInPlace() [4/12]

void mrpt::reverseBytesInPlace ( uint16_t v_in_out)

Definition at line 107 of file reverse_bytes.cpp.

References reverseBytesInPlace_2b().

◆ reverseBytesInPlace() [5/12]

void mrpt::reverseBytesInPlace ( int16_t v_in_out)

Definition at line 112 of file reverse_bytes.cpp.

References reverseBytesInPlace_2b().

◆ reverseBytesInPlace() [6/12]

void mrpt::reverseBytesInPlace ( uint32_t v_in_out)

Definition at line 117 of file reverse_bytes.cpp.

References reverseBytesInPlace_4b().

◆ reverseBytesInPlace() [7/12]

void mrpt::reverseBytesInPlace ( int32_t v_in_out)

Definition at line 122 of file reverse_bytes.cpp.

References reverseBytesInPlace_4b().

◆ reverseBytesInPlace() [8/12]

void mrpt::reverseBytesInPlace ( uint64_t v_in_out)

Definition at line 127 of file reverse_bytes.cpp.

References reverseBytesInPlace_8b().

◆ reverseBytesInPlace() [9/12]

void mrpt::reverseBytesInPlace ( int64_t v_in_out)

Definition at line 132 of file reverse_bytes.cpp.

References reverseBytesInPlace_8b().

◆ reverseBytesInPlace() [10/12]

void mrpt::reverseBytesInPlace ( float &  v_in_out)

Definition at line 137 of file reverse_bytes.cpp.

References reverseBytesInPlace_4b().

◆ reverseBytesInPlace() [11/12]

void mrpt::reverseBytesInPlace ( double &  v_in_out)

Definition at line 142 of file reverse_bytes.cpp.

References reverseBytesInPlace_8b().

◆ reverseBytesInPlace() [12/12]

void mrpt::reverseBytesInPlace ( long double &  v_in_out)

◆ to_string()




Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020