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:
Definition at line 59 of file CObservation2DRangeScan.h.
#include <mrpt/slam/CObservation2DRangeScan.h>
Public Types | |
typedef std::vector < mrpt::math::CPolygon > | TListExclusionAreas |
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 (CPose3D &out_sensorPose) const |
A general method to retrieve the sensor pose on the robot. | |
void | setSensorPose (const CPose3D &newSensorPose) |
A general method to change the sensor pose on the robot. | |
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>. | |
Public Attributes | |
Scan data | |
std::vector< float > | scan |
The range values of the scan, in meters. | |
std::vector< char > | validRange |
It's false (=0) on no reflected rays, referenced to elements in "scan" (Added in the streamming version #1 of the class) | |
float | aperture |
The aperture of the range finder, in radians (typically M_PI = 180 degrees). | |
bool | rightToLeft |
The scanning direction. | |
float | maxRange |
The maximum range allowed by the device, in meters (e.g. | |
CPose3D | sensorPose |
The 6D pose of the sensor on the robot. | |
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). | |
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. | |
virtual mrpt::utils::CObject * | duplicate () const |
Returns a copy of the object, indepently of its class. | |
static mrpt::utils::CObject * | CreateObject () |
static CObservation2DRangeScanPtr | Create () |
Cached points map | |
mrpt::slam::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() |
A typedef for the associated smart pointer
Definition at line 62 of file CObservation2DRangeScan.h.
typedef std::vector<mrpt::math::CPolygon> mrpt::slam::CObservation2DRangeScan::TListExclusionAreas |
Used in filterByExclusionAreas.
Definition at line 65 of file CObservation2DRangeScan.h.
typedef std::vector<std::pair<mrpt::math::CPolygon,std::pair<double,double> > > mrpt::slam::CObservation2DRangeScan::TListExclusionAreasWithRanges |
Used in filterByExclusionAreas.
Definition at line 66 of file CObservation2DRangeScan.h.
mrpt::slam::CObservation2DRangeScan::CObservation2DRangeScan | ( | ) |
Default constructor.
virtual mrpt::slam::CObservation2DRangeScan::~CObservation2DRangeScan | ( | ) | [virtual] |
Destructor.
static const mrpt::utils::TRuntimeClassId* mrpt::slam::CObservation2DRangeScan::_GetBaseClass | ( | ) | [static, protected] |
Reimplemented from mrpt::slam::CObservation.
const POINTSMAP* mrpt::slam::CObservation2DRangeScan::buildAuxPointsMap | ( | const void * | options = NULL | ) | const [inline] |
Returns a cached points map representing this laser scan, building it upon the first call.
options | Can be NULL to use default point maps' insertion options, or a pointer to a "CPointsMap::TInsertionOptions" structure to override some params. Usage:
mrpt::slam::CPointsMap *map = obs->buildAuxPointsMap<mrpt::slam::CPointsMap>(&options or NULL); |
Definition at line 153 of file CObservation2DRangeScan.h.
static CObservation2DRangeScanPtr mrpt::slam::CObservation2DRangeScan::Create | ( | ) | [static] |
static mrpt::utils::CObject* mrpt::slam::CObservation2DRangeScan::CreateObject | ( | ) | [static] |
virtual mrpt::utils::CObject* mrpt::slam::CObservation2DRangeScan::duplicate | ( | ) | const [virtual] |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
void mrpt::slam::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>.
void mrpt::slam::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.
void mrpt::slam::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").
const POINTSMAP* mrpt::slam::CObservation2DRangeScan::getAuxPointsMap | ( | ) | const [inline] |
Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or NULL otherwise.
Usage:
mrpt::slam::CPointsMap *map = obs->getAuxPointsMap<mrpt::slam::CPointsMap>();
Definition at line 140 of file CObservation2DRangeScan.h.
virtual const mrpt::utils::TRuntimeClassId* mrpt::slam::CObservation2DRangeScan::GetRuntimeClass | ( | ) | const [virtual] |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::slam::CObservation.
void mrpt::slam::CObservation2DRangeScan::getSensorPose | ( | CPose3D & | out_sensorPose | ) | const [inline, virtual] |
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.
Implements mrpt::slam::CObservation.
Definition at line 170 of file CObservation2DRangeScan.h.
void mrpt::slam::CObservation2DRangeScan::internal_buildAuxPointsMap | ( | const void * | options = NULL | ) | const [protected] |
Internal method, used from buildAuxPointsMap()
bool mrpt::slam::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).
void mrpt::slam::CObservation2DRangeScan::setSensorPose | ( | const CPose3D & | newSensorPose | ) | [inline, virtual] |
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.
Implements mrpt::slam::CObservation.
Definition at line 177 of file CObservation2DRangeScan.h.
void mrpt::slam::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).
mrpt::utils::CLASSINIT mrpt::slam::CObservation2DRangeScan::_init_CObservation2DRangeScan [static, protected] |
Definition at line 62 of file CObservation2DRangeScan.h.
The aperture of the range finder, in radians (typically M_PI = 180 degrees).
Definition at line 89 of file CObservation2DRangeScan.h.
Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().
The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid.
(Added in the streamming version #4 of the class)
Definition at line 110 of file CObservation2DRangeScan.h.
mrpt::utils::TRuntimeClassId mrpt::slam::CObservation2DRangeScan::classCObservation2DRangeScan [static] |
Definition at line 62 of file CObservation2DRangeScan.h.
Definition at line 62 of file CObservation2DRangeScan.h.
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 114 of file CObservation2DRangeScan.h.
Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().
mrpt::slam::CMetricMapPtr mrpt::slam::CObservation2DRangeScan::m_cachedMap [mutable, protected] |
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 126 of file CObservation2DRangeScan.h.
The maximum range allowed by the device, in meters (e.g.
80m, 50m,...)
Definition at line 97 of file CObservation2DRangeScan.h.
Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().
The scanning direction.
Definition at line 93 of file CObservation2DRangeScan.h.
Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().
std::vector<float> mrpt::slam::CObservation2DRangeScan::scan |
The range values of the scan, in meters.
Definition at line 80 of file CObservation2DRangeScan.h.
Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().
The 6D pose of the sensor on the robot.
Definition at line 101 of file CObservation2DRangeScan.h.
Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
Definition at line 105 of file CObservation2DRangeScan.h.
std::vector<char> mrpt::slam::CObservation2DRangeScan::validRange |
It's false (=0) on no reflected rays, referenced to elements in "scan" (Added in the streamming version #1 of the class)
Definition at line 85 of file CObservation2DRangeScan.h.
Referenced by mrpt::opengl::CAngularObservationMesh::FTrace2D< T >::operator()(), and mrpt::opengl::CAngularObservationMesh::trace1DSetOfRays().
Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN: at Sat Mar 26 06:16:28 UTC 2011 |