class mrpt::obs::CObservation2DRangeScan
Overview
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), it holds
true
for those ranges than are valid (i.e. will be zero for non-reflected rays, etc.),false
for scan rays without a valid lidar return.Reflection intensity: A vector (of identical size to scan ) a unitless int values representing the relative strength of each return. Higher values indicate a more intense return. This is useful for filtering out low intensity (noisy) returns or detecting intense landmarks.
CObservation2DRangeScan::aperture : The field-of-view of the scanner, in radians (typically, M_PI = 180deg).
CObservation2DRangeScan::sensorPose : The 6D location of the sensor on the robot reference frame (default=at the origin), i.e. wrt
base_link
following ROS conventions.CObservation2DRangeScan::rightToLeft : The scanning direction: true=counterclockwise (default), false=clockwise.
Note that the angle of each range in the vectors above is implicitly defined by the index within the vector.
See also:
CObservation, CPointsMap, T2DScanProperties
#include <mrpt/obs/CObservation2DRangeScan.h> class CObservation2DRangeScan: public mrpt::obs::CObservation { public: // typedefs typedef std::vector<mrpt::math::CPolygon> TListExclusionAreas; typedef std::vector<std::pair<mrpt::math::CPolygon, std::pair<double, double>>> TListExclusionAreasWithRanges; // fields float aperture {M_PIf}; bool rightToLeft {true}; float maxRange {80.0f}; mrpt::poses::CPose3D sensorPose; float stdError {0.01f}; float beamAperture {0}; double deltaPitch {0}; // construction CObservation2DRangeScan(); // methods void resizeScan(size_t len); void resizeScanAndAssign( size_t len, const float rangeVal, const bool rangeValidity, const int32_t rangeIntensity = 0 ); size_t getScanSize() const; const float& getScanRange(size_t i) const; float& getScanRange(size_t i); void setScanRange( size_t i, const float val ); const int32_t& getScanIntensity(size_t i) const; int32_t& getScanIntensity(size_t i); void setScanIntensity( size_t i, const int val ); bool getScanRangeValidity(size_t i) const; void setScanRangeValidity( size_t i, const bool val ); float getScanAngle(size_t idx) const; void getScanProperties(T2DScanProperties& p) const; template <class POINTSMAP> const POINTSMAP* getAuxPointsMap() const; template <class POINTSMAP> const POINTSMAP* buildAuxPointsMap(const void* options = nullptr) const; void loadFromVectors( size_t nRays, const float* scanRanges, const char* scanValidity ); bool isPlanarScan(const double tolerance = 0) const; bool hasIntensity() const; void setScanHasIntensity(bool setHasIntensityFlag); virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const; virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose); virtual void getDescriptionAsText(std::ostream& o) const; void truncateByDistanceAndAngle( float min_distance, float max_angle, float min_height = 0, float max_height = 0, float h = 0 ); void filterByExclusionAreas(const TListExclusionAreas& areas); void filterByExclusionAreas(const TListExclusionAreasWithRanges& areas); void filterByExclusionAngles(const std::vector<std::pair<double, double>>& angles); virtual bool exportTxtSupported() const; virtual std::string exportTxtHeader() const; virtual std::string exportTxtDataRow() const; };
Inherited Members
public: // fields mrpt::system::TTimeStamp timestamp {mrpt::Clock::now()}; std::string sensorLabel; // methods mrpt::system::TTimeStamp getTimeStamp() const; virtual mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const; void load() const; virtual void unload() const; virtual bool exportTxtSupported() const; virtual std::string exportTxtHeader() const; virtual std::string exportTxtDataRow() const; template <class METRICMAP> bool insertObservationInto( METRICMAP& theMap, const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt ) const; virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const = 0; void getSensorPose(mrpt::math::TPose3D& out_sensorPose) const; mrpt::math::TPose3D sensorPose() const; virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose) = 0; void setSensorPose(const mrpt::math::TPose3D& newSensorPose); virtual void getDescriptionAsText(std::ostream& o) const; virtual std::string asString() const;
Typedefs
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.
Fields
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).
Construction
CObservation2DRangeScan()
Default constructor.
Methods
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
const int32_t& getScanIntensity(size_t i) const
The intensity values of the scan.
If available, must have same length than validRange
bool getScanRangeValidity(size_t i) const
It’s false (=0) on no reflected rays, referenced to elements in scan.
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 0
to size()-1
.
(New in MRPT 2.3.1)
void getScanProperties(T2DScanProperties& p) const
Fill out a T2DScanProperties structure with the parameters of this scan.
template <class POINTSMAP> 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> const POINTSMAP* buildAuxPointsMap(const void* options = nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call.
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); |
See also:
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.
virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const
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:
virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose)
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
Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
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
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
virtual bool exportTxtSupported() const
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
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
Returns one row of data with the data stored in this particular object.
Do not include newlines.