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

Detailed Description

Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from a set of RGBD sensors.

This kind of observations can carry one or more of these data fields:

The coordinates of the 3D point cloud are in millimeters with respect to the RGB camera origin of coordinates

The 2D images and matrices are stored as common images, with an up->down rows order and left->right, as usual. Optionally, the intensity and confidence channels can be set to delayed-load images for off-rawlog storage so it saves memory by having loaded in memory just the needed images. See the methods load() and unload(). Due to the intensive storage requirements of this kind of observations, this observation is the only one in MRPT for which it's recommended to always call "load()" and "unload()" before and after using the observation, ONLY when the observation was read from a rawlog dataset, in order to make sure that all the externally stored data fields are loaded and ready in memory.

Classes that grab observations of this type are:

3D point clouds can be generated at any moment after grabbing with CObservationRGBD360::project3DPointsFromDepthImage() and CObservationRGBD360::project3DPointsFromDepthImageInto(), provided the correct calibration parameters.

Note
Starting at serialization version 3 (MRPT 0.9.1+), the 3D point cloud and the rangeImage can both be stored externally to save rawlog space.
Starting at serialization version 5 (MRPT 0.9.5+), the new field range_is_depth
Starting at serialization version 6 (MRPT 0.9.5+), the new field intensityImageChannel
See also
mrpt::hwdrivers::CSwissRanger3DCamera, mrpt::hwdrivers::COpenNI2_RGBD360, CObservation

Definition at line 66 of file obs/CObservationRGBD360.h.

#include <mrpt/obs/CObservationRGBD360.h>

Inheritance diagram for mrpt::obs::CObservationRGBD360:
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 ()
 
 CObservationRGBD360 ()
 Default constructor. More...
 
virtual ~CObservationRGBD360 ()
 Destructor. More...
 
void rangeImage_setSize (const int HEIGHT, const int WIDTH, const unsigned sensor_id)
 Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the memory allocation. 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...
 
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)
 

Public Attributes

mrpt::system::TTimeStamp timestamps [NUM_SENSORS]
 
bool hasRangeImage
 true means the field rangeImage contains valid data More...
 
mrpt::math::CMatrix rangeImages [NUM_SENSORS]
 If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) More...
 
bool hasIntensityImage
 true means the field intensityImage contains valid data More...
 
mrpt::utils::CImage intensityImages [NUM_SENSORS]
 If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage". More...
 
mrpt::utils::TCamera sensorParamss [NUM_SENSORS]
 Projection parameters of the 8 RGBD sensor. More...
 
float maxRange
 The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...) More...
 
mrpt::poses::CPose3D sensorPose
 The 6D pose of the sensor on the robot. More...
 
float stdError
 The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid. More...
 

Static Public Attributes

static const unsigned int NUM_SENSORS = 2
 
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...
 

Protected Attributes

bool m_points3D_external_stored
 If set to true, m_points3D_external_file is valid. More...
 
std::string m_points3D_external_file
 3D points are in CImage::IMAGES_PATH_BASE+<this_file_name> More...
 
bool m_rangeImage_external_stored
 If set to true, m_rangeImage_external_file is valid. More...
 
std::string m_rangeImage_external_file
 rangeImage is in CImage::IMAGES_PATH_BASE+<this_file_name> 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 CObservationRGBD360Ptr Ptr
 
typedef CObservationRGBD360Ptr ConstPtr
 
static mrpt::utils::CLASSINIT _init_CObservationRGBD360
 
static mrpt::utils::TRuntimeClassId classCObservationRGBD360
 
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 CObservationRGBD360Ptr Create ()
 

Member Typedef Documentation

◆ ConstPtr

typedef CObservationRGBD360Ptr mrpt::obs::CObservationRGBD360::ConstPtr

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ Ptr

typedef CObservationRGBD360Ptr mrpt::obs::CObservationRGBD360::Ptr

A typedef for the associated smart pointer

Definition at line 69 of file obs/CObservationRGBD360.h.

Constructor & Destructor Documentation

◆ CObservationRGBD360()

CObservationRGBD360::CObservationRGBD360 ( )

Default constructor.

Definition at line 31 of file CObservationRGBD360.cpp.

◆ ~CObservationRGBD360()

CObservationRGBD360::~CObservationRGBD360 ( )
virtual

Destructor.

Definition at line 50 of file CObservationRGBD360.cpp.

References mempool_donate_range_matrix(), and mempool_donate_xyz_buffers().

Member Function Documentation

◆ _GetBaseClass()

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

◆ clone()

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

Cloning interface for smart pointers.

Definition at line 133 of file CObject.h.

◆ Create()

static CObservationRGBD360Ptr mrpt::obs::CObservationRGBD360::Create ( )
static

◆ CreateObject()

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

◆ duplicate()

virtual mrpt::utils::CObject* mrpt::obs::CObservationRGBD360::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 CObservationRGBD360::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 from mrpt::obs::CObservation.

Definition at line 171 of file CObservationRGBD360.cpp.

◆ 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::CObservationRGBD360::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::CObservationRGBD360::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 100 of file obs/CObservationRGBD360.h.

◆ 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::CObservationRGBD360::operator delete ( void ptr)
throw (
)
inline

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ operator delete() [2/3]

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

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ operator delete() [3/3]

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

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ operator delete[]()

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

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ operator new() [1/3]

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

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ operator new() [2/3]

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

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ operator new() [3/3]

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

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ operator new[]()

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

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ rangeImage_setSize()

void CObservationRGBD360::rangeImage_setSize ( const int  HEIGHT,
const int  WIDTH,
const unsigned  sensor_id 
)

Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the memory allocation.

Definition at line 145 of file CObservationRGBD360.cpp.

References mrpt::system::CGenericMemoryPool< DATA_PARAMS, POOLABLE_DATA >::getInstance(), and mrpt::system::CGenericMemoryPool< DATA_PARAMS, POOLABLE_DATA >::request_memory().

◆ readFromStream()

void CObservationRGBD360::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 100 of file CObservationRGBD360.cpp.

References MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, and version.

◆ setSensorPose() [1/2]

void mrpt::obs::CObservationRGBD360::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 101 of file obs/CObservationRGBD360.h.

◆ setSensorPose() [2/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.

◆ swap()

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 mrpt::obs::CObservationStereoImages::swap(), and mrpt::obs::CObservation3DRangeScan::swap().

◆ 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 CObservationRGBD360::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 61 of file CObservationRGBD360.cpp.

References version.

Member Data Documentation

◆ _init_CObservationRGBD360

mrpt::utils::CLASSINIT mrpt::obs::CObservationRGBD360::_init_CObservationRGBD360
staticprotected

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ 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.

◆ classCObservationRGBD360

mrpt::utils::TRuntimeClassId mrpt::obs::CObservationRGBD360::classCObservationRGBD360
static

Definition at line 69 of file obs/CObservationRGBD360.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::CObservationRGBD360::classinfo
static

Definition at line 69 of file obs/CObservationRGBD360.h.

◆ hasIntensityImage

bool mrpt::obs::CObservationRGBD360::hasIntensityImage

true means the field intensityImage contains valid data

Definition at line 91 of file obs/CObservationRGBD360.h.

Referenced by mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation().

◆ hasRangeImage

bool mrpt::obs::CObservationRGBD360::hasRangeImage

true means the field rangeImage contains valid data

Definition at line 86 of file obs/CObservationRGBD360.h.

Referenced by mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation().

◆ intensityImages

mrpt::utils::CImage mrpt::obs::CObservationRGBD360::intensityImages[NUM_SENSORS]

If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".

Definition at line 92 of file obs/CObservationRGBD360.h.

Referenced by mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation().

◆ m_points3D_external_file

std::string mrpt::obs::CObservationRGBD360::m_points3D_external_file
protected

3D points are in CImage::IMAGES_PATH_BASE+<this_file_name>

Definition at line 73 of file obs/CObservationRGBD360.h.

◆ m_points3D_external_stored

bool mrpt::obs::CObservationRGBD360::m_points3D_external_stored
protected

If set to true, m_points3D_external_file is valid.

Definition at line 72 of file obs/CObservationRGBD360.h.

◆ m_rangeImage_external_file

std::string mrpt::obs::CObservationRGBD360::m_rangeImage_external_file
protected

rangeImage is in CImage::IMAGES_PATH_BASE+<this_file_name>

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

◆ m_rangeImage_external_stored

bool mrpt::obs::CObservationRGBD360::m_rangeImage_external_stored
protected

If set to true, m_rangeImage_external_file is valid.

Definition at line 75 of file obs/CObservationRGBD360.h.

◆ maxRange

float mrpt::obs::CObservationRGBD360::maxRange

The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...)

Definition at line 95 of file obs/CObservationRGBD360.h.

◆ NUM_SENSORS

const unsigned int mrpt::obs::CObservationRGBD360::NUM_SENSORS = 2
static

Definition at line 82 of file obs/CObservationRGBD360.h.

◆ rangeImages

mrpt::math::CMatrix mrpt::obs::CObservationRGBD360::rangeImages[NUM_SENSORS]

If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters)

See also
range_is_depth

Definition at line 87 of file obs/CObservationRGBD360.h.

Referenced by mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation().

◆ 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(), mrpt::obs::CObservationStereoImages::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(), mrpt::obs::CObservationStereoImages::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().

◆ sensorParamss

mrpt::utils::TCamera mrpt::obs::CObservationRGBD360::sensorParamss[NUM_SENSORS]

Projection parameters of the 8 RGBD sensor.

Definition at line 93 of file obs/CObservationRGBD360.h.

◆ sensorPose

mrpt::poses::CPose3D mrpt::obs::CObservationRGBD360::sensorPose

The 6D pose of the sensor on the robot.

Definition at line 96 of file obs/CObservationRGBD360.h.

◆ stdError

float mrpt::obs::CObservationRGBD360::stdError

The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.

Definition at line 97 of file obs/CObservationRGBD360.h.

◆ 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(), mrpt::obs::CObservationStereoImages::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(), mrpt::obs::CObservationStereoImages::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().

◆ timestamps

mrpt::system::TTimeStamp mrpt::obs::CObservationRGBD360::timestamps[NUM_SENSORS]



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