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

Detailed Description

A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser scanner).

The data structures are generic enough to hold a wide variety of 2D scanners and "3D" planar rotating 2D lasers.

These are the most important data fields:

See Also
CObservation, CPointsMap, T2DScanProperties

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

#include <mrpt/obs/CObservation2DRangeScan.h>

Inheritance diagram for mrpt::obs::CObservation2DRangeScan:
Inheritance graph

Public Types

typedef std::vector
< mrpt::math::CPolygon
TListExclusionAreas
 Used in filterByExclusionAreas. More...
 
typedef std::vector< std::pair
< mrpt::math::CPolygon,
std::pair< double, double > > > 
TListExclusionAreasWithRanges
 Used in filterByExclusionAreas. More...
 

Public Member Functions

void * operator new (size_t size)
 
void * operator new[] (size_t size)
 
void operator delete (void *ptr) throw ()
 
void operator delete[] (void *ptr) throw ()
 
void operator delete (void *memory, void *ptr) throw ()
 
void * operator new (size_t size, const std::nothrow_t &) throw ()
 
void operator delete (void *ptr, const std::nothrow_t &) throw ()
 
 CObservation2DRangeScan ()
 Default constructor. More...
 
 CObservation2DRangeScan (const CObservation2DRangeScan &o)
 copy ctor More...
 
virtual ~CObservation2DRangeScan ()
 Destructor. More...
 
void loadFromVectors (size_t nRays, const float *scanRanges, const char *scanValidity)
 
bool isPlanarScan (const double tolerance=0) const
 Return true if the laser scanner is "horizontal", so it has an absolute value of "pitch" and "roll" less or equal to the given tolerance (in rads, default=0) (with the normal vector either upwards or downwards). More...
 
bool hasIntensity () const
 Return true if scan has intensity. More...
 
void setScanHasIntensity (bool setHasIntensityFlag)
 Marks this scan as having or not intensity data. 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 truncateByDistanceAndAngle (float min_distance, float max_angle, float min_height=0, float max_height=0, float h=0)
 A general method to truncate the scan by defining a minimum valid distance and a maximum valid angle as well as minimun and maximum heights (NOTE: the laser z-coordinate must be provided). More...
 
void filterByExclusionAreas (const TListExclusionAreas &areas)
 Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinates relative to the vehicle (taking into account "sensorPose"). More...
 
void filterByExclusionAreas (const TListExclusionAreasWithRanges &areas)
 Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinates relative to the vehicle (taking into account "sensorPose"), AND such as the Z coordinate of the point falls in the range [min,max] associated to each exclusion polygon. More...
 
void filterByExclusionAngles (const std::vector< std::pair< double, double > > &angles)
 Mark as invalid the ranges in any of a given set of "forbiden angle ranges", given as pairs<min_angle,max_angle>. 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...
 
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...
 
CObject * clone () 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...
 

Static Public Member Functions

static void * operator 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...
 

Private Attributes

std::vector< float > m_scan
 The range values of the scan, in meters. Must have same length than validRange. More...
 
std::vector< int32_t > m_intensity
 The intensity values of the scan. If available, must have same length than validRange. More...
 
std::vector< char > m_validRange
 It's false (=0) on no reflected rays, referenced to elements in scan. More...
 
bool m_has_intensity
 Whether the intensity values are present or not. If not, space is saved during serialization. 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 CObservation2DRangeScanPtr SmartPtr
 
static mrpt::utils::CLASSINIT _init_CObservation2DRangeScan
 
static mrpt::utils::TRuntimeClassId classCObservation2DRangeScan
 
static const
mrpt::utils::TRuntimeClassId
classinfo
 
static const
mrpt::utils::TRuntimeClassId
_GetBaseClass ()
 
virtual const
mrpt::utils::TRuntimeClassId
GetRuntimeClass () 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 CObservation2DRangeScanPtr Create ()
 

Scan data

mrpt::utils::ContainerReadOnlyProxyAccessor
< std::vector< float > > 
scan
 The range values of the scan, in meters. Must have same length than validRange. More...
 
mrpt::utils::ContainerReadOnlyProxyAccessor
< std::vector< int32_t > > 
intensity
 The intensity values of the scan. If available, must have same length than validRange. More...
 
mrpt::utils::ContainerReadOnlyProxyAccessor
< std::vector< char > > 
validRange
 It's false (=0) on no reflected rays, referenced to elements in scan. More...
 
float aperture
 The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees). More...
 
bool rightToLeft
 The scanning direction: true=counterclockwise; false=clockwise. More...
 
float maxRange
 The maximum range allowed by the device, in meters (e.g. 80m, 50m,...) More...
 
mrpt::poses::CPose3D sensorPose
 The 6D pose of the sensor on the robot at the moment of starting the scan. More...
 
float stdError
 The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid. More...
 
float beamAperture
 The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid. More...
 
double deltaPitch
 If the laser gathers data by sweeping in the pitch/elevation angle, this holds the increment in "pitch" (=-"elevation") between the beginning and the end of the scan (the sensorPose member stands for the pose at the beginning of the scan). More...
 
void resizeScan (const size_t len)
 Resizes all data vectors to allocate a given number of scan rays. More...
 
void resizeScanAndAssign (const size_t len, const float rangeVal, const bool rangeValidity, const int32_t rangeIntensity=0)
 Resizes all data vectors to allocate a given number of scan rays and assign default values. More...
 
size_t getScanSize () const
 Get number of scan rays. More...
 
float getScanRange (const size_t i) const
 
void setScanRange (const size_t i, const float val)
 
int32_t getScanIntensity (const size_t i) const
 
void setScanIntensity (const size_t i, const int val)
 
bool getScanRangeValidity (const size_t i) const
 
void setScanRangeValidity (const size_t i, const bool val)
 
void getScanProperties (T2DScanProperties &p) const
 Fill out a T2DScanProperties structure with the parameters of this scan. More...
 

Cached points map

mrpt::maps::CMetricMapPtr m_cachedMap
 A points map, build only under demand by the methods getAuxPointsMap() and buildAuxPointsMap(). More...
 
template<class POINTSMAP >
const POINTSMAP * getAuxPointsMap () const
 Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or NULL otherwise. More...
 
template<class POINTSMAP >
const POINTSMAP * buildAuxPointsMap (const void *options=NULL) const
 Returns a cached points map representing this laser scan, building it upon the first call. More...
 
void internal_buildAuxPointsMap (const void *options=NULL) const
 Internal method, used from buildAuxPointsMap() More...
 

Member Typedef Documentation

typedef CObservation2DRangeScanPtr mrpt::obs::CObservation2DRangeScan::SmartPtr

A typedef for the associated smart pointer

Definition at line 46 of file obs/CObservation2DRangeScan.h.

Used in filterByExclusionAreas.

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

typedef std::vector<std::pair<mrpt::math::CPolygon,std::pair<double,double> > > mrpt::obs::CObservation2DRangeScan::TListExclusionAreasWithRanges

Used in filterByExclusionAreas.

Definition at line 57 of file obs/CObservation2DRangeScan.h.

Constructor & Destructor Documentation

mrpt::obs::CObservation2DRangeScan::CObservation2DRangeScan ( )

Default constructor.

mrpt::obs::CObservation2DRangeScan::CObservation2DRangeScan ( const CObservation2DRangeScan o)

copy ctor

virtual mrpt::obs::CObservation2DRangeScan::~CObservation2DRangeScan ( )
virtual

Destructor.

Member Function Documentation

static const mrpt::utils::TRuntimeClassId* mrpt::obs::CObservation2DRangeScan::_GetBaseClass ( )
staticprotected
template<class POINTSMAP >
const POINTSMAP* mrpt::obs::CObservation2DRangeScan::buildAuxPointsMap ( const void *  options = NULL) const
inline

Returns a cached points map representing this laser scan, building it upon the first call.

Parameters
optionsCan be NULL to use default point maps' insertion options, or a pointer to a "CPointsMap::TInsertionOptions" structure to override some params. Usage:
mrpt::maps::CPointsMap *map = obs->buildAuxPointsMap<mrpt::maps::CPointsMap>(&options or NULL);
See Also
getAuxPointsMap

Definition at line 125 of file obs/CObservation2DRangeScan.h.

Referenced by mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::internal_build_PointCloud_for_observation().

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

Cloning interface for smart pointers.

Definition at line 143 of file CObject.h.

static CObservation2DRangeScanPtr mrpt::obs::CObservation2DRangeScan::Create ( )
static
static mrpt::utils::CObject* mrpt::obs::CObservation2DRangeScan::CreateObject ( )
static
virtual mrpt::utils::CObject* mrpt::obs::CObservation2DRangeScan::duplicate ( ) const
virtual

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

Implements mrpt::utils::CObject.

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

void mrpt::obs::CObservation2DRangeScan::filterByExclusionAngles ( const std::vector< std::pair< double, double > > &  angles)

Mark as invalid the ranges in any of a given set of "forbiden angle ranges", given as pairs<min_angle,max_angle>.

See Also
C2DRangeFinderAbstract::loadExclusionAreas
void mrpt::obs::CObservation2DRangeScan::filterByExclusionAreas ( const TListExclusionAreas areas)

Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinates relative to the vehicle (taking into account "sensorPose").

See Also
C2DRangeFinderAbstract::loadExclusionAreas
void mrpt::obs::CObservation2DRangeScan::filterByExclusionAreas ( const TListExclusionAreasWithRanges areas)

Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinates relative to the vehicle (taking into account "sensorPose"), AND such as the Z coordinate of the point falls in the range [min,max] associated to each exclusion polygon.

See Also
C2DRangeFinderAbstract::loadExclusionAreas
template<class POINTSMAP >
const POINTSMAP* mrpt::obs::CObservation2DRangeScan::getAuxPointsMap ( ) const
inline

Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or NULL otherwise.

Usage:

mrpt::maps::CPointsMap *map = obs->getAuxPointsMap<mrpt::maps::CPointsMap>();
See Also
buildAuxPointsMap

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

void mrpt::obs::CObservation2DRangeScan::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.

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.

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

Returns information about the class of an object in runtime.

Reimplemented from mrpt::obs::CObservation.

int32_t mrpt::obs::CObservation2DRangeScan::getScanIntensity ( const size_t  i) const
void mrpt::obs::CObservation2DRangeScan::getScanProperties ( T2DScanProperties p) const

Fill out a T2DScanProperties structure with the parameters of this scan.

float mrpt::obs::CObservation2DRangeScan::getScanRange ( const size_t  i) const
bool mrpt::obs::CObservation2DRangeScan::getScanRangeValidity ( const size_t  i) const
size_t mrpt::obs::CObservation2DRangeScan::getScanSize ( ) const

Get number of scan rays.

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

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.

bool mrpt::obs::CObservation2DRangeScan::hasIntensity ( ) const

Return true if scan has intensity.

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.

void mrpt::obs::CObservation2DRangeScan::internal_buildAuxPointsMap ( const void *  options = NULL) const
protected

Internal method, used from buildAuxPointsMap()

bool mrpt::obs::CObservation2DRangeScan::isPlanarScan ( const double  tolerance = 0) const

Return true if the laser scanner is "horizontal", so it has an absolute value of "pitch" and "roll" less or equal to the given tolerance (in rads, default=0) (with the normal vector either upwards or downwards).

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.

void mrpt::obs::CObservation2DRangeScan::loadFromVectors ( size_t  nRays,
const float *  scanRanges,
const char *  scanValidity 
)
void mrpt::obs::CObservation2DRangeScan::operator delete ( void *  ptr)
throw (
)
inline

Definition at line 46 of file obs/CObservation2DRangeScan.h.

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

Definition at line 46 of file obs/CObservation2DRangeScan.h.

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

Definition at line 46 of file obs/CObservation2DRangeScan.h.

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

Definition at line 46 of file obs/CObservation2DRangeScan.h.

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

Definition at line 46 of file obs/CObservation2DRangeScan.h.

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

Definition at line 46 of file obs/CObservation2DRangeScan.h.

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

Definition at line 46 of file obs/CObservation2DRangeScan.h.

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

Definition at line 46 of file obs/CObservation2DRangeScan.h.

void mrpt::obs::CObservation2DRangeScan::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.

void mrpt::obs::CObservation2DRangeScan::resizeScan ( const size_t  len)

Resizes all data vectors to allocate a given number of scan rays.

Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()().

void mrpt::obs::CObservation2DRangeScan::resizeScanAndAssign ( const size_t  len,
const float  rangeVal,
const bool  rangeValidity,
const int32_t  rangeIntensity = 0 
)

Resizes all data vectors to allocate a given number of scan rays and assign default values.

void mrpt::obs::CObservation2DRangeScan::setScanHasIntensity ( bool  setHasIntensityFlag)

Marks this scan as having or not intensity data.

void mrpt::obs::CObservation2DRangeScan::setScanIntensity ( const size_t  i,
const int  val 
)
void mrpt::obs::CObservation2DRangeScan::setScanRange ( const size_t  i,
const float  val 
)
void mrpt::obs::CObservation2DRangeScan::setScanRangeValidity ( const size_t  i,
const bool  val 
)
void mrpt::obs::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
void mrpt::obs::CObservation2DRangeScan::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 143 of file obs/CObservation2DRangeScan.h.

void mrpt::obs::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.

void mrpt::obs::CObservation2DRangeScan::truncateByDistanceAndAngle ( float  min_distance,
float  max_angle,
float  min_height = 0,
float  max_height = 0,
float  h = 0 
)

A general method to truncate the scan by defining a minimum valid distance and a maximum valid angle as well as minimun and maximum heights (NOTE: the laser z-coordinate must be provided).

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.

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.

void mrpt::obs::CObservation2DRangeScan::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.

Member Data Documentation

mrpt::utils::CLASSINIT mrpt::obs::CObservation2DRangeScan::_init_CObservation2DRangeScan
staticprotected

Definition at line 46 of file obs/CObservation2DRangeScan.h.

float mrpt::obs::CObservation2DRangeScan::aperture

The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees).

Definition at line 81 of file obs/CObservation2DRangeScan.h.

Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().

float mrpt::obs::CObservation2DRangeScan::beamAperture

The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid.

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

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

Definition at line 128 of file CObject.h.

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

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

mrpt::utils::TRuntimeClassId mrpt::obs::CObservation2DRangeScan::classCObservation2DRangeScan
static

Definition at line 46 of file obs/CObservation2DRangeScan.h.

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

Definition at line 42 of file CSerializable.h.

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

Definition at line 46 of file obs/CObservation2DRangeScan.h.

double mrpt::obs::CObservation2DRangeScan::deltaPitch

If the laser gathers data by sweeping in the pitch/elevation angle, this holds the increment in "pitch" (=-"elevation") between the beginning and the end of the scan (the sensorPose member stands for the pose at the beginning of the scan).

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

Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().

mrpt::utils::ContainerReadOnlyProxyAccessor<std::vector<int32_t> > mrpt::obs::CObservation2DRangeScan::intensity

The intensity values of the scan. If available, must have same length than validRange.

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

mrpt::maps::CMetricMapPtr mrpt::obs::CObservation2DRangeScan::m_cachedMap
mutableprotected

A points map, build only under demand by the methods getAuxPointsMap() and buildAuxPointsMap().

It's a generic smart pointer to avoid depending here in the library mrpt-obs on classes on other libraries.

Definition at line 100 of file obs/CObservation2DRangeScan.h.

bool mrpt::obs::CObservation2DRangeScan::m_has_intensity
private

Whether the intensity values are present or not. If not, space is saved during serialization.

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

std::vector<int32_t> mrpt::obs::CObservation2DRangeScan::m_intensity
private

The intensity values of the scan. If available, must have same length than validRange.

Definition at line 51 of file obs/CObservation2DRangeScan.h.

std::vector<float> mrpt::obs::CObservation2DRangeScan::m_scan
private

The range values of the scan, in meters. Must have same length than validRange.

Definition at line 50 of file obs/CObservation2DRangeScan.h.

std::vector<char> mrpt::obs::CObservation2DRangeScan::m_validRange
private

It's false (=0) on no reflected rays, referenced to elements in scan.

Definition at line 52 of file obs/CObservation2DRangeScan.h.

float mrpt::obs::CObservation2DRangeScan::maxRange

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

Definition at line 83 of file obs/CObservation2DRangeScan.h.

Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().

bool mrpt::obs::CObservation2DRangeScan::rightToLeft

The scanning direction: true=counterclockwise; false=clockwise.

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

Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().

mrpt::utils::ContainerReadOnlyProxyAccessor<std::vector<float> > mrpt::obs::CObservation2DRangeScan::scan

The range values of the scan, in meters. Must have same length than validRange.

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

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::decimateLaserScan(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().

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.

mrpt::poses::CPose3D mrpt::obs::CObservation2DRangeScan::sensorPose
float mrpt::obs::CObservation2DRangeScan::stdError

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

Definition at line 85 of file obs/CObservation2DRangeScan.h.

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.

mrpt::utils::ContainerReadOnlyProxyAccessor<std::vector<char> > mrpt::obs::CObservation2DRangeScan::validRange

It's false (=0) on no reflected rays, referenced to elements in scan.

Definition at line 77 of file obs/CObservation2DRangeScan.h.

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::decimateLaserScan(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().




Page generated by Doxygen 1.8.6 for MRPT 1.5.3 Git: c178c63 Mon Aug 14 15:49:58 2017 +0200 at dom ago 20 03:04:12 CEST 2017