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-2018, 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>
20 
21 // Add for declaration of mexplus::from template specialization
23 
24 namespace mrpt
25 {
26 namespace obs
27 {
28 /** A "CObservation"-derived class that represents a 2D range scan measurement
29  * (typically from a laser scanner).
30  * The data structures are generic enough to hold a wide variety of 2D
31  * scanners and "3D" planar rotating 2D lasers.
32  *
33  * These are the most important data fields:
34  * - These three fields are private data member (since MRPT 1.5.0) for
35  * safety and to ensure data consistency. Read them with the
36  * backwards-compatible proxies `scan`, `intensity`, `validRange` or (preferred)
37  * with the new `get_*`, `set_*` and `resize()` methods:
38  * - CObservation2DRangeScan::scan -> A vector of float values with all
39  * the range measurements (in meters).
40  * - CObservation2DRangeScan::validRange -> A vector (of <b>identical
41  * size</b> to <i>scan<i>), has non-zeros for those ranges than are valid (i.e.
42  * will be zero for non-reflected rays, etc.)
43  * - CObservation2DRangeScan::intensity -> A vector (of <b>identical
44  * size</b> to <i>scan<i>) a unitless int values representing the relative
45  * strength of each return. Higher values indicate a more intense return. This
46  * is useful for filtering out low intensity(noisy) returns or detecting intense
47  * landmarks.
48  * - CObservation2DRangeScan::aperture -> The field-of-view of the scanner,
49  * in radians (typically, M_PI = 180deg).
50  * - CObservation2DRangeScan::sensorPose -> The 6D location of the sensor on
51  * the robot reference frame (default=at the origin).
52  *
53  * \sa CObservation, CPointsMap, T2DScanProperties
54  * \ingroup mrpt_obs_grp
55  */
57 {
59  // This must be added for declaration of MEX-related functions
61  private:
62  /** The range values of the scan, in meters. Must have same length than \a
63  * validRange */
65  /** The intensity values of the scan. If available, must have same length
66  * than \a validRange */
68  /** It's false (=0) on no reflected rays, referenced to elements in \a scan
69  */
71  /** Whether the intensity values are present or not. If not, space is saved
72  * during serialization. */
73  bool m_has_intensity{false};
74 
75  public:
76  /** Used in filterByExclusionAreas */
77  using TListExclusionAreas = std::vector<mrpt::math::CPolygon>;
78  /** Used in filterByExclusionAreas */
80  std::vector<std::pair<mrpt::math::CPolygon, std::pair<double, double>>>;
81 
82  /** Default constructor */
83  CObservation2DRangeScan() = default;
84  /** copy ctor */
86 
87  /** @name Scan data
88  @{ */
89  /** Resizes all data vectors to allocate a given number of scan rays */
90  void resizeScan(const size_t len);
91  /** Resizes all data vectors to allocate a given number of scan rays and
92  * assign default values. */
94  const size_t len, const float rangeVal, const bool rangeValidity,
95  const int32_t rangeIntensity = 0);
96  /** Get number of scan rays */
97  size_t getScanSize() const;
98 
99  /** The range values of the scan, in meters. Must have same length than \a
100  * 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 */
112  int32_t getScanIntensity(const size_t i) const;
113  void setScanIntensity(const size_t i, const int val);
114 
115  /** It's false (=0) on no reflected rays, referenced to elements in \a scan
116  */
120  bool getScanRangeValidity(const size_t i) const;
121  void setScanRangeValidity(const size_t i, const bool val);
122 
123  /** The "aperture" or field-of-view of the range finder, in radians
124  * (typically M_PI = 180 degrees). */
125  float aperture{M_PIf};
126  /** The scanning direction: true=counterclockwise; false=clockwise */
127  bool rightToLeft{true};
128  /** The maximum range allowed by the device, in meters (e.g. 80m, 50m,...)
129  */
130  float maxRange{80.0f};
131  /** The 6D pose of the sensor on the robot at the moment of starting the
132  * scan. */
134  /** The "sigma" error of the device in meters, used while inserting the scan
135  * in an occupancy grid. */
136  float stdError{0.01f};
137  /** The aperture of each beam, in radians, used to insert "thick" rays in
138  * the occupancy grid. */
139  float beamAperture{0};
140  /** If the laser gathers data by sweeping in the pitch/elevation angle, this
141  * holds the increment in "pitch" (=-"elevation") between the beginning and
142  * the end of the scan (the sensorPose member stands for the pose at the
143  * beginning of the scan). */
144  double deltaPitch{0};
145 
146  /** Fill out a T2DScanProperties structure with the parameters of this scan
147  */
149  /** @} */
150 
151  void loadFromVectors(
152  size_t nRays, const float* scanRanges, const char* scanValidity);
153 
154  /** @name Cached points map
155  @{ */
156  protected:
157  /** A points map, build only under demand by the methods getAuxPointsMap()
158  * and buildAuxPointsMap().
159  * It's a generic smart pointer to avoid depending here in the library
160  * mrpt-obs on classes on other libraries.
161  */
163  /** Internal method, used from buildAuxPointsMap() */
164  void internal_buildAuxPointsMap(const void* options = nullptr) const;
165 
166  public:
167  /** Returns the cached points map representation of the scan, if already
168  * build with buildAuxPointsMap(), or nullptr otherwise.
169  * Usage:
170  * \code
171  * mrpt::maps::CPointsMap *map =
172  * obs->getAuxPointsMap<mrpt::maps::CPointsMap>();
173  * \endcode
174  * \sa buildAuxPointsMap
175  */
176  template <class POINTSMAP>
177  inline const POINTSMAP* getAuxPointsMap() const
178  {
179  return static_cast<const POINTSMAP*>(m_cachedMap.get());
180  }
181 
182  /** Returns a cached points map representing this laser scan, building it
183  * upon the first call.
184  * \param options Can be nullptr to use default point maps' insertion
185  * options, or a pointer to a "CPointsMap::TInsertionOptions" structure to
186  * override some params.
187  * Usage:
188  * \code
189  * mrpt::maps::CPointsMap *map =
190  * obs->buildAuxPointsMap<mrpt::maps::CPointsMap>(&options or nullptr);
191  * \endcode
192  * \sa getAuxPointsMap
193  */
194  template <class POINTSMAP>
195  inline const POINTSMAP* buildAuxPointsMap(
196  const void* options = nullptr) const
197  {
199  return static_cast<const POINTSMAP*>(m_cachedMap.get());
200  }
201 
202  /** @} */
203 
204  /** Return true if the laser scanner is "horizontal", so it has an absolute
205  * value of "pitch" and "roll" less or equal to the given tolerance (in
206  * rads, default=0) (with the normal vector either upwards or downwards).
207  */
208  bool isPlanarScan(const double tolerance = 0) const;
209 
210  /** Return true if scan has intensity */
211  bool hasIntensity() const;
212  /** Marks this scan as having or not intensity data. */
213  void setScanHasIntensity(bool setHasIntensityFlag);
214 
215  // See base class docs
216  void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const override
217  {
218  out_sensorPose = sensorPose;
219  }
220  void setSensorPose(const mrpt::poses::CPose3D& newSensorPose) override
221  {
222  sensorPose = newSensorPose;
223  }
224  void getDescriptionAsText(std::ostream& o) const override;
225 
226  /** A general method to truncate the scan by defining a minimum valid
227  distance and a maximum valid angle as well as minimun and maximum heights
228  (NOTE: the laser z-coordinate must be provided).
229  */
231  float min_distance, float max_angle, float min_height = 0,
232  float max_height = 0, float h = 0);
233 
234  /** Mark as invalid sensed points that fall within any of a set of
235  * "exclusion areas", given in coordinates relative to the vehicle (taking
236  * into account "sensorPose").
237  * \sa C2DRangeFinderAbstract::loadExclusionAreas
238  */
239  void filterByExclusionAreas(const TListExclusionAreas& areas);
240 
241  /** Mark as invalid sensed points that fall within any of a set of
242  * "exclusion areas", given in coordinates relative to the vehicle (taking
243  * into account "sensorPose"), AND such as the Z coordinate of the point
244  * falls in the range [min,max] associated to each exclusion polygon.
245  * \sa C2DRangeFinderAbstract::loadExclusionAreas
246  */
248 
249  /** Mark as invalid the ranges in any of a given set of "forbiden angle
250  * ranges", given as pairs<min_angle,max_angle>.
251  * \sa C2DRangeFinderAbstract::loadExclusionAreas
252  */
254  const std::vector<std::pair<double, double>>& angles);
255 
256 }; // End of class def.
257 
258 } // namespace obs
259 namespace typemeta
260 {
261 // Specialization must occur in the same namespace
262 MRPT_DECLARE_TTYPENAME_PTR_NAMESPACE(CObservation2DRangeScan, ::mrpt::obs)
263 } // namespace typemeta
264 
265 } // namespace mrpt
266 
267 #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)
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< int32_t > > intensity
The intensity values of the scan.
#define DECLARE_MEXPLUS_FROM(complete_type)
This must be inserted if a custom conversion method for MEX API is implemented in the class...
A generic proxy accessor template that only allows read-only access to the original binded STL contai...
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...
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
int32_t getScanIntensity(const size_t i) const
GLenum GLsizei len
Definition: glext.h:4712
size_t getScanSize() const
Get number of scan rays.
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< char > > 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::vector< mrpt::math::CPolygon > TListExclusionAreas
Used in filterByExclusionAreas.
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< float > > scan
The range values of the scan, in meters.
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)
mrpt::aligned_std_vector< float > m_scan
The range values of the scan, in meters.
This namespace contains representation of robot actions and observations.
#define M_PIf
Definition: common.h:61
int val
Definition: mrpt_jpeglib.h:955
bool m_has_intensity
Whether the intensity values are present or not.
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:138
__int32 int32_t
Definition: rptypes.h:46
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:86
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
std::vector< std::pair< mrpt::math::CPolygon, std::pair< double, double > >> TListExclusionAreasWithRanges
Used in filterByExclusionAreas.
void resizeScan(const size_t len)
Resizes all data vectors to allocate a given number of scan rays.
mrpt::aligned_std_vector< int32_t > m_intensity
The intensity values of the scan.
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.
mrpt::aligned_std_vector< char > m_validRange
It&#39;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)...
void loadFromVectors(size_t nRays, const float *scanRanges, const char *scanValidity)
bool hasIntensity() const
Return true if scan has intensity.
void filterByExclusionAreas(const TListExclusionAreas &areas)
Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinate...
CObservation2DRangeScan()=default
Default constructor.
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: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020