Class CObservation2DRangeScan
Defined in File CObservation2DRangeScan.h
Inheritance Relationships
Base Type
public mrpt::obs::CObservation(Class CObservation)
Class Documentation
-
class CObservation2DRangeScan : public mrpt::obs::CObservation
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:
Scan ranges: A vector of float values with all the range measurements [meters]. Access via
CObservation2DRangeScan::getScanRange()andCObservation2DRangeScan::setScanRange().Range validity: A vector (of identical size to scan
Scan data
-
float aperture = {M_PIf}
The “aperture” or field-of-view of the range finder, in radians (typically M_PI = 180 degrees).
-
bool rightToLeft = {true}
The scanning direction: true=counterclockwise; false=clockwise
-
float maxRange = {80.0f}
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 = {0.01f}
The “sigma” error of the device in meters, used while inserting the scan in an occupancy grid.
-
float beamAperture = {0}
The aperture of each beam, in radians, used to insert “thick” rays in the occupancy grid.
-
double deltaPitch = {0}
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).
-
float sweepDuration = {.0f}
Time that takes one LIDAR rotation (in seconds). 0=means, not available. This is used to compute per-point timestamps
-
void resizeScan(size_t len)
Resizes all data vectors to allocate a given number of scan rays
-
void resizeScanAndAssign(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.
-
size_t getScanSize() const
Get number of scan rays
-
const float &getScanRange(size_t i) const
The range values of the scan, in meters. Must have same length than validRange
-
float &getScanRange(size_t i)
-
void setScanRange(size_t i, const float val)
-
const int32_t &getScanIntensity(size_t i) const
The intensity values of the scan. If available, must have same length than validRange
-
int32_t &getScanIntensity(size_t i)
-
void setScanIntensity(size_t i, const int val)
-
bool getScanRangeValidity(size_t i) const
It’s false (=0) on no reflected rays, referenced to elements in scan
-
void setScanRangeValidity(size_t i, const bool val)
-
float getScanRelativeTimestamp(size_t idx) const
-
float getScanAngle(size_t idx) const
Returns the computed direction (relative heading in radians, with 0=forward) of the given ray index, following the following formula:
float Ang = -0.5f * aperture; float dA = aperture / (m_scan.size() - 1); if (!rightToLeft) { Ang = -Ang; dA = -dA; } return Ang + dA * idx;\params[in] idx Index of the ray, from
0tosize()-1.Note
(New in MRPT 2.3.1)
-
void getScanProperties(T2DScanProperties &p) const
Fill out a T2DScanProperties structure with the parameters of this scan
Cached points map
-
mutable mrpt::containers::NonCopiableData<std::recursive_mutex> m_cachedMapMtx
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.
-
mutable mrpt::maps::CMetricMap::Ptr m_cachedMap
-
template<class POINTSMAP>
inline const POINTSMAP *getAuxPointsMap() const Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or nullptr otherwise. Usage:
mrpt::maps::CPointsMap *map = obs->getAuxPointsMap<mrpt::maps::CPointsMap>();
See also
-
template<class POINTSMAP>
inline const POINTSMAP *buildAuxPointsMap(const void *options = nullptr) const Returns a cached points map representing this laser scan, building it upon the first call.
See also
- Parameters:
options – Can be nullptr 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 nullptr);
-
void internal_buildAuxPointsMap(const void *options = nullptr) const
Internal method, used from buildAuxPointsMap()
Public Types
Public Functions
-
CObservation2DRangeScan() = default
Default constructor
-
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).
-
bool hasIntensity() const
Return true if scan has intensity
-
void setScanHasIntensity(bool setHasIntensityFlag)
Marks this scan as having or not intensity data.
-
inline virtual void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
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
-
inline virtual void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
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
-
virtual void getDescriptionAsText(std::ostream &o) const override
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.
Note
This is the text that appears in RawLogViewer when selecting an object in the dataset
-
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 minimum 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”).
See also
C2DRangeFinderAbstract::loadExclusionAreas
-
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.
See also
C2DRangeFinderAbstract::loadExclusionAreas
-
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>.
See also
C2DRangeFinderAbstract::loadExclusionAreas
-
inline virtual bool exportTxtSupported() const override
Must return true if the class is exportable to TXT/CSV files, in which case the other virtual methods in this group must be redefined too.
-
virtual std::string exportTxtHeader() const override
Returns the description of the data columns. Timestamp is automatically included as the first column, do not list it. See example implementations if interested in enabling this in custom CObservation classes. Do not include newlines.
-
virtual std::string exportTxtDataRow() const override
Returns one row of data with the data stored in this particular object. Do not include newlines.