Main MRPT website > C++ reference for MRPT 1.5.9
List of all members | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions
mrpt::obs::CObservationStereoImages Class Reference

Detailed Description

Observation class for either a pair of left+right or left+disparity images from a stereo camera.

To find whether the observation contains a right image and/or a disparity image, see the fields hasImageDisparity and hasImageRight, respectively.

This figure illustrates the coordinate frames involved in this class:

  <center>
Note
The images stored in this class can be raw or undistorted images. In the latter case, the "distortion" params of the corresponding "leftCamera" and "rightCamera" fields should be all zeros.
See also
CObservation

Definition at line 41 of file obs/CObservationStereoImages.h.

#include <mrpt/obs/CObservationStereoImages.h>

Inheritance diagram for mrpt::obs::CObservationStereoImages:
Inheritance graph

Public Member Functions

voidoperator new (size_t size)
 
voidoperator new[] (size_t size)
 
void operator delete (void *ptr) throw ()
 
void operator delete[] (void *ptr) throw ()
 
void operator delete (void *memory, void *ptr) throw ()
 
voidoperator new (size_t size, const std::nothrow_t &) throw ()
 
void operator delete (void *ptr, const std::nothrow_t &) throw ()
 
 CObservationStereoImages ()
 Default Constructor. More...
 
 CObservationStereoImages (void *iplImageLeft, void *iplImageRight, void *iplImageDisparity=NULL, bool ownMemory=false)
 Constructor from "IplImage*" images, which could be NULL. More...
 
 ~CObservationStereoImages ()
 Destructor. More...
 
void getSensorPose (mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
 A general method to retrieve the sensor pose on the robot. More...
 
void setSensorPose (const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
 A general method to change the sensor pose on the robot. More...
 
void getDescriptionAsText (std::ostream &o) const MRPT_OVERRIDE
 Build a detailed, multi-line textual description of the observation contents and dump it to the output stream. More...
 
void swap (CObservationStereoImages &o)
 Do an efficient swap of all data members of this object with "o". More...
 
template<class METRICMAP >
bool insertObservationInto (METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose=NULL) const
 This method is equivalent to: More...
 
void getSensorPose (mrpt::math::TPose3D &out_sensorPose) const
 A general method to retrieve 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 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...
 
CObjectclone () const
 Cloning interface for smart pointers. More...
 
Delayed-load manual control methods.
virtual void load () const
 Makes sure all images and other fields which may be externally stored are loaded in memory. More...
 
virtual void unload ()
 Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect). More...
 
RTTI classes and functions
mrpt::utils::CObjectPtr duplicateGetSmartPtr () const
 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). More...
 

Static Public Member Functions

static voidoperator new (size_t size, void *ptr)
 

Static Public Attributes

static const mrpt::utils::TRuntimeClassId classCObject
 
RTTI stuff
static const mrpt::utils::TRuntimeClassId classCObservation
 
RTTI stuff
static const mrpt::utils::TRuntimeClassId classCSerializable
 

Protected Member Functions

void swap (CObservation &o)
 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. More...
 
CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const
 Introduces a pure virtual method responsible for writing to a CStream. More...
 
void readFromStream (mrpt::utils::CStream &in, int version)
 Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More...
 

Data common to any observation

mrpt::system::TTimeStamp timestamp
 The associated UTC time-stamp. Where available, this should contain the accurate satellite-based timestamp of the sensor reading. 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...
 

RTTI stuff

typedef CObservationStereoImagesPtr Ptr
 
typedef CObservationStereoImagesPtr ConstPtr
 
static mrpt::utils::CLASSINIT _init_CObservationStereoImages
 
static mrpt::utils::TRuntimeClassId classCObservationStereoImages
 
static const mrpt::utils::TRuntimeClassIdclassinfo
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const
 Returns information about the class of an object in runtime. More...
 
virtual mrpt::utils::CObjectduplicate () const
 Returns a copy of the object, indepently of its class. More...
 
static mrpt::utils::CObjectCreateObject ()
 
static CObservationStereoImagesPtr Create ()
 

Main observation data members

mrpt::utils::CImage imageLeft
 Image from the left camera (this image will be ALWAYS present) More...
 
mrpt::utils::CImage imageRight
 Image from the right camera, only contains a valid image if hasImageRight == true. More...
 
mrpt::utils::CImage imageDisparity
 Disparity image, only contains a valid image if hasImageDisparity == true. More...
 
bool hasImageDisparity
 Whether imageDisparity actually contains data (Default upon construction: false) More...
 
bool hasImageRight
 Whether imageRight actually contains data (Default upon construction: true) More...
 
mrpt::utils::TCamera leftCamera
 Parameters for the left/right cameras: individual intrinsic and distortion parameters of the cameras. More...
 
mrpt::utils::TCamera rightCamera
 
mrpt::poses::CPose3DQuat cameraPose
 The pose of the LEFT camera, relative to the robot. More...
 
mrpt::poses::CPose3DQuat rightCameraPose
 The pose of the right camera, relative to the left one: Note that using the conventional reference coordinates for the left camera (x points to the right, y down), the "right" camera is situated at position (BL, 0, 0) with yaw=pitch=roll=0, where BL is the BASELINE. More...
 
void getStereoCameraParams (mrpt::utils::TStereoCamera &out_params) const
 Populates a TStereoCamera structure with the parameters in leftCamera, rightCamera and rightCameraPose. More...
 
void setStereoCameraParams (const mrpt::utils::TStereoCamera &in_params)
 Sets leftCamera, rightCamera and rightCameraPose from a TStereoCamera structure. More...
 
bool areImagesRectified () const
 This method only checks whether ALL the distortion parameters in leftCamera are set to zero, which is the convention in MRPT to denote that this pair of stereo images has been rectified. More...
 

Member Typedef Documentation

◆ ConstPtr

typedef CObservationStereoImagesPtr mrpt::obs::CObservationStereoImages::ConstPtr

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ Ptr

typedef CObservationStereoImagesPtr mrpt::obs::CObservationStereoImages::Ptr

A typedef for the associated smart pointer

Definition at line 44 of file obs/CObservationStereoImages.h.

Constructor & Destructor Documentation

◆ CObservationStereoImages() [1/2]

CObservationStereoImages::CObservationStereoImages ( )

Default Constructor.

Definition at line 48 of file CObservationStereoImages.cpp.

◆ CObservationStereoImages() [2/2]

CObservationStereoImages::CObservationStereoImages ( void iplImageLeft,
void iplImageRight,
void iplImageDisparity = NULL,
bool  ownMemory = false 
)

Constructor from "IplImage*" images, which could be NULL.

The fields hasImageDisparity and hasImageRight will be set to true/false depending on them being !=NULL. Note that the IplImage's will be COPIED, so it's still the caller's reponsibility to free the original images, unless ownMemory is set to true: in that case the IplImage pointers are copied and those IplImage's will be automatically freed by this object.

Definition at line 30 of file CObservationStereoImages.cpp.

◆ ~CObservationStereoImages()

CObservationStereoImages::~CObservationStereoImages ( )

Destructor.

Definition at line 57 of file CObservationStereoImages.cpp.

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId* mrpt::obs::CObservationStereoImages::_GetBaseClass ( )
staticprotected

◆ areImagesRectified()

bool CObservationStereoImages::areImagesRectified ( ) const

This method only checks whether ALL the distortion parameters in leftCamera are set to zero, which is the convention in MRPT to denote that this pair of stereo images has been rectified.

Definition at line 230 of file CObservationStereoImages.cpp.

References mrpt::utils::TCamera::dist, and leftCamera.

◆ clone()

CObject* mrpt::utils::CObject::clone ( ) const
inlineinherited

Cloning interface for smart pointers.

Definition at line 133 of file CObject.h.

◆ Create()

static CObservationStereoImagesPtr mrpt::obs::CObservationStereoImages::Create ( )
static

◆ CreateObject()

static mrpt::utils::CObject* mrpt::obs::CObservationStereoImages::CreateObject ( )
static

◆ duplicate()

virtual mrpt::utils::CObject* mrpt::obs::CObservationStereoImages::duplicate ( ) const
virtual

Returns a copy of the object, indepently of its class.

Implements mrpt::utils::CObject.

◆ duplicateGetSmartPtr()

mrpt::utils::CObjectPtr 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 162 of file CObject.h.

References mrpt::utils::CObjectPtr.

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

◆ getDescriptionAsText()

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

◆ getOriginalReceivedTimeStamp()

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

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 58 of file obs/CObservation.h.

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId* mrpt::obs::CObservationStereoImages::GetRuntimeClass ( ) const
virtual

Returns information about the class of an object in runtime.

Reimplemented from mrpt::obs::CObservation.

◆ getSensorPose() [1/2]

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

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 38 of file CObservation.cpp.

◆ getSensorPose() [2/2]

void mrpt::obs::CObservationStereoImages::getSensorPose ( mrpt::poses::CPose3D out_sensorPose) const
inlinevirtual

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

Implements mrpt::obs::CObservation.

Definition at line 111 of file obs/CObservationStereoImages.h.

◆ getStereoCameraParams()

void CObservationStereoImages::getStereoCameraParams ( mrpt::utils::TStereoCamera out_params) const

Populates a TStereoCamera structure with the parameters in leftCamera, rightCamera and rightCameraPose.

See also
areImagesRectified()

Definition at line 212 of file CObservationStereoImages.cpp.

References mrpt::utils::TStereoCamera::leftCamera, leftCamera, mrpt::utils::TStereoCamera::rightCamera, rightCamera, mrpt::utils::TStereoCamera::rightCameraPose, and rightCameraPose.

Referenced by getDescriptionAsText(), and mrpt::vision::CStereoRectifyMap::setFromCamParams().

◆ getTimeStamp()

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

Returns CObservation::timestamp for all kind of observations.

See also
getOriginalReceivedTimeStamp()

Definition at line 56 of file obs/CObservation.h.

◆ insertObservationInto()

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

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 NULL (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 77 of file obs/CObservation.h.

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

◆ load()

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

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 119 of file obs/CObservation.h.

◆ operator delete() [1/3]

void mrpt::obs::CObservationStereoImages::operator delete ( void ptr)
throw (
)
inline

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ operator delete() [2/3]

void mrpt::obs::CObservationStereoImages::operator delete ( void memory,
void ptr 
)
throw (
)
inline

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ operator delete() [3/3]

void mrpt::obs::CObservationStereoImages::operator delete ( void ptr,
const std::nothrow_t &   
)
throw (
)
inline

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ operator delete[]()

void mrpt::obs::CObservationStereoImages::operator delete[] ( void ptr)
throw (
)
inline

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ operator new() [1/3]

void* mrpt::obs::CObservationStereoImages::operator new ( size_t  size)
inline

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ operator new() [2/3]

static void* mrpt::obs::CObservationStereoImages::operator new ( size_t  size,
void ptr 
)
inlinestatic

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ operator new() [3/3]

void* mrpt::obs::CObservationStereoImages::operator new ( size_t  size,
const std::nothrow_t &   
)
throw (
)
inline

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ operator new[]()

void* mrpt::obs::CObservationStereoImages::operator new[] ( size_t  size)
inline

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ readFromStream()

void CObservationStereoImages::readFromStream ( mrpt::utils::CStream in,
int  version 
)
protectedvirtual

Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.

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 error, see CStream::ReadBuffer
See also
CStream

Implements mrpt::utils::CSerializable.

Definition at line 92 of file CObservationStereoImages.cpp.

References cameraPose, mrpt::utils::TCamera::focalLengthMeters, hasImageDisparity, hasImageRight, imageDisparity, imageLeft, imageRight, mrpt::utils::TCamera::intrinsicParams, INVALID_TIMESTAMP, leftCamera, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, rightCamera, rightCameraPose, mrpt::obs::CObservation::sensorLabel, mrpt::obs::CObservation::timestamp, and version.

◆ setSensorPose() [1/2]

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

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 45 of file CObservation.cpp.

◆ setSensorPose() [2/2]

void mrpt::obs::CObservationStereoImages::setSensorPose ( const mrpt::poses::CPose3D newSensorPose)
inlinevirtual

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

Implements mrpt::obs::CObservation.

Definition at line 112 of file obs/CObservationStereoImages.h.

◆ setStereoCameraParams()

void CObservationStereoImages::setStereoCameraParams ( const mrpt::utils::TStereoCamera in_params)

◆ swap() [1/2]

void CObservation::swap ( CObservation o)
protectedinherited

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 50 of file CObservation.cpp.

References mrpt::obs::CObservation::sensorLabel, and mrpt::obs::CObservation::timestamp.

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

◆ swap() [2/2]

void CObservationStereoImages::swap ( CObservationStereoImages o)

◆ unload()

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

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 123 of file obs/CObservation.h.

◆ writeToMatlab()

virtual mxArray* mrpt::utils::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 NULL is class does not support conversion to MATLAB.

Definition at line 79 of file CSerializable.h.

◆ writeToStream()

void CObservationStereoImages::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
protectedvirtual

Introduces a pure virtual method responsible for writing to a CStream.

This can not be used directly be users, instead use "stream << object;" for writing it to a stream.

Parameters
outThe output binary stream where object must be dumped.
getVersionIf NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data.
Exceptions
std::exceptionOn any error, see CStream::WriteBuffer
See also
CStream

Implements mrpt::utils::CSerializable.

Definition at line 64 of file CObservationStereoImages.cpp.

References cameraPose, hasImageDisparity, hasImageRight, imageDisparity, imageLeft, imageRight, leftCamera, rightCamera, rightCameraPose, mrpt::obs::CObservation::sensorLabel, mrpt::obs::CObservation::timestamp, and version.

Member Data Documentation

◆ _init_CObservationStereoImages

mrpt::utils::CLASSINIT mrpt::obs::CObservationStereoImages::_init_CObservationStereoImages
staticprotected

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ cameraPose

mrpt::poses::CPose3DQuat mrpt::obs::CObservationStereoImages::cameraPose

◆ classCObject

const mrpt::utils::TRuntimeClassId mrpt::utils::CObject::classCObject
staticinherited

Definition at line 118 of file CObject.h.

◆ classCObservation

const mrpt::utils::TRuntimeClassId mrpt::obs::CObservation::classCObservation
staticinherited

Definition at line 43 of file obs/CObservation.h.

◆ classCObservationStereoImages

mrpt::utils::TRuntimeClassId mrpt::obs::CObservationStereoImages::classCObservationStereoImages
static

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ classCSerializable

const mrpt::utils::TRuntimeClassId mrpt::utils::CSerializable::classCSerializable
staticinherited

Definition at line 42 of file CSerializable.h.

◆ classinfo

const mrpt::utils::TRuntimeClassId* mrpt::obs::CObservationStereoImages::classinfo
static

Definition at line 44 of file obs/CObservationStereoImages.h.

◆ hasImageDisparity

bool mrpt::obs::CObservationStereoImages::hasImageDisparity

Whether imageDisparity actually contains data (Default upon construction: false)

Definition at line 78 of file obs/CObservationStereoImages.h.

Referenced by getDescriptionAsText(), readFromStream(), swap(), and writeToStream().

◆ hasImageRight

bool mrpt::obs::CObservationStereoImages::hasImageRight

Whether imageRight actually contains data (Default upon construction: true)

Definition at line 79 of file obs/CObservationStereoImages.h.

Referenced by getDescriptionAsText(), readFromStream(), mrpt::vision::CStereoRectifyMap::rectify(), swap(), and writeToStream().

◆ imageDisparity

mrpt::utils::CImage mrpt::obs::CObservationStereoImages::imageDisparity

Disparity image, only contains a valid image if hasImageDisparity == true.

The relation between the actual disparity and pixels and each value in this image is... ???????????

Definition at line 76 of file obs/CObservationStereoImages.h.

Referenced by getDescriptionAsText(), readFromStream(), swap(), and writeToStream().

◆ imageLeft

mrpt::utils::CImage mrpt::obs::CObservationStereoImages::imageLeft

◆ imageRight

mrpt::utils::CImage mrpt::obs::CObservationStereoImages::imageRight

◆ leftCamera

mrpt::utils::TCamera mrpt::obs::CObservationStereoImages::leftCamera

◆ rightCamera

mrpt::utils::TCamera mrpt::obs::CObservationStereoImages::rightCamera

◆ rightCameraPose

mrpt::poses::CPose3DQuat mrpt::obs::CObservationStereoImages::rightCameraPose

The pose of the right camera, relative to the left one: Note that using the conventional reference coordinates for the left camera (x points to the right, y down), the "right" camera is situated at position (BL, 0, 0) with yaw=pitch=roll=0, where BL is the BASELINE.

Definition at line 94 of file obs/CObservationStereoImages.h.

Referenced by mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), getStereoCameraParams(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), readFromStream(), mrpt::vision::CStereoRectifyMap::rectify(), setStereoCameraParams(), mrpt::vision::StereoObs2BRObs(), swap(), and writeToStream().

◆ sensorLabel

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

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

Definition at line 53 of file obs/CObservation.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), 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::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CImpinjRFID::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::obs::CObservation6DFeatures::readFromStream(), readFromStream(), mrpt::obs::CObservation2DRangeScan::readFromStream(), mrpt::obs::CObservationVelodyneScan::readFromStream(), mrpt::obs::CObservation3DRangeScan::readFromStream(), mrpt::obs::CObservation::swap(), mrpt::obs::CObservationGPS::swap(), mrpt::obs::CObservation6DFeatures::writeToStream(), writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().

◆ timestamp

mrpt::system::TTimeStamp mrpt::obs::CObservation::timestamp
inherited

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 52 of file obs/CObservation.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservationVelodyneScan::TPointCloud::clear_deep(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), 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::obs::CObservationGasSensors::CMOSmodel::get_GasDistribution_estimation(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::obs::CObservationGasSensors::CMOSmodel::inverse_MOSmodeling(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::obs::CObservationGasSensors::CMOSmodel::noise_filtering(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::obs::CObservation6DFeatures::readFromStream(), readFromStream(), mrpt::obs::CObservation2DRangeScan::readFromStream(), mrpt::obs::CObservationVelodyneScan::readFromStream(), mrpt::obs::CObservation3DRangeScan::readFromStream(), mrpt::obs::CObservationGasSensors::CMOSmodel::save_log_map(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::obs::CObservation::swap(), mrpt::obs::CObservationGPS::swap(), velodyne_scan_to_pointcloud(), mrpt::obs::CObservation6DFeatures::writeToStream(), writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().




Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020