Main MRPT website > C++ reference for MRPT 1.9.9
List of all members | Public Member Functions | Protected Member Functions
mrpt::obs::CObservation Class Referenceabstract

Detailed Description

Declares a class that represents any robot's observation.

This is a base class for many types of sensor observations. Users can add new observation types creating a new class deriving from this one.

IMPORTANT: Observations don't include any information about the robot pose, just raw sensory data and, where aplicable, information about the sensor position and orientation in the local frame of the robot.

See also
CSensoryFrame, CMetricMap

Definition at line 43 of file CObservation.h.

#include <mrpt/obs/CObservation.h>

Inheritance diagram for mrpt::obs::CObservation:
Inheritance graph

Public Member Functions

 CObservation ()=default
 Constructor: It sets the initial timestamp to current time. More...
 
template<class METRICMAP >
bool insertObservationInto (METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose=nullptr) const
 This method is equivalent to: More...
 
virtual void getSensorPose (mrpt::poses::CPose3D &out_sensorPose) const =0
 A general method to retrieve the sensor pose on the robot. More...
 
void getSensorPose (mrpt::math::TPose3D &out_sensorPose) const
 A general method to retrieve the sensor pose on the robot. More...
 
virtual void setSensorPose (const mrpt::poses::CPose3D &newSensorPose)=0
 A general method to change the sensor pose on the robot. More...
 
void setSensorPose (const mrpt::math::TPose3D &newSensorPose)
 A general method to change the sensor pose on the robot. More...
 
virtual void getDescriptionAsText (std::ostream &o) const
 Build a detailed, multi-line textual description of the observation contents and dump it to the output stream. More...
 
virtual mxArraywriteToMatlab () const
 Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More...
 
virtual CObjectclone () const =0
 Returns a deep copy (clone) of the object, indepently of its class. More...
 

Protected Member Functions

void swap (CObservation &o)
 Swap with another observation, ONLY the data defined here in the base class CObservation. More...
 

RTTI stuff


using Ptr = std::shared_ptr< CObservation >
 
using ConstPtr = std::shared_ptr< const CObservation >
 
static const mrpt::rtti::TRuntimeClassId runtimeClassId
 
static const mrpt::rtti::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::rtti::TRuntimeClassIdGetRuntimeClass () const override
 Returns information about the class of an object in runtime. More...
 
static const mrpt::rtti::TRuntimeClassIdGetRuntimeClassIdStatic ()
 

Data common to any observation

mrpt::system::TTimeStamp timestamp {mrpt::system::now()}
 The associated UTC time-stamp. More...
 
std::string sensorLabel
 An arbitrary label that can be used to identify the sensor. More...
 
mrpt::system::TTimeStamp getTimeStamp () const
 Returns CObservation::timestamp for all kind of observations. More...
 
virtual mrpt::system::TTimeStamp getOriginalReceivedTimeStamp () const
 By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accurate UTC timing of readings, this contains the computer-based timestamp of reception, which may be slightly different than timestamp. More...
 

Member Typedef Documentation

◆ ConstPtr

using mrpt::obs::CObservation::ConstPtr = std::shared_ptr<const CObservation >

Definition at line 45 of file CObservation.h.

◆ Ptr

using mrpt::obs::CObservation::Ptr = std::shared_ptr< CObservation >

Definition at line 45 of file CObservation.h.

Constructor & Destructor Documentation

◆ CObservation()

mrpt::obs::CObservation::CObservation ( )
default

Constructor: It sets the initial timestamp to current time.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::rtti::TRuntimeClassId* mrpt::obs::CObservation::_GetBaseClass ( )
staticprotected

◆ clone()

virtual CObject* mrpt::rtti::CObject::clone ( ) const
pure virtualinherited

Returns a deep copy (clone) of the object, indepently of its class.

Implemented in mrpt::obs::CObservation3DRangeScan, mrpt::nav::CLogFileRecord_FullEval, mrpt::nav::CLogFileRecord_ND, mrpt::maps::CMultiMetricMap, mrpt::img::CImage, mrpt::db::CSimpleDatabase, mrpt::obs::CObservationIMU, mrpt::maps::TMapGenericParams, mrpt::poses::CPose3D, mrpt::obs::CObservationRGBD360, mrpt::maps::CRandomFieldGridMap3D, mrpt::detectors::CDetectable3D, mrpt::hmtslam::THypothesisIDSet, mrpt::obs::CObservationVelodyneScan, mrpt::maps::CLandmarksMap, mrpt::hmtslam::CHMTSLAM, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::kinematics::CKinematicChain, mrpt::obs::CObservationGPS, mrpt::opengl::COctoMapVoxels, mrpt::maps::COccupancyGridMap2D, mrpt::obs::CRawlog, mrpt::maps::CMultiMetricMapPDF, mrpt::maps::CHeightGridMap2D, mrpt::slam::CIncrementalMapPartitioner, mrpt::opengl::COpenGLViewport, mrpt::opengl::COpenGLScene, mrpt::vision::CFeature, mrpt::opengl::CPlanarLaserScan, mrpt::nav::CHolonomicFullEval, mrpt::obs::CObservation2DRangeScan, mrpt::nav::CHolonomicND, mrpt::obs::CSensoryFrame, mrpt::opengl::CFrustum, mrpt::poses::CPose2DInterpolator, mrpt::nav::CHolonomicVFF, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::poses::CPose3DInterpolator, mrpt::poses::CPose3DQuat, mrpt::opengl::CPointCloud, mrpt::opengl::CEllipsoid, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::opengl::CPointCloudColoured, mrpt::pbmap::PbMap, mrpt::detectors::CDetectable2D, mrpt::maps::CBeaconMap, mrpt::pbmap::Plane, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CText3D, mrpt::poses::CPose3DRotVec, mrpt::opengl::CAngularObservationMesh, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CPolyhedron, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::hmtslam::CLSLAMParticleData, mrpt::maps::CReflectivityGridMap2D, mrpt::poses::CPose3DPDFGaussianInf, mrpt::nav::CPTG_DiffDrive_C, mrpt::opengl::CAssimpModel, mrpt::opengl::CBox, mrpt::obs::CObservationStereoImages, mrpt::opengl::CMeshFast, mrpt::opengl::CVectorField3D, mrpt::poses::CPose2D, mrpt::poses::CPosePDFParticles, mrpt::hmtslam::CHMHMapNode, mrpt::hmtslam::CRobotPosesGraph, mrpt::poses::CPose3DPDFGaussian, mrpt::obs::CObservationStereoImagesFeatures, mrpt::opengl::CMesh, mrpt::poses::CPose3DPDFParticles, mrpt::hmtslam::CMHPropertiesValuesList, mrpt::maps::CBeacon, mrpt::opengl::CMesh3D, mrpt::opengl::CText, MyNS::Bar, mrpt::maps::CHeightGridMap2D_MRF, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::maps::COctoMap, mrpt::opengl::CColorBar, mrpt::opengl::CVectorField2D, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::maps::CRBPFParticleData, mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CSimpleMap, mrpt::obs::CObservationImage, mrpt::maps::CLandmark, mrpt::poses::CPoint3D, mrpt::poses::CPose3DPDFSOG, mrpt::hmtslam::CHierarchicalMHMap, mrpt::maps::CColouredOctoMap, mrpt::obs::CObservationBatteryState, mrpt::opengl::CDisk, mrpt::opengl::CSetOfLines, mrpt::nav::CLogFileRecord, mrpt::obs::CActionRobotMovement2D, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::opengl::CCamera, mrpt::opengl::CCylinder, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::poses::CPointPDFParticles, mrpt::maps::CSimplePointsMap, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::opengl::CArrow, mrpt::opengl::CAxis, mrpt::opengl::CGeneralizedCylinder, mrpt::opengl::CSphere, mrpt::poses::CPosePDFGaussian, mrpt::maps::CWeightedPointsMap, mrpt::obs::CObservationRange, mrpt::img::TCamera, mrpt::maps::CColouredPointsMap, mrpt::obs::CActionRobotMovement3D, mrpt::obs::CObservationWirelessPower, mrpt::nav::CLogFileRecord_VFF, mrpt::nav::CMultiObjMotionOpt_Scalarization, mrpt::nav::CPTG_Holo_Blend, mrpt::obs::CActionCollection, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::opengl::CSetOfObjects, mrpt::obs::CObservationVisualLandmarks, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::poses::CPosePDFGrid, mrpt::math::CSplineInterpolator1D, mrpt::opengl::COpenGLStandardObject, mrpt::poses::CPoses2DSequence, mrpt::poses::CPoses3DSequence, mrpt::img::TStereoCamera, mrpt::math::CMatrixD, mrpt::opengl::CSetOfTriangles, mrpt::poses::CPointPDFGaussian, mrpt::hmtslam::CPropertiesValuesList, mrpt::math::CMatrix, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationRobotPose, mrpt::math::CMatrixB, mrpt::opengl::CSetOfTexturedTriangles, mrpt::poses::CPoint2DPDFGaussian, mrpt::math::CPolygon, mrpt::opengl::CSimpleLine, mrpt::opengl::CTexturedPlane, mrpt::db::CSimpleDatabaseTable, mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo, MyNS::Foo, MyNS::Foo, and MyNS::MyDerived1.

Referenced by mrpt::rtti::CObject::duplicateGetSmartPtr(), mrpt::maps::CSimpleMap::insert(), mrpt::obs::CActionCollection::insert(), and mrpt::poses::CPoseRandomSampler::setPosePDF().

◆ duplicateGetSmartPtr()

mrpt::rtti::CObject::Ptr CObject::duplicateGetSmartPtr ( ) const
inlineinherited

Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer).

Definition at line 169 of file CObject.h.

References mrpt::rtti::CObject::clone().

Referenced by mrpt::obs::CRawlog::addActions(), and mrpt::obs::CRawlog::addObservations().

◆ getDescriptionAsText()

void CObservation::getDescriptionAsText ( std::ostream &  o) const
virtual

Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.

Note
If overried by derived classes, call base CObservation::getDescriptionAsText() first to show common information.
This is the text that appears in RawLogViewer when selecting an object in the dataset

Reimplemented in mrpt::obs::CObservation3DRangeScan, mrpt::obs::CObservationVelodyneScan, mrpt::obs::CObservation2DRangeScan, mrpt::obs::CObservationGPS, mrpt::obs::CObservationIMU, mrpt::obs::CObservationRGBD360, mrpt::obs::CObservationStereoImages, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationRawDAQ, mrpt::obs::CObservationStereoImagesFeatures, mrpt::obs::CObservationSkeleton, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationRange, mrpt::obs::CObservationImage, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationVisualLandmarks, mrpt::obs::CObservationBatteryState, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationRFID, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationWindSensor, mrpt::obs::CObservationWirelessPower, mrpt::obs::CObservationComment, and mrpt::obs::CObservationRobotPose.

Definition at line 44 of file CObservation.cpp.

References mrpt::system::dateTimeToString(), and mrpt::system::timestampTotime_t().

Referenced by mrpt::obs::CObservationRobotPose::getDescriptionAsText(), mrpt::obs::CObservationComment::getDescriptionAsText(), mrpt::obs::CObservationWirelessPower::getDescriptionAsText(), mrpt::obs::CObservationWindSensor::getDescriptionAsText(), mrpt::obs::CObservationReflectivity::getDescriptionAsText(), mrpt::obs::CObservationOdometry::getDescriptionAsText(), mrpt::obs::CObservation6DFeatures::getDescriptionAsText(), mrpt::obs::CObservationRFID::getDescriptionAsText(), mrpt::obs::CObservationBatteryState::getDescriptionAsText(), mrpt::obs::CObservationVisualLandmarks::getDescriptionAsText(), mrpt::obs::CObservationBeaconRanges::getDescriptionAsText(), mrpt::obs::CObservationCANBusJ1939::getDescriptionAsText(), mrpt::obs::CObservationImage::getDescriptionAsText(), mrpt::obs::CObservationRange::getDescriptionAsText(), mrpt::obs::CObservationGasSensors::getDescriptionAsText(), mrpt::obs::CObservationSkeleton::getDescriptionAsText(), mrpt::obs::CObservationStereoImagesFeatures::getDescriptionAsText(), mrpt::obs::CObservationRawDAQ::getDescriptionAsText(), mrpt::obs::CObservationBearingRange::getDescriptionAsText(), mrpt::obs::CObservationStereoImages::getDescriptionAsText(), mrpt::obs::CObservationIMU::getDescriptionAsText(), and mrpt::obs::CObservation3DRangeScan::getDescriptionAsText().

◆ getOriginalReceivedTimeStamp()

virtual mrpt::system::TTimeStamp mrpt::obs::CObservation::getOriginalReceivedTimeStamp ( ) const
inlinevirtual

By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accurate UTC timing of readings, this contains the computer-based timestamp of reception, which may be slightly different than timestamp.

See also
getTimeStamp()

Reimplemented in mrpt::obs::CObservationGPS, and mrpt::obs::CObservationVelodyneScan.

Definition at line 71 of file CObservation.h.

References timestamp.

◆ GetRuntimeClass()

virtual const mrpt::rtti::TRuntimeClassId* mrpt::obs::CObservation::GetRuntimeClass ( ) const
overridevirtual

Returns information about the class of an object in runtime.

Reimplemented from mrpt::serialization::CSerializable.

Reimplemented in mrpt::obs::CObservation3DRangeScan, mrpt::obs::CObservationIMU, mrpt::obs::CObservationRGBD360, mrpt::obs::CObservationVelodyneScan, mrpt::obs::CObservationGPS, mrpt::obs::CObservation2DRangeScan, mrpt::obs::CObservationStereoImages, mrpt::obs::CObservationStereoImagesFeatures, mrpt::obs::CObservationImage, mrpt::obs::CObservationBatteryState, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::obs::CObservationRange, mrpt::obs::CObservationWirelessPower, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::obs::CObservationVisualLandmarks, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::obs::CObservationCANBusJ1939, and mrpt::obs::CObservationRobotPose.

Referenced by 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_rayTracing(), mrpt::maps::COccupancyGridMap2D::internal_canComputeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::maps::COccupancyGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::CLandmarksMap::internal_insertObservation(), and mrpt::maps::COccupancyGridMap2D::internal_insertObservation().

◆ GetRuntimeClassIdStatic()

static const mrpt::rtti::TRuntimeClassId& mrpt::obs::CObservation::GetRuntimeClassIdStatic ( )
static

◆ getSensorPose() [1/2]

void CObservation::getSensorPose ( mrpt::math::TPose3D out_sensorPose) const

A general method to retrieve the sensor pose on the robot.

Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.

See also
setSensorPose

Definition at line 26 of file CObservation.cpp.

◆ getSensorPose() [2/2]

virtual void mrpt::obs::CObservation::getSensorPose ( mrpt::poses::CPose3D out_sensorPose) const
pure virtual

◆ getTimeStamp()

mrpt::system::TTimeStamp mrpt::obs::CObservation::getTimeStamp ( ) const
inline

Returns CObservation::timestamp for all kind of observations.

See also
getOriginalReceivedTimeStamp()

Definition at line 66 of file CObservation.h.

References timestamp.

◆ insertObservationInto()

template<class METRICMAP >
bool mrpt::obs::CObservation::insertObservationInto ( METRICMAP *  theMap,
const mrpt::poses::CPose3D robotPose = nullptr 
) const
inline

This method is equivalent to:

map->insertObservation(this, robotPose)
Parameters
theMapThe map where this observation is to be inserted: the map will be updated.
robotPoseThe pose of the robot base for this observation, relative to the target metric map. Set to nullptr (default) to use (0,0,0deg)
Returns
Returns true if the map has been updated, or false if this observations has nothing to do with a metric map (for example, a sound observation).

See: Maps and observations compatibility matrix

See also
CMetricMap, CMetricMap::insertObservation

Definition at line 99 of file CObservation.h.

Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference().

◆ load()

virtual void mrpt::obs::CObservation::load ( ) const
inlinevirtual

Makes sure all images and other fields which may be externally stored are loaded in memory.

Note that for all CImages, calling load() is not required since the images will be automatically loaded upon first access, so load() shouldn't be needed to be called in normal cases by the user. If all the data were alredy loaded or this object has no externally stored data fields, calling this method has no effects.

See also
unload

Reimplemented in mrpt::obs::CObservation3DRangeScan.

Definition at line 154 of file CObservation.h.

◆ serializeFrom()

virtual void mrpt::serialization::CSerializable::serializeFrom ( CArchive in,
uint8_t  serial_version 
)
protectedpure virtualinherited

Pure virtual method for reading (deserializing) from an abstract archive.

Users don't call this method directly. Instead, use stream >> object;.

Parameters
inThe input binary stream where the object data must read from.
versionThe version of the object stored in the stream: use this version number in your code to know how to read the incoming data.
Exceptions
std::exceptionOn any I/O error

Implemented in mrpt::obs::CObservation3DRangeScan, mrpt::nav::CLogFileRecord_FullEval, mrpt::nav::CLogFileRecord_ND, mrpt::maps::CMultiMetricMap, mrpt::img::CImage, mrpt::db::CSimpleDatabase, mrpt::obs::CObservationIMU, mrpt::maps::TMapGenericParams, mrpt::poses::CPose3D, mrpt::obs::CObservationRGBD360, mrpt::maps::CRandomFieldGridMap3D, mrpt::detectors::CDetectable3D, mrpt::hmtslam::THypothesisIDSet, mrpt::obs::CObservationVelodyneScan, mrpt::maps::CLandmarksMap, mrpt::hmtslam::CHMTSLAM, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::kinematics::CKinematicChain, mrpt::obs::CObservationGPS, mrpt::opengl::COctoMapVoxels, mrpt::maps::COccupancyGridMap2D, mrpt::obs::CRawlog, mrpt::maps::CMultiMetricMapPDF, mrpt::maps::CHeightGridMap2D, mrpt::slam::CIncrementalMapPartitioner, mrpt::opengl::COpenGLViewport, mrpt::opengl::COpenGLScene, mrpt::vision::CFeature, mrpt::opengl::CPlanarLaserScan, mrpt::nav::CHolonomicFullEval, mrpt::obs::CObservation2DRangeScan, mrpt::nav::CHolonomicND, mrpt::obs::CSensoryFrame, mrpt::opengl::CFrustum, mrpt::poses::CPose2DInterpolator, mrpt::nav::CHolonomicVFF, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::poses::CPose3DInterpolator, mrpt::poses::CPose3DQuat, mrpt::opengl::CPointCloud, mrpt::opengl::CEllipsoid, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::opengl::CPointCloudColoured, mrpt::pbmap::PbMap, mrpt::detectors::CDetectable2D, mrpt::maps::CBeaconMap, mrpt::pbmap::Plane, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CText3D, mrpt::poses::CPose3DRotVec, mrpt::opengl::CAngularObservationMesh, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CPolyhedron, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::hmtslam::CLSLAMParticleData, mrpt::maps::CReflectivityGridMap2D, mrpt::poses::CPose3DPDFGaussianInf, mrpt::nav::CPTG_DiffDrive_C, mrpt::opengl::CAssimpModel, mrpt::opengl::CBox, mrpt::obs::CObservationStereoImages, mrpt::opengl::CMeshFast, mrpt::opengl::CVectorField3D, mrpt::poses::CPose2D, mrpt::poses::CPosePDFParticles, mrpt::hmtslam::CHMHMapNode, mrpt::hmtslam::CRobotPosesGraph, mrpt::poses::CPose3DPDFGaussian, mrpt::obs::CObservationStereoImagesFeatures, mrpt::opengl::CMesh, mrpt::poses::CPose3DPDFParticles, mrpt::hmtslam::CMHPropertiesValuesList, mrpt::maps::CBeacon, mrpt::opengl::CMesh3D, mrpt::opengl::CText, mrpt::maps::CHeightGridMap2D_MRF, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::maps::COctoMap, mrpt::opengl::CColorBar, mrpt::opengl::CVectorField2D, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::maps::CRBPFParticleData, mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CSimpleMap, mrpt::obs::CObservationImage, mrpt::maps::CLandmark, mrpt::poses::CPoint3D, mrpt::poses::CPose3DPDFSOG, mrpt::hmtslam::CHierarchicalMHMap, mrpt::maps::CColouredOctoMap, mrpt::obs::CObservationBatteryState, mrpt::opengl::CDisk, mrpt::opengl::CSetOfLines, mrpt::nav::CLogFileRecord, mrpt::obs::CActionRobotMovement2D, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::opengl::CCamera, mrpt::opengl::CCylinder, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::poses::CPointPDFParticles, mrpt::maps::CSimplePointsMap, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::opengl::CArrow, mrpt::opengl::CAxis, mrpt::opengl::CGeneralizedCylinder, mrpt::opengl::CSphere, mrpt::poses::CPosePDFGaussian, mrpt::maps::CWeightedPointsMap, mrpt::obs::CObservationRange, mrpt::img::TCamera, mrpt::maps::CColouredPointsMap, mrpt::obs::CActionRobotMovement3D, mrpt::obs::CObservationWirelessPower, mrpt::nav::CLogFileRecord_VFF, mrpt::nav::CPTG_Holo_Blend, mrpt::obs::CActionCollection, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::opengl::CSetOfObjects, mrpt::obs::CObservationVisualLandmarks, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::poses::CPosePDFGrid, mrpt::math::CSplineInterpolator1D, mrpt::opengl::COpenGLStandardObject, mrpt::poses::CPoses2DSequence, mrpt::poses::CPoses3DSequence, mrpt::img::TStereoCamera, mrpt::math::CMatrixD, mrpt::opengl::CSetOfTriangles, mrpt::poses::CPointPDFGaussian, mrpt::hmtslam::CPropertiesValuesList, mrpt::math::CMatrix, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationRobotPose, mrpt::math::CMatrixB, mrpt::opengl::CSetOfTexturedTriangles, mrpt::poses::CPoint2DPDFGaussian, mrpt::math::CPolygon, mrpt::opengl::CSimpleLine, mrpt::opengl::CTexturedPlane, mrpt::db::CSimpleDatabaseTable, mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo, and MyNS::Foo.

◆ serializeGetVersion()

virtual uint8_t mrpt::serialization::CSerializable::serializeGetVersion ( ) const
protectedpure virtualinherited

Must return the current versioning number of the object.

Start in zero for new classes, and increments each time there is a change in the stored format.

Implemented in mrpt::obs::CObservation3DRangeScan, mrpt::nav::CLogFileRecord_FullEval, mrpt::nav::CLogFileRecord_ND, mrpt::maps::CMultiMetricMap, mrpt::img::CImage, mrpt::db::CSimpleDatabase, mrpt::obs::CObservationIMU, mrpt::maps::TMapGenericParams, mrpt::poses::CPose3D, mrpt::obs::CObservationRGBD360, mrpt::maps::CRandomFieldGridMap3D, mrpt::detectors::CDetectable3D, mrpt::hmtslam::THypothesisIDSet, mrpt::obs::CObservationVelodyneScan, mrpt::maps::CLandmarksMap, mrpt::hmtslam::CHMTSLAM, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::kinematics::CKinematicChain, mrpt::obs::CObservationGPS, mrpt::opengl::COctoMapVoxels, mrpt::maps::COccupancyGridMap2D, mrpt::obs::CRawlog, mrpt::maps::CMultiMetricMapPDF, mrpt::maps::CHeightGridMap2D, mrpt::slam::CIncrementalMapPartitioner, mrpt::opengl::COpenGLViewport, mrpt::opengl::COpenGLScene, mrpt::vision::CFeature, mrpt::opengl::CPlanarLaserScan, mrpt::nav::CHolonomicFullEval, mrpt::obs::CObservation2DRangeScan, mrpt::nav::CHolonomicND, mrpt::obs::CSensoryFrame, mrpt::opengl::CFrustum, mrpt::poses::CPose2DInterpolator, mrpt::nav::CHolonomicVFF, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::poses::CPose3DInterpolator, mrpt::poses::CPose3DQuat, mrpt::opengl::CPointCloud, mrpt::opengl::CEllipsoid, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::opengl::CPointCloudColoured, mrpt::pbmap::PbMap, mrpt::detectors::CDetectable2D, mrpt::maps::CBeaconMap, mrpt::pbmap::Plane, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CText3D, mrpt::poses::CPose3DRotVec, mrpt::opengl::CAngularObservationMesh, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CPolyhedron, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::hmtslam::CLSLAMParticleData, mrpt::maps::CReflectivityGridMap2D, mrpt::poses::CPose3DPDFGaussianInf, mrpt::nav::CPTG_DiffDrive_C, mrpt::opengl::CAssimpModel, mrpt::opengl::CBox, mrpt::obs::CObservationStereoImages, mrpt::opengl::CMeshFast, mrpt::opengl::CVectorField3D, mrpt::poses::CPose2D, mrpt::poses::CPosePDFParticles, mrpt::hmtslam::CHMHMapNode, mrpt::hmtslam::CRobotPosesGraph, mrpt::poses::CPose3DPDFGaussian, mrpt::obs::CObservationStereoImagesFeatures, mrpt::opengl::CMesh, mrpt::poses::CPose3DPDFParticles, mrpt::hmtslam::CMHPropertiesValuesList, mrpt::maps::CBeacon, mrpt::opengl::CMesh3D, mrpt::opengl::CText, mrpt::maps::CHeightGridMap2D_MRF, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::maps::COctoMap, mrpt::opengl::CColorBar, mrpt::opengl::CVectorField2D, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::maps::CRBPFParticleData, mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CSimpleMap, mrpt::obs::CObservationImage, mrpt::maps::CLandmark, mrpt::poses::CPoint3D, mrpt::poses::CPose3DPDFSOG, mrpt::hmtslam::CHierarchicalMHMap, mrpt::maps::CColouredOctoMap, mrpt::obs::CObservationBatteryState, mrpt::opengl::CDisk, mrpt::opengl::CSetOfLines, mrpt::nav::CLogFileRecord, mrpt::obs::CActionRobotMovement2D, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::opengl::CCamera, mrpt::opengl::CCylinder, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::poses::CPointPDFParticles, mrpt::maps::CSimplePointsMap, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::opengl::CArrow, mrpt::opengl::CAxis, mrpt::opengl::CGeneralizedCylinder, mrpt::opengl::CSphere, mrpt::poses::CPosePDFGaussian, mrpt::maps::CWeightedPointsMap, mrpt::obs::CObservationRange, mrpt::img::TCamera, mrpt::maps::CColouredPointsMap, mrpt::obs::CActionRobotMovement3D, mrpt::obs::CObservationWirelessPower, mrpt::nav::CLogFileRecord_VFF, mrpt::nav::CPTG_Holo_Blend, mrpt::obs::CActionCollection, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::opengl::CSetOfObjects, mrpt::obs::CObservationVisualLandmarks, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::poses::CPosePDFGrid, mrpt::math::CSplineInterpolator1D, mrpt::opengl::COpenGLStandardObject, mrpt::poses::CPoses2DSequence, mrpt::poses::CPoses3DSequence, mrpt::img::TStereoCamera, mrpt::math::CMatrixD, mrpt::opengl::CSetOfTriangles, mrpt::poses::CPointPDFGaussian, mrpt::hmtslam::CPropertiesValuesList, mrpt::math::CMatrix, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationRobotPose, mrpt::math::CMatrixB, mrpt::opengl::CSetOfTexturedTriangles, mrpt::poses::CPoint2DPDFGaussian, mrpt::math::CPolygon, mrpt::opengl::CSimpleLine, mrpt::opengl::CTexturedPlane, mrpt::db::CSimpleDatabaseTable, mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo, and MyNS::Foo.

Referenced by mrpt::serialization::CArchive::WriteObject().

◆ serializeTo()

virtual void mrpt::serialization::CSerializable::serializeTo ( CArchive out) const
protectedpure virtualinherited

Pure virtual method for writing (serializing) to an abstract archive.

Users don't call this method directly. Instead, use stream << object;.

Exceptions
std::exceptionOn any I/O error

Implemented in mrpt::obs::CObservation3DRangeScan, mrpt::nav::CLogFileRecord_FullEval, mrpt::nav::CLogFileRecord_ND, mrpt::maps::CMultiMetricMap, mrpt::img::CImage, mrpt::db::CSimpleDatabase, mrpt::obs::CObservationIMU, mrpt::maps::TMapGenericParams, mrpt::poses::CPose3D, mrpt::obs::CObservationRGBD360, mrpt::maps::CRandomFieldGridMap3D, mrpt::detectors::CDetectable3D, mrpt::hmtslam::THypothesisIDSet, mrpt::obs::CObservationVelodyneScan, mrpt::maps::CLandmarksMap, mrpt::hmtslam::CHMTSLAM, mrpt::hmtslam::CLocalMetricHypothesis, mrpt::kinematics::CKinematicChain, mrpt::obs::CObservationGPS, mrpt::opengl::COctoMapVoxels, mrpt::maps::COccupancyGridMap2D, mrpt::obs::CRawlog, mrpt::maps::CMultiMetricMapPDF, mrpt::maps::CHeightGridMap2D, mrpt::slam::CIncrementalMapPartitioner, mrpt::opengl::COpenGLViewport, mrpt::opengl::COpenGLScene, mrpt::vision::CFeature, mrpt::opengl::CPlanarLaserScan, mrpt::nav::CHolonomicFullEval, mrpt::obs::CObservation2DRangeScan, mrpt::nav::CHolonomicND, mrpt::obs::CSensoryFrame, mrpt::opengl::CFrustum, mrpt::poses::CPose2DInterpolator, mrpt::nav::CHolonomicVFF, mrpt::opengl::CEllipsoidInverseDepth3D, mrpt::poses::CPose3DInterpolator, mrpt::poses::CPose3DQuat, mrpt::opengl::CPointCloud, mrpt::opengl::CEllipsoid, mrpt::opengl::CEllipsoidInverseDepth2D, mrpt::opengl::CPointCloudColoured, mrpt::pbmap::PbMap, mrpt::detectors::CDetectable2D, mrpt::maps::CBeaconMap, mrpt::pbmap::Plane, mrpt::poses::CPose3DQuatPDFGaussianInf, mrpt::opengl::CText3D, mrpt::poses::CPose3DRotVec, mrpt::opengl::CAngularObservationMesh, mrpt::opengl::CEllipsoidRangeBearing2D, mrpt::opengl::CPolyhedron, mrpt::poses::CPose3DQuatPDFGaussian, mrpt::hmtslam::CLSLAMParticleData, mrpt::maps::CReflectivityGridMap2D, mrpt::poses::CPose3DPDFGaussianInf, mrpt::nav::CPTG_DiffDrive_C, mrpt::opengl::CAssimpModel, mrpt::opengl::CBox, mrpt::obs::CObservationStereoImages, mrpt::opengl::CMeshFast, mrpt::opengl::CVectorField3D, mrpt::poses::CPose2D, mrpt::poses::CPosePDFParticles, mrpt::hmtslam::CHMHMapNode, mrpt::hmtslam::CRobotPosesGraph, mrpt::poses::CPose3DPDFGaussian, mrpt::obs::CObservationStereoImagesFeatures, mrpt::opengl::CMesh, mrpt::poses::CPose3DPDFParticles, mrpt::hmtslam::CMHPropertiesValuesList, mrpt::maps::CBeacon, mrpt::opengl::CMesh3D, mrpt::opengl::CText, mrpt::maps::CHeightGridMap2D_MRF, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::poses::CPosePDFGaussianInf, mrpt::poses::CPosePDFSOG, mrpt::hmtslam::CHMHMapArc, mrpt::maps::COctoMap, mrpt::opengl::CColorBar, mrpt::opengl::CVectorField2D, mrpt::poses::CPoint2D, mrpt::poses::CPointPDFSOG, mrpt::maps::CRBPFParticleData, mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CSimpleMap, mrpt::obs::CObservationImage, mrpt::maps::CLandmark, mrpt::poses::CPoint3D, mrpt::poses::CPose3DPDFSOG, mrpt::hmtslam::CHierarchicalMHMap, mrpt::maps::CColouredOctoMap, mrpt::obs::CObservationBatteryState, mrpt::opengl::CDisk, mrpt::opengl::CSetOfLines, mrpt::nav::CLogFileRecord, mrpt::obs::CActionRobotMovement2D, mrpt::obs::CObservationOdometry, mrpt::obs::CObservationRawDAQ, mrpt::opengl::CCamera, mrpt::opengl::CCylinder, mrpt::opengl::CGridPlaneXY, mrpt::opengl::CGridPlaneXZ, mrpt::poses::CPointPDFParticles, mrpt::maps::CSimplePointsMap, mrpt::obs::CObservationBearingRange, mrpt::obs::CObservationWindSensor, mrpt::opengl::CArrow, mrpt::opengl::CAxis, mrpt::opengl::CGeneralizedCylinder, mrpt::opengl::CSphere, mrpt::poses::CPosePDFGaussian, mrpt::maps::CWeightedPointsMap, mrpt::obs::CObservationRange, mrpt::img::TCamera, mrpt::maps::CColouredPointsMap, mrpt::obs::CActionRobotMovement3D, mrpt::obs::CObservationWirelessPower, mrpt::nav::CLogFileRecord_VFF, mrpt::nav::CPTG_Holo_Blend, mrpt::obs::CActionCollection, mrpt::obs::CObservation6DFeatures, mrpt::obs::CObservationSkeleton, mrpt::opengl::CSetOfObjects, mrpt::obs::CObservationVisualLandmarks, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, mrpt::obs::CObservationBeaconRanges, mrpt::obs::CObservationComment, mrpt::obs::CObservationGasSensors, mrpt::obs::CObservationReflectivity, mrpt::obs::CObservationRFID, mrpt::poses::CPosePDFGrid, mrpt::math::CSplineInterpolator1D, mrpt::opengl::COpenGLStandardObject, mrpt::poses::CPoses2DSequence, mrpt::poses::CPoses3DSequence, mrpt::img::TStereoCamera, mrpt::math::CMatrixD, mrpt::opengl::CSetOfTriangles, mrpt::poses::CPointPDFGaussian, mrpt::hmtslam::CPropertiesValuesList, mrpt::math::CMatrix, mrpt::obs::CObservationCANBusJ1939, mrpt::obs::CObservationRobotPose, mrpt::math::CMatrixB, mrpt::opengl::CSetOfTexturedTriangles, mrpt::poses::CPoint2DPDFGaussian, mrpt::math::CPolygon, mrpt::opengl::CSimpleLine, mrpt::opengl::CTexturedPlane, mrpt::db::CSimpleDatabaseTable, mrpt::kinematics::CVehicleVelCmd_DiffDriven, mrpt::kinematics::CVehicleVelCmd_Holo, and MyNS::Foo.

Referenced by mrpt::serialization::CArchive::WriteObject().

◆ setSensorPose() [1/2]

void CObservation::setSensorPose ( const mrpt::math::TPose3D newSensorPose)

A general method to change the sensor pose on the robot.

Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.

See also
getSensorPose

Definition at line 33 of file CObservation.cpp.

◆ setSensorPose() [2/2]

virtual void mrpt::obs::CObservation::setSensorPose ( const mrpt::poses::CPose3D newSensorPose)
pure virtual

◆ swap()

void CObservation::swap ( CObservation o)
protected

Swap with another observation, ONLY the data defined here in the base class CObservation.

It's protected since it'll be only called from child classes that should know what else to swap appart from these common data.

Definition at line 38 of file CObservation.cpp.

References sensorLabel, and timestamp.

Referenced by mrpt::obs::CObservationStereoImages::swap(), and mrpt::obs::CObservation3DRangeScan::swap().

◆ unload()

virtual void mrpt::obs::CObservation::unload ( )
inlinevirtual

Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).

See also
load

Reimplemented in mrpt::obs::CObservation3DRangeScan.

Definition at line 161 of file CObservation.h.

◆ writeToMatlab()

virtual mxArray* mrpt::serialization::CSerializable::writeToMatlab ( ) const
inlinevirtualinherited

Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.

Returns
A new mxArray (caller is responsible of memory freeing) or nullptr is class does not support conversion to MATLAB.

Definition at line 70 of file CSerializable.h.

Member Data Documentation

◆ runtimeClassId

const mrpt::rtti::TRuntimeClassId mrpt::obs::CObservation::runtimeClassId
staticprotected

Definition at line 45 of file CObservation.h.

◆ sensorLabel

std::string mrpt::obs::CObservation::sensorLabel

An arbitrary label that can be used to identify the sensor.

Definition at line 62 of file CObservation.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CImpinjRFID::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::obs::CObservation6DFeatures::serializeFrom(), mrpt::obs::CObservation3DRangeScan::serializeFrom(), mrpt::obs::CObservation6DFeatures::serializeTo(), mrpt::obs::CObservation3DRangeScan::serializeTo(), and swap().

◆ timestamp

mrpt::system::TTimeStamp mrpt::obs::CObservation::timestamp {mrpt::system::now()}

The associated UTC time-stamp.

Where available, this should contain the accurate satellite-based timestamp of the sensor reading.

See also
getOriginalReceivedTimeStamp(), getTimeStamp()

Definition at line 60 of file CObservation.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::detectors::CObjectDetection::detectObjects(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CCameraSensor::getNextFrame(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), getOriginalReceivedTimeStamp(), getTimeStamp(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::obs::CObservation6DFeatures::serializeFrom(), mrpt::obs::CObservation3DRangeScan::serializeFrom(), mrpt::obs::CObservation6DFeatures::serializeTo(), mrpt::obs::CObservation3DRangeScan::serializeTo(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), swap(), and velodyne_scan_to_pointcloud().




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