MRPT
1.9.9
|
#include <mrpt/core/aligned_allocator.h>
#include <mrpt/core/safe_pointers.h>
#include <mrpt/typemeta/static_string.h>
#include <functional>
#include <memory>
#include <vector>
Go to the source code of this file.
Classes | |
struct | mrpt::rtti::TRuntimeClassId |
A structure that holds runtime class type information. More... | |
struct | mrpt::rtti::CLASS_ID_impl< T > |
struct | mrpt::rtti::IS_CLASS_impl< T > |
struct | mrpt::rtti::internal::CopyCtor< is_copy_ctrtible > |
struct | mrpt::rtti::internal::CopyCtor< true > |
struct | mrpt::rtti::internal::CopyCtor< false > |
class | mrpt::rtti::CObject |
Virtual base to provide a compiler-independent RTTI system. More... | |
struct | mrpt::ptr_cast< CAST_TO > |
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... | |
Namespaces | |
mrpt | |
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries. | |
mrpt::rtti | |
mrpt::rtti::internal | |
RTTI classes and functions for polymorphic hierarchies | |
#define | CLASS_ID(T) mrpt::rtti::CLASS_ID_impl<T>::get() |
Access to runtime class ID for a defined class name. More... | |
#define | CLASS_ID_TEMPLATE(class_name, T) mrpt::rtti::CLASS_ID_impl<T>::get() |
#define | CLASS_ID_NAMESPACE(class_name, namespaceName) mrpt::rtti::CLASS_ID_impl<namespaceName::class_name>::get() |
#define | IS_CLASS(obj, class_name) mrpt::rtti::IS_CLASS_impl<class_name>::check(obj) |
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class. More... | |
#define | IS_DERIVED(obj, class_name) ((obj).GetRuntimeClass()->derivedFrom(CLASS_ID(class_name))) |
True if the given reference to object (derived from mrpt::rtti::CObject) is an instance of the given class OR any of its derived classes. More... | |
#define | DEFINE_MRPT_OBJECT(class_name, NameSpace) |
This declaration must be inserted in all CObject classes definition, within the class declaration. More... | |
#define | INTERNAL_IMPLEMENTS_MRPT_OBJECT( class_name, base, NameSpace, class_registry_name) |
#define | IMPLEMENTS_MRPT_OBJECT(class_name, base, NameSpace) |
Must be added to all CObject-derived classes implementation file. More... | |
#define | DEFINE_VIRTUAL_MRPT_OBJECT(class_name) |
This declaration must be inserted in virtual CObject classes definition: More... | |
#define | INTERNAL_IMPLEMENTS_VIRTUAL_MRPT_OBJECT( class_name, base_name, NS, registered_name) |
This must be inserted as implementation of some required members for virtual CObject classes: More... | |
#define | IMPLEMENTS_VIRTUAL_MRPT_OBJECT(class_name, base, NS) |
void | mrpt::rtti::registerClass (const mrpt::rtti::TRuntimeClassId *pNewClass) |
Register a class into the MRPT internal list of "CObject" descendents. More... | |
void | mrpt::rtti::registerClassCustomName (const char *customName, const TRuntimeClassId *pNewClass) |
Mostly for internal use within mrpt sources, to handle exceptional cases with multiple serialization names for backward compatibility (CMultiMetricMaps, CImage,...) More... | |
std::vector< const mrpt::rtti::TRuntimeClassId * > | mrpt::rtti::getAllRegisteredClasses () |
Returns a list with all the classes registered in the system through mrpt::rtti::registerClass. More... | |
std::vector< const TRuntimeClassId * > | mrpt::rtti::getAllRegisteredClassesChildrenOf (const TRuntimeClassId *parent_id) |
Like getAllRegisteredClasses(), but filters the list to only include children clases of a given base one. More... | |
const TRuntimeClassId * | mrpt::rtti::findRegisteredClass (const std::string &className, const bool allow_ignore_namespace=true) |
Return info about a given class by its name, or nullptr if the class is not registered. More... | |
void | mrpt::rtti::registerAllPendingClasses () |
Register all pending classes - to be called just before de-serializing an object, for example. More... | |
mrpt::rtti::CObject::Ptr | mrpt::rtti::classFactory (const std::string &className) |
Creates an object given by its registered name. More... | |
#define CLASS_ID | ( | T | ) | mrpt::rtti::CLASS_ID_impl<T>::get() |
Access to runtime class ID for a defined class name.
Definition at line 102 of file CObject.h.
Referenced by mrpt::slam::CGridMapAligner::AlignPDF_correlation(), mrpt::hwdrivers::CGenericSensor::appendObservations(), mrpt::poses::CPose3DPDFSOG::bayesianFusion(), mrpt::poses::CPosePDFGaussian::bayesianFusion(), mrpt::poses::CPosePDFGaussianInf::bayesianFusion(), mrpt::poses::CPointPDFSOG::bayesianFusion(), mrpt::poses::CPosePDFSOG::bayesianFusion(), mrpt::hmtslam::CLocalMetricHypothesis::changeCoordinateOrigin(), mrpt::maps::CBeaconMap::compute3DMatchingRatio(), mrpt::maps::CLandmarksMap::compute3DMatchingRatio(), mrpt::maps::CLandmarksMap::computeMatchingWith2D(), mrpt::poses::CPose3DPDFParticles::copyFrom(), mrpt::poses::CPosePDFParticles::copyFrom(), mrpt::poses::CPose3DPDFSOG::copyFrom(), mrpt::poses::CPointPDFSOG::copyFrom(), mrpt::poses::CPosePDFSOG::copyFrom(), mrpt::poses::CPose3DPDF::createFrom2D(), mrpt::maps::CBeaconMap::determineMatching2D(), mrpt::maps::COccupancyGridMap2D::determineMatching2D(), mrpt::maps::CPointsMap::determineMatching3D(), mrpt::obs::CRawlog::findObservationsByClassInRange(), mrpt::obs::CRawlog::getActionObservationPairOrObservation(), mrpt::obs::CRawlog::getAsAction(), mrpt::obs::CRawlog::getAsObservation(), mrpt::obs::CRawlog::getAsObservations(), mrpt::obs::CActionCollection::getBestMovementEstimation(), mrpt::obs::CActionRobotMovement2D::getDescriptionAsText(), mrpt::obs::CActionCollection::getMovementEstimationByType(), mrpt::rtti::CObject::GetRuntimeClass(), mrpt::obs::CRawlog::getType(), mrpt::obs::CRawlog::iterator::getType(), mrpt::obs::CRawlog::const_iterator::getType(), mrpt::slam::CICP::ICP3D_Method_Classic(), mrpt::slam::CICP::ICP_Method_LM(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::CLandmarksMap::internal_insertObservation(), mrpt::poses::CPose3DPDFParticles::inverse(), mrpt::poses::CPose3DQuatPDFGaussianInf::inverse(), mrpt::poses::CPose3DQuatPDFGaussian::inverse(), mrpt::poses::CPose3DPDFSOG::inverse(), mrpt::poses::CPose3DPDFGaussianInf::inverse(), mrpt::poses::CPosePDFParticles::inverse(), mrpt::poses::CPosePDFGaussian::inverse(), mrpt::poses::CPose3DPDFGaussian::inverse(), mrpt::poses::CPosePDFGaussianInf::inverse(), mrpt::poses::CPosePDFSOG::inverse(), mrpt::obs::CRawlog::loadFromRawLogFile(), MRPT_INITIALIZER(), mrpt::topography::path_from_rtk_gps(), mrpt::detectors::CDetectorDoorCrossing::process(), mrpt::obs::CRawlog::readActionObservationPair(), mrpt::nav::CAbstractPTGBasedReactive::saveConfigFile(), mrpt::nav::CAbstractPTGBasedReactive::TAbstractPTGNavigatorParams::saveToConfigFile(), TEST(), and mrpt::hmtslam::CHMTSLAM::thread_LSLAM().
#define CLASS_ID_NAMESPACE | ( | class_name, | |
namespaceName | |||
) | mrpt::rtti::CLASS_ID_impl<namespaceName::class_name>::get() |
Definition at line 105 of file CObject.h.
Referenced by do_register(), mrpt::opengl::CSetOfObjects::dumpListOfObjects(), mrpt::opengl::COpenGLViewport::dumpListOfObjects(), mrpt::opengl::CSetOfObjects::getByClass(), mrpt::opengl::COpenGLViewport::getByClass(), mrpt::opengl::CSetOfObjects::getByName(), mrpt::opengl::COpenGLViewport::getByName(), mrpt::opengl::CSetOfObjects::removeObject(), and mrpt::opengl::COpenGLViewport::removeObject().
#define CLASS_ID_TEMPLATE | ( | class_name, | |
T | |||
) | mrpt::rtti::CLASS_ID_impl<T>::get() |
#define DEFINE_MRPT_OBJECT | ( | class_name, | |
NameSpace | |||
) |
This declaration must be inserted in all CObject classes definition, within the class declaration.
#define DEFINE_VIRTUAL_MRPT_OBJECT | ( | class_name | ) |
This declaration must be inserted in virtual CObject classes definition:
#define IMPLEMENTS_MRPT_OBJECT | ( | class_name, | |
base, | |||
NameSpace | |||
) |
Must be added to all CObject-derived classes implementation file.
This registers class ns1::Foo as "ns1::Foo".
#define IMPLEMENTS_VIRTUAL_MRPT_OBJECT | ( | class_name, | |
base, | |||
NS | |||
) |
#define INTERNAL_IMPLEMENTS_MRPT_OBJECT | ( | class_name, | |
base, | |||
NameSpace, | |||
class_registry_name | |||
) |
#define INTERNAL_IMPLEMENTS_VIRTUAL_MRPT_OBJECT | ( | class_name, | |
base_name, | |||
NS, | |||
registered_name | |||
) |
This must be inserted as implementation of some required members for virtual CObject classes:
#define IS_CLASS | ( | obj, | |
class_name | |||
) | mrpt::rtti::IS_CLASS_impl<class_name>::check(obj) |
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class.
Definition at line 146 of file CObject.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::_execGraphSlamStep(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::graphslam::apps::TUserOptionsChecker< GRAPH_T >::checkOptimizerExists(), mrpt::graphslam::apps::TUserOptionsChecker< GRAPH_T >::checkRegistrationDeciderExists(), mrpt::maps::CMultiMetricMapPDF::clear(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_Consensus(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_ConsensusOWA(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_likelihoodField_II(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_likelihoodField_Thrun(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::poses::CPosePDFGaussianInf::copyFrom(), mrpt::poses::CPose3DPDFGaussianInf::copyFrom(), mrpt::maps::CHeightGridMap2D_Base::dem_internal_insertObservation(), mrpt::detectors::CCascadeClassifierDetection::detectObjects_Impl(), mrpt::detectors::CFaceDetection::detectObjects_Impl(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::poses::CPoseRandomSampler::do_sample_2D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), mrpt::obs::CRawlog::getActionObservationPairOrObservation(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::apps::ICP_SLAM_App_Live::impl_get_next_observations(), mrpt::obs::CRawlog::insert(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::obs::CSensoryFrame::internal_buildAuxPointsMap(), mrpt::maps::COccupancyGridMap2D::internal_canComputeObservationLikelihood(), mrpt::maps::CReflectivityGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::maps::COccupancyGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CWirelessPowerGridMap2D::internal_insertObservation(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::opengl::COpenGLScene::internal_visitAllObjects(), mrpt::obs::CRawlog::loadFromRawLogFile(), main(), mrpt::slam::observationsOverlap(), mrpt::opengl::CSetOfObjects::posePDF2opengl(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::obs::CActionRobotMovement2D::prepareFastDrawSingleSample_modelGaussian(), mrpt::apps::RawlogGrabberApp::process_observations_for_sf(), mrpt::slam::CMetricMapBuilderICP::processObservation(), mrpt::serialization::CArchive::ReadVariant_helper(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::poses::CPoseRandomSampler::setPosePDF(), mrpt::hmtslam::CHMTSLAM::TBI_main_method(), mrpt::hwdrivers::CCameraSensor::thread_save_images(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::updateState(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateState(), and mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::updateState().
#define IS_DERIVED | ( | obj, | |
class_name | |||
) | ((obj).GetRuntimeClass()->derivedFrom(CLASS_ID(class_name))) |
True if the given reference to object (derived from mrpt::rtti::CObject) is an instance of the given class OR any of its derived classes.
Definition at line 151 of file CObject.h.
Referenced by mrpt::maps::CPointsMap::determineMatching2D(), mrpt::obs::CRawlog::getActionObservationPairOrObservation(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::apps::RawlogGrabberApp::process_observations_for_sf(), mrpt::slam::CMetricMapBuilderICP::processObservation(), TEST(), and mrpt::hwdrivers::CCameraSensor::thread_save_images().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020 |