Main MRPT website > C++ reference for MRPT 1.9.9
CObservation2DRangeScan.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #ifndef CObservation2DRangeScan_H
10 #define CObservation2DRangeScan_H
11 
13 #include <mrpt/obs/CObservation.h>
15 #include <mrpt/poses/CPose3D.h>
16 #include <mrpt/maps/CMetricMap.h>
17 #include <mrpt/math/CPolygon.h>
19 
20 // Add for declaration of mexplus::from template specialization
22 
23 namespace mrpt
24 {
25 namespace obs
26 {
27 /** A "CObservation"-derived class that represents a 2D range scan measurement
28  * (typically from a laser scanner).
29  * The data structures are generic enough to hold a wide variety of 2D
30  * scanners and "3D" planar rotating 2D lasers.
31  *
32  * These are the most important data fields:
33  * - These three fields are private data member (since MRPT 1.5.0) for
34  * safety and to ensure data consistency. Read them with the
35  * backwards-compatible proxies `scan`, `intensity`, `validRange` or (preferred)
36  * with the new `get_*`, `set_*` and `resize()` methods:
37  * - CObservation2DRangeScan::scan -> A vector of float values with all
38  * the range measurements (in meters).
39  * - CObservation2DRangeScan::validRange -> A vector (of <b>identical
40  * size</b> to <i>scan<i>), has non-zeros for those ranges than are valid (i.e.
41  * will be zero for non-reflected rays, etc.)
42  * - CObservation2DRangeScan::intensity -> A vector (of <b>identical
43  * size</b> to <i>scan<i>) a unitless int values representing the relative
44  * strength of each return. Higher values indicate a more intense return. This
45  * is useful for filtering out low intensity(noisy) returns or detecting intense
46  * landmarks.
47  * - CObservation2DRangeScan::aperture -> The field-of-view of the scanner,
48  * in radians (typically, M_PI = 180deg).
49  * - CObservation2DRangeScan::sensorPose -> The 6D location of the sensor on
50  * the robot reference frame (default=at the origin).
51  *
52  * \sa CObservation, CPointsMap, T2DScanProperties
53  * \ingroup mrpt_obs_grp
54  */
56 {
58  // This must be added for declaration of MEX-related functions
60  private:
61  /** The range values of the scan, in meters. Must have same length than \a
62  * validRange */
63  std::vector<float> m_scan;
64  /** The intensity values of the scan. If available, must have same length
65  * than \a validRange */
66  std::vector<int32_t> m_intensity;
67  /** It's false (=0) on no reflected rays, referenced to elements in \a scan
68  */
69  std::vector<char> m_validRange;
70  /** Whether the intensity values are present or not. If not, space is saved
71  * during serialization. */
73 
74  public:
75  /** Used in filterByExclusionAreas */
76  typedef std::vector<mrpt::math::CPolygon> TListExclusionAreas;
77  /** Used in filterByExclusionAreas */
78  typedef std::vector<
79  std::pair<mrpt::math::CPolygon, std::pair<double, double>>>
81 
82  /** Default constructor */
84  /** copy ctor */
86  /** Destructor */
87  virtual ~CObservation2DRangeScan();
88 
89  /** @name Scan data
90  @{ */
91  /** Resizes all data vectors to allocate a given number of scan rays */
92  void resizeScan(const size_t len);
93  /** Resizes all data vectors to allocate a given number of scan rays and
94  * assign default values. */
96  const size_t len, const float rangeVal, const bool rangeValidity,
97  const int32_t rangeIntensity = 0);
98  /** Get number of scan rays */
99  size_t getScanSize() const;
100 
101  /** The range values of the scan, in meters. Must have same length than \a
102  * validRange */
104  float getScanRange(const size_t i) const;
105  void setScanRange(const size_t i, const float val);
106 
107  /** The intensity values of the scan. If available, must have same length
108  * than \a validRange */
110  int32_t getScanIntensity(const size_t i) const;
111  void setScanIntensity(const size_t i, const int val);
112 
113  /** It's false (=0) on no reflected rays, referenced to elements in \a scan
114  */
116  bool getScanRangeValidity(const size_t i) const;
117  void setScanRangeValidity(const size_t i, const bool val);
118 
119  /** The "aperture" or field-of-view of the range finder, in radians
120  * (typically M_PI = 180 degrees). */
121  float aperture;
122  /** The scanning direction: true=counterclockwise; false=clockwise */
124  /** The maximum range allowed by the device, in meters (e.g. 80m, 50m,...)
125  */
126  float maxRange;
127  /** The 6D pose of the sensor on the robot at the moment of starting the
128  * scan. */
130  /** The "sigma" error of the device in meters, used while inserting the scan
131  * in an occupancy grid. */
132  float stdError;
133  /** The aperture of each beam, in radians, used to insert "thick" rays in
134  * the occupancy grid. */
136  /** If the laser gathers data by sweeping in the pitch/elevation angle, this
137  * holds the increment in "pitch" (=-"elevation") between the beginning and
138  * the end of the scan (the sensorPose member stands for the pose at the
139  * beginning of the scan). */
140  double deltaPitch;
141 
142  /** Fill out a T2DScanProperties structure with the parameters of this scan
143  */
145  /** @} */
146 
147  void loadFromVectors(
148  size_t nRays, const float* scanRanges, const char* scanValidity);
149 
150  /** @name Cached points map
151  @{ */
152  protected:
153  /** A points map, build only under demand by the methods getAuxPointsMap()
154  * and buildAuxPointsMap().
155  * It's a generic smart pointer to avoid depending here in the library
156  * mrpt-obs on classes on other libraries.
157  */
159  /** Internal method, used from buildAuxPointsMap() */
160  void internal_buildAuxPointsMap(const void* options = nullptr) const;
161 
162  public:
163  /** Returns the cached points map representation of the scan, if already
164  * build with buildAuxPointsMap(), or nullptr otherwise.
165  * Usage:
166  * \code
167  * mrpt::maps::CPointsMap *map =
168  * obs->getAuxPointsMap<mrpt::maps::CPointsMap>();
169  * \endcode
170  * \sa buildAuxPointsMap
171  */
172  template <class POINTSMAP>
173  inline const POINTSMAP* getAuxPointsMap() const
174  {
175  return static_cast<const POINTSMAP*>(m_cachedMap.get());
176  }
177 
178  /** Returns a cached points map representing this laser scan, building it
179  * upon the first call.
180  * \param options Can be nullptr to use default point maps' insertion
181  * options, or a pointer to a "CPointsMap::TInsertionOptions" structure to
182  * override some params.
183  * Usage:
184  * \code
185  * mrpt::maps::CPointsMap *map =
186  * obs->buildAuxPointsMap<mrpt::maps::CPointsMap>(&options or nullptr);
187  * \endcode
188  * \sa getAuxPointsMap
189  */
190  template <class POINTSMAP>
191  inline const POINTSMAP* buildAuxPointsMap(
192  const void* options = nullptr) const
193  {
195  return static_cast<const POINTSMAP*>(m_cachedMap.get());
196  }
197 
198  /** @} */
199 
200  /** Return true if the laser scanner is "horizontal", so it has an absolute
201  * value of "pitch" and "roll" less or equal to the given tolerance (in
202  * rads, default=0) (with the normal vector either upwards or downwards).
203  */
204  bool isPlanarScan(const double tolerance = 0) const;
205 
206  /** Return true if scan has intensity */
207  bool hasIntensity() const;
208  /** Marks this scan as having or not intensity data. */
209  void setScanHasIntensity(bool setHasIntensityFlag);
210 
211  // See base class docs
212  void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const override
213  {
214  out_sensorPose = sensorPose;
215  }
216  void setSensorPose(const mrpt::poses::CPose3D& newSensorPose) override
217  {
218  sensorPose = newSensorPose;
219  }
220  void getDescriptionAsText(std::ostream& o) const override;
221 
222  /** A general method to truncate the scan by defining a minimum valid
223  distance and a maximum valid angle as well as minimun and maximum heights
224  (NOTE: the laser z-coordinate must be provided).
225  */
227  float min_distance, float max_angle, float min_height = 0,
228  float max_height = 0, float h = 0);
229 
230  /** Mark as invalid sensed points that fall within any of a set of
231  * "exclusion areas", given in coordinates relative to the vehicle (taking
232  * into account "sensorPose").
233  * \sa C2DRangeFinderAbstract::loadExclusionAreas
234  */
235  void filterByExclusionAreas(const TListExclusionAreas& areas);
236 
237  /** Mark as invalid sensed points that fall within any of a set of
238  * "exclusion areas", given in coordinates relative to the vehicle (taking
239  * into account "sensorPose"), AND such as the Z coordinate of the point
240  * falls in the range [min,max] associated to each exclusion polygon.
241  * \sa C2DRangeFinderAbstract::loadExclusionAreas
242  */
244 
245  /** Mark as invalid the ranges in any of a given set of "forbiden angle
246  * ranges", given as pairs<min_angle,max_angle>.
247  * \sa C2DRangeFinderAbstract::loadExclusionAreas
248  */
250  const std::vector<std::pair<double, double>>& angles);
251 
252 }; // End of class def.
253 
254 } // End of namespace
255 namespace utils
256 {
257 // Specialization must occur in the same namespace
258 MRPT_DECLARE_TTYPENAME_PTR_NAMESPACE(CObservation2DRangeScan, ::mrpt::obs)
259 }
260 
261 } // End of namespace
262 
263 #endif
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...
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
float beamAperture
The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid...
const POINTSMAP * buildAuxPointsMap(const void *options=nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call...
void getScanProperties(T2DScanProperties &p) const
Fill out a T2DScanProperties structure with the parameters of this scan.
void setScanRange(const size_t i, const float val)
#define DECLARE_MEXPLUS_FROM(complete_type)
This must be inserted if a custom conversion method for MEX API is implemented in the class...
void setScanHasIntensity(bool setHasIntensityFlag)
Marks this scan as having or not intensity data.
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
int32_t getScanIntensity(const size_t i) const
GLenum GLsizei len
Definition: glext.h:4712
size_t getScanSize() const
Get number of scan rays.
std::vector< char > m_validRange
It&#39;s false (=0) on no reflected rays, referenced to elements in scan.
float maxRange
The maximum range allowed by the device, in meters (e.g.
std::shared_ptr< CMetricMap > Ptr
Definition: CMetricMap.h:58
mrpt::maps::CMetricMap::Ptr m_cachedMap
A points map, build only under demand by the methods getAuxPointsMap() and buildAuxPointsMap().
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" l...
Auxiliary struct that holds all the relevant geometry information about a 2D scan.
void internal_buildAuxPointsMap(const void *options=nullptr) const
Internal method, used from buildAuxPointsMap()
#define DECLARE_MEX_CONVERSION
This must be inserted if a custom conversion method for MEX API is implemented in the class...
void setScanIntensity(const size_t i, const int val)
std::vector< int32_t > m_intensity
The intensity values of the scan.
This namespace contains representation of robot actions and observations.
int val
Definition: mrpt_jpeglib.h:955
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< char > > validRange
It&#39;s false (=0) on no reflected rays, referenced to elements in scan.
bool m_has_intensity
Whether the intensity values are present or not.
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< int32_t > > intensity
The intensity values of the scan.
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...
#define MRPT_DECLARE_TTYPENAME_PTR_NAMESPACE(_TYPE, __NS)
Definition: TTypeName.h:93
std::vector< mrpt::math::CPolygon > TListExclusionAreas
Used in filterByExclusionAreas.
__int32 int32_t
Definition: rptypes.h:46
A generic proxy accessor template that only allows read-only access to the original binded STL contai...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve 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 ...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
std::vector< std::pair< mrpt::math::CPolygon, std::pair< double, double > > > TListExclusionAreasWithRanges
Used in filterByExclusionAreas.
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:41
void resizeScan(const size_t len)
Resizes all data vectors to allocate a given number of scan rays.
double deltaPitch
If the laser gathers data by sweeping in the pitch/elevation angle, this holds the increment in "pitc...
const POINTSMAP * getAuxPointsMap() const
Returns the cached points map representation of the scan, if already build with buildAuxPointsMap(), or nullptr otherwise.
float aperture
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees)...
std::vector< float > m_scan
The range values of the scan, in meters.
void loadFromVectors(size_t nRays, const float *scanRanges, const char *scanValidity)
bool hasIntensity() const
Return true if scan has intensity.
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< float > > scan
The range values of the scan, in meters.
void filterByExclusionAreas(const TListExclusionAreas &areas)
Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinate...
GLfloat GLfloat p
Definition: glext.h:6305
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
bool rightToLeft
The scanning direction: true=counterclockwise; false=clockwise.
void setScanRangeValidity(const size_t i, const bool val)
bool getScanRangeValidity(const size_t i) const



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019