Main MRPT website > C++ reference for MRPT 1.4.0
List of all members | Public Types | Public Member Functions | Protected Member Functions
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 40 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::CPolygonTListExclusionAreas
 Used in filterByExclusionAreas.
 
typedef std::vector< std::pair< mrpt::math::CPolygon, std::pair< double, double > > > TListExclusionAreasWithRanges
 Used in filterByExclusionAreas.
 

Public Member Functions

 CObservation2DRangeScan ()
 Default constructor.
 
virtual ~CObservation2DRangeScan ()
 Destructor.
 
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).
 
void getSensorPose (mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
 A general method to retrieve the sensor pose on the robot.
 
void setSensorPose (const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
 A general method to change the sensor pose on the robot.
 
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.
 
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).
 
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").
 
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.
 
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>.
 
template<class METRICMAP >
bool insertObservationInto (METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose=NULL) const
 This method is equivalent to:
 
void getSensorPose (mrpt::math::TPose3D &out_sensorPose) const
 A general method to retrieve the sensor pose on the robot.
 
void setSensorPose (const mrpt::math::TPose3D &newSensorPose)
 A general method to change the sensor pose on the robot.
 
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.
 
virtual void unload ()
 Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).
 

Static Public Attributes

RTTI stuff <br>
static const mrpt::utils::TRuntimeClassId classCObservation
 

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.
 
CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const MRPT_OVERRIDE
 
void readFromStream (mrpt::utils::CStream &in, int version) MRPT_OVERRIDE
 

RTTI stuff <br>

typedef CObservation2DRangeScanPtr SmartPtr
 
static mrpt::utils::CLASSINIT _init_CObservation2DRangeScan
 
static mrpt::utils::TRuntimeClassId classCObservation2DRangeScan
 
static const mrpt::utils::TRuntimeClassIdclassinfo
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const MRPT_OVERRIDE
 
virtual mrpt::utils::CObjectduplicate () const MRPT_OVERRIDE
 
static mrpt::utils::CObjectCreateObject ()
 
static CObservation2DRangeScanPtr Create ()
 

Scan data

std::vector< float > scan
 The range values of the scan, in meters. Must have same length than validRange.
 
std::vector< char > validRange
 It's false (=0) on no reflected rays, referenced to elements in scan.
 
float aperture
 The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees).
 
bool rightToLeft
 The scanning direction: true=counterclockwise; false=clockwise.
 
float maxRange
 The maximum range allowed by the device, in meters (e.g. 80m, 50m,...)
 
mrpt::poses::CPose3D sensorPose
 The 6D pose of the sensor on the robot at the moment of starting the scan.
 
float stdError
 The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
 
float beamAperture
 The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid.
 
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).
 
void getScanProperties (T2DScanProperties &p) const
 Fill out a T2DScanProperties structure with the parameters of this scan.
 

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.
 
std::string sensorLabel
 An arbitrary label that can be used to identify the sensor.
 
mrpt::system::TTimeStamp getTimeStamp () const
 Returns CObservation::timestamp for all kind of observations.
 
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.
 

Cached points map


mrpt::maps::CMetricMapPtr m_cachedMap
 A points map, build only under demand by the methods getAuxPointsMap() and buildAuxPointsMap().
 
template<class POINTSMAP >
const POINTSMAP * getAuxPointsMap () const
 Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or NULL otherwise.
 
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.
 
void internal_buildAuxPointsMap (const void *options=NULL) const
 Internal method, used from buildAuxPointsMap()
 

Member Typedef Documentation

◆ SmartPtr

A typedef for the associated smart pointer

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

◆ TListExclusionAreas

Used in filterByExclusionAreas.

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

◆ TListExclusionAreasWithRanges

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

Used in filterByExclusionAreas.

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

Constructor & Destructor Documentation

◆ CObservation2DRangeScan()

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

Default constructor.

◆ ~CObservation2DRangeScan()

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

Destructor.

Member Function Documentation

◆ _GetBaseClass()

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

◆ buildAuxPointsMap()

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);
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors.
See also
getAuxPointsMap

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

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

◆ Create()

static CObservation2DRangeScanPtr mrpt::obs::CObservation2DRangeScan::Create ( )
static

◆ CreateObject()

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

◆ duplicate()

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

◆ filterByExclusionAngles()

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

◆ filterByExclusionAreas() [1/2]

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

◆ filterByExclusionAreas() [2/2]

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

◆ getAuxPointsMap()

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 93 of file obs/CObservation2DRangeScan.h.

◆ getDescriptionAsText()

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.

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

◆ GetRuntimeClass()

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

Reimplemented from mrpt::obs::CObservation.

◆ getScanProperties()

void mrpt::obs::CObservation2DRangeScan::getScanProperties ( T2DScanProperties p) const

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

◆ getSensorPose() [1/2]

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

◆ getSensorPose() [2/2]

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 120 of file obs/CObservation2DRangeScan.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 63 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 also
CMetricMap, CMetricMap::insertObservation

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

◆ internal_buildAuxPointsMap()

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

Internal method, used from buildAuxPointsMap()

◆ isPlanarScan()

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

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

◆ readFromStream()

void mrpt::obs::CObservation2DRangeScan::readFromStream ( mrpt::utils::CStream in,
int  version 
)
protected

◆ setSensorPose() [1/2]

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

◆ setSensorPose() [2/2]

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 121 of file obs/CObservation2DRangeScan.h.

◆ swap()

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.

◆ truncateByDistanceAndAngle()

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

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

◆ writeToStream()

void mrpt::obs::CObservation2DRangeScan::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
protected

Member Data Documentation

◆ _init_CObservation2DRangeScan

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

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

◆ aperture

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 62 of file obs/CObservation2DRangeScan.h.

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

◆ beamAperture

float mrpt::obs::CObservation2DRangeScan::beamAperture

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

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

◆ classCObservation

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

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

◆ classCObservation2DRangeScan

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

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

◆ classinfo

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

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

◆ deltaPitch

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 68 of file obs/CObservation2DRangeScan.h.

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

◆ m_cachedMap

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 79 of file obs/CObservation2DRangeScan.h.

◆ maxRange

float mrpt::obs::CObservation2DRangeScan::maxRange

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

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

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

◆ rightToLeft

bool mrpt::obs::CObservation2DRangeScan::rightToLeft

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

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

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

◆ scan

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

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

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

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

◆ sensorLabel

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

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

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

◆ sensorPose

mrpt::poses::CPose3D mrpt::obs::CObservation2DRangeScan::sensorPose

◆ stdError

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 66 of file obs/CObservation2DRangeScan.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 59 of file obs/CObservation.h.

◆ validRange

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

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

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

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




Page generated by Doxygen 1.9.8 for MRPT 1.4.0 SVN: at Thu Dec 14 16:41:50 UTC 2023