Main MRPT website > C++ reference for MRPT 1.5.5
CObservation2DRangeScan.cpp
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 
10 #include "obs-precomp.h" // Precompiled headers
11 
13 #include <mrpt/poses/CPosePDF.h>
14 #include <mrpt/utils/CStream.h>
15 #include <mrpt/math/CMatrix.h>
16 #include <mrpt/math/wrap2pi.h>
17 #if MRPT_HAS_MATLAB
18 # include <mexplus.h>
19 #endif
20 
21 using namespace std;
22 using namespace mrpt::obs;
23 using namespace mrpt::utils;
24 using namespace mrpt::poses;
25 using namespace mrpt::math;
26 
27 // This must be added to any CSerializable class implementation file.
29 
30 /*---------------------------------------------------------------
31  Constructor
32  ---------------------------------------------------------------*/
34  m_scan(),
35  m_intensity(),
36  m_validRange(),
37  m_has_intensity(false),
38  scan( m_scan ), // proxy ctor
39  intensity( m_intensity ), // proxy ctor
40  validRange( m_validRange ), // proxy ctor
41  aperture( M_PIf ),
42  rightToLeft( true ),
43  maxRange( 80.0f ),
44  sensorPose(),
45  stdError( 0.01f ),
46  beamAperture(0),
47  deltaPitch(0),
48  m_cachedMap()
49 {
50 }
51 
52 CObservation2DRangeScan::CObservation2DRangeScan(const CObservation2DRangeScan &o ) :
53  scan( m_scan ), // proxy ctor
54  intensity( m_intensity ), // proxy ctor
55  validRange( m_validRange ) // proxy ctor
56 {
57  *this = o; // rely on compiler-generated copy op + the custom = operator in proxies.
58 }
59 
60 /*---------------------------------------------------------------
61  Destructor
62  ---------------------------------------------------------------*/
64 {
65 }
66 
67 /*---------------------------------------------------------------
68  Implements the writing to a CStream capability of CSerializable objects
69  ---------------------------------------------------------------*/
71 {
72  if (version)
73  *version = 7;
74  else
75  {
76  // The data
77  out << aperture << rightToLeft << maxRange << sensorPose;
78  uint32_t N = scan.size();
79  out << N;
80  ASSERT_(validRange.size() == scan.size() );
81  if (N)
82  {
83  out.WriteBufferFixEndianness( &m_scan[0], N );
84  out.WriteBuffer( &m_validRange[0],sizeof(m_validRange[0])*N );
85  }
86  out << stdError;
87  out << timestamp;
88  out << beamAperture;
89 
90  out << sensorLabel;
91 
92  out << deltaPitch;
93 
94  out << hasIntensity();
95  if(hasIntensity())
97  }
98 }
99 
100 /*---------------------------------------------------------------
101  Filter out invalid points by a minimum distance, a maximum angle and a certain distance at the end (z-coordinate of the lasers must be provided)
102  ---------------------------------------------------------------*/
103 void CObservation2DRangeScan::truncateByDistanceAndAngle(float min_distance, float max_angle, float min_height, float max_height, float h )
104 {
105  // FILTER OUT INVALID POINTS!!
108  CPose3D pose;
109  unsigned int k;
110  unsigned int nPts = scan.size();
111 
112  for( itScan = m_scan.begin(), itValid = m_validRange.begin(), k = 0;
113  itScan != m_scan.end();
114  itScan++, itValid++, k++ )
115  {
116  float ang = fabs(k*aperture/nPts - aperture*0.5);
117  float x = (*itScan)*cos(ang);
118 
119  if( min_height != 0 || max_height != 0 )
120  {
121  ASSERT_( max_height > min_height );
122  if( *itScan < min_distance || ang > max_angle || x > h - min_height || x < h - max_height )
123  *itValid = false;
124  } // end if
125  else
126  if( *itScan < min_distance || ang > max_angle )
127  *itValid = false;
128  }
129 }
130 
131 /*---------------------------------------------------------------
132  Implements the reading from a CStream capability of CSerializable objects
133  ---------------------------------------------------------------*/
135 {
136  switch(version)
137  {
138  case 0:
139  case 1:
140  case 2:
141  case 3:
142  {
143  CMatrix covSensorPose;
144  in >> aperture >> rightToLeft >> maxRange >> sensorPose >> covSensorPose;
145  uint32_t N,i;
146 
147  in >> N;
148 
149  this->resizeScan(N);
150  if (N)
151  in.ReadBufferFixEndianness( &m_scan[0], N);
152 
153  if (version>=1)
154  { // Load validRange:
155  if (N)
156  in.ReadBuffer( &m_validRange[0], sizeof(m_validRange[0])*N );
157  }
158  else
159  {
160  // validRange: Default values: If distance is not maxRange
161  for (i=0;i<N;i++)
162  m_validRange[i]= scan[i] < maxRange;
163  }
164 
165  if (version>=2)
166  {
167  in >> stdError;
168  }
169  else
170  {
171  stdError = 0.01f;
172  }
173 
174  if (version>=3)
175  {
176  in >> timestamp;
177  }
178 
179  // Default values for newer versions:
180  beamAperture = DEG2RAD(0.25f);
181 
182  deltaPitch = 0;
183  sensorLabel = "";
184 
185  } break;
186 
187  case 4:
188  case 5:
189  case 6:
190  case 7:
191  {
192  uint32_t N;
193 
194  CMatrix covSensorPose;
196 
197  if (version<6) // covSensorPose was removed in version 6
198  in >> covSensorPose;
199 
200  in >> N;
201  this->resizeScan(N);
202  if (N)
203  {
204  in.ReadBufferFixEndianness( &m_scan[0], N);
205  in.ReadBuffer( &m_validRange[0], sizeof(m_validRange[0])*N );
206  }
207  in >> stdError;
208  in.ReadBufferFixEndianness( &timestamp, 1);
209  in >> beamAperture;
210 
211  if (version>=5)
212  {
213  in >> sensorLabel;
214  in >> deltaPitch;
215  }
216  else
217  {
218  sensorLabel = "";
219  deltaPitch = 0;
220  }
221  if (version>=7)
222  {
223  bool hasIntensity;
224  in >> hasIntensity;
226  if (hasIntensity && N) {
227  in.ReadBufferFixEndianness( &m_intensity[0], N);
228  }
229  }
230  } break;
231  default:
233  };
234 
235  m_cachedMap.clear();
236 }
237 
238 /*---------------------------------------------------------------
239  Implements the writing to a mxArray for Matlab
240  ---------------------------------------------------------------*/
241 #if MRPT_HAS_MATLAB
242 // Add to implement mexplus::from template specialization
244 
246 {
247  const char* fields[] = {"class", // Data common to any MRPT class
248  "ts","sensorLabel", // Data common to any observation
249  "scan","validRange","intensity" // Received raw data
250  "aperture","rightToLeft","maxRange", // Scan plane geometry and properties
251  "stdError","beamAperture","deltaPitch", // Ray properties
252  "pose", // Sensor pose
253  "map"}; // Points map
254  mexplus::MxArray obs_struct( mexplus::MxArray::Struct(sizeof(fields)/sizeof(fields[0]),fields) );
255 
256  obs_struct.set("class", this->GetRuntimeClass()->className);
257 
258  obs_struct.set("ts", this->timestamp);
259  obs_struct.set("sensorLabel", this->sensorLabel);
260 
261  obs_struct.set("scan", this->m_scan);
262  // TODO: "validRange should be a vector<bool> for Matlab instead of vector<char>" ==> JLBC: It cannot be done like that since serializing "bool" is not cross-platform safe, while "char" is...
263  obs_struct.set("validRange", this->m_validRange);
264  obs_struct.set("intensity", this->m_intensity);
265  obs_struct.set("aperture", this->aperture);
266  obs_struct.set("rightToLeft", this->rightToLeft);
267  obs_struct.set("maxRange", this->maxRange);
268  obs_struct.set("stdError", this->stdError);
269  obs_struct.set("beamAperture", this->beamAperture);
270  obs_struct.set("deltaPitch", this->deltaPitch);
271  obs_struct.set("pose", this->sensorPose);
272  // TODO: obs_struct.set("map", ...)
273  return obs_struct.release();
274 }
275 #endif
276 
277 /*---------------------------------------------------------------
278  isPlanarScan
279  ---------------------------------------------------------------*/
280 bool CObservation2DRangeScan::isPlanarScan( const double tolerance ) const
281 {
282  return sensorPose.isHorizontal(tolerance);
283 }
284 
286 {
287  return m_has_intensity;
288 }
289 void CObservation2DRangeScan::setScanHasIntensity(bool setHasIntensityFlag)
290 {
291  m_has_intensity = setHasIntensityFlag;
292 }
293 
294 
295 /*---------------------------------------------------------------
296  filterByExclusionAreas
297  ---------------------------------------------------------------*/
299 {
300  if (areas.empty()) return;
301 
302  MRPT_START
303 
304  double Ang, dA;
305  size_t sizeRangeScan = scan.size();
306 
308 
309  if (!sizeRangeScan) return;
310 
311  if (rightToLeft)
312  {
313  Ang = - 0.5 * aperture;
314  dA = aperture / (sizeRangeScan-1);
315  }
316  else
317  {
318  Ang = + 0.5 * aperture;
319  dA = - aperture / (sizeRangeScan-1);
320  }
321 
324 
325  for (scan_it=m_scan.begin(), valid_it=m_validRange.begin(); scan_it!=m_scan.end(); scan_it++, valid_it++)
326  {
327  if (! *valid_it)
328  {
329  Ang+=dA;
330  continue; // Already it's invalid
331  }
332 
333  // Compute point in 2D, local to the laser center:
334  const double Lx = *scan_it * cos( Ang );
335  const double Ly = *scan_it * sin( Ang );
336  Ang+=dA;
337 
338  // To real 3D pose:
339  double Gx,Gy,Gz;
340  this->sensorPose.composePoint(Lx,Ly,0, Gx,Gy,Gz);
341 
342  // Filter by X,Y:
343  for (TListExclusionAreasWithRanges::const_iterator i=areas.begin();i!=areas.end();++i)
344  {
345  if ( i->first.PointIntoPolygon(Gx,Gy) &&
346  (Gz>=i->second.first && Gz<=i->second.second) )
347  {
348  *valid_it = false;
349  break; // Go for next point
350  }
351  } // for each area
352  } // for each point
353 
354  MRPT_END
355 }
356 
357 /*---------------------------------------------------------------
358  filterByExclusionAreas
359  ---------------------------------------------------------------*/
360 void CObservation2DRangeScan::filterByExclusionAreas( const std::vector<mrpt::math::CPolygon> &areas )
361 {
362  if (areas.empty()) return;
363 
365  for (size_t i=0;i<areas.size();i++)
366  {
367  TListExclusionAreasWithRanges::value_type dat;
368  dat.first = areas[i];
369  dat.second.first = -std::numeric_limits<double>::max();
370  dat.second.second = std::numeric_limits<double>::max();
371 
372  lst.push_back(dat);
373  }
375 }
376 
377 /*---------------------------------------------------------------
378  filterByExclusionAngles
379  ---------------------------------------------------------------*/
380 void CObservation2DRangeScan::filterByExclusionAngles( const std::vector<std::pair<double,double> > &angles )
381 {
382  if (angles.empty()) return;
383 
384  MRPT_START
385 
386  double Ang, dA;
387  const size_t sizeRangeScan = scan.size();
388 
390 
391  if (!sizeRangeScan) return;
392 
393  if (rightToLeft)
394  {
395  Ang = - 0.5 * aperture;
396  dA = aperture / (sizeRangeScan-1);
397  }
398  else
399  {
400  Ang = + 0.5 * aperture;
401  dA = - aperture / (sizeRangeScan-1);
402  }
403 
404  // For each forbiden angle range:
405  for (vector<pair<double,double> >::const_iterator itA=angles.begin();itA!=angles.end();++itA)
406  {
407  int ap_idx_ini = mrpt::math::wrapTo2Pi(itA->first-Ang) / dA; // The signs are all right! ;-)
408  int ap_idx_end = mrpt::math::wrapTo2Pi(itA->second-Ang) / dA;
409 
410  if (ap_idx_ini<0) ap_idx_ini=0;
411  if (ap_idx_end<0) ap_idx_end=0;
412 
413  if (ap_idx_ini>(int)sizeRangeScan) ap_idx_ini=sizeRangeScan-1;
414  if (ap_idx_end>(int)sizeRangeScan) ap_idx_end=sizeRangeScan-1;
415 
416  const size_t idx_ini = ap_idx_ini;
417  const size_t idx_end = ap_idx_end;
418 
419  if (idx_end>=idx_ini)
420  {
421  for (size_t i=idx_ini;i<=idx_end;i++)
422  m_validRange[i]=false;
423  }
424  else
425  {
426  for (size_t i=0;i<idx_end;i++)
427  m_validRange[i]=false;
428 
429  for (size_t i=idx_ini;i<sizeRangeScan;i++)
430  m_validRange[i]=false;
431  }
432  }
433 
434  MRPT_END
435 }
436 
437 namespace mrpt
438 {
439  namespace obs
440  {
441  // Tricky way to call to a library that depends on us, a sort of "run-time" linking:
442  // ptr_internal_build_points_map_from_scan2D is a functor in "mrpt-obs", set by "mrpt-maps" at its startup.
443  void OBS_IMPEXP (*ptr_internal_build_points_map_from_scan2D)(const mrpt::obs::CObservation2DRangeScan &obs, mrpt::maps::CMetricMapPtr &out_map, const void *insertOps) = NULL;
444  }
445 }
446 
447 /*---------------------------------------------------------------
448  internal_buildAuxPointsMap
449  ---------------------------------------------------------------*/
451 {
453  throw std::runtime_error("[CObservation2DRangeScan::buildAuxPointsMap] ERROR: This function needs linking against mrpt-maps.\n");
454 
455  (*ptr_internal_build_points_map_from_scan2D)(*this,m_cachedMap, options);
456 }
457 
458 /** Fill out a T2DScanProperties structure with the parameters of this scan */
460 {
461  p.nRays = this->scan.size();
462  p.aperture = this->aperture;
463  p.rightToLeft = this->rightToLeft;
464 }
465 
467 {
468  if (a.nRays != b.nRays) return a.nRays<b.nRays;
469  if (a.aperture != b.aperture) return a.aperture < b.aperture;
470  if (a.rightToLeft != b.rightToLeft) return a.rightToLeft;
471  return false;
472 }
473 
474 
476 {
478  o << "Homogeneous matrix for the sensor's 3D pose, relative to robot base:\n";
480 
481  o << format("Samples direction: %s\n", (rightToLeft) ? "Right->Left" : "Left->Right");
482  o << format("Points in the scan: %u\n", (unsigned)scan.size());
483  o << format("Estimated sensor 'sigma': %f\n", stdError );
484  o << format("Increment in pitch during the scan: %f deg\n", RAD2DEG( deltaPitch ));
485 
486  size_t i,inval = 0;
487  for (i=0;i<scan.size();i++) if (!validRange[i]) inval++;
488  o << format("Invalid points in the scan: %u\n", (unsigned)inval);
489 
490  o << format("Sensor maximum range: %.02f m\n", maxRange );
491  o << format("Sensor field-of-view (\"aperture\"): %.01f deg\n", RAD2DEG(aperture) );
492 
493  o << "Raw scan values: [";
494  for (i=0;i<scan.size();i++) o << format("%.03f ", scan[i] );
495  o << "]\n";
496 
497  o << "Raw valid-scan values: [";
498  for (i=0;i<validRange.size();i++) o << format("%u ", validRange[i] ? 1:0 );
499  o << "]\n\n";
500 
501  if(hasIntensity()){
502  o << "Raw intensity values: [";
503  for (i=0;i<m_intensity.size();i++) o << format("%d ", m_intensity[i]);
504  o << "]\n\n";
505  }
506 
507 }
508 
509 float CObservation2DRangeScan::getScanRange(const size_t i) const
510 {
511  ASSERT_BELOW_(i,m_scan.size());
512  return m_scan[i];
513 }
514 
515 void CObservation2DRangeScan::setScanRange(const size_t i, const float val)
516 {
517  ASSERT_BELOW_(i,m_scan.size());
518  m_scan[i] = val;
519 }
520 
522 {
523  ASSERT_BELOW_(i,m_intensity.size());
524  return m_intensity[i];
525 }
526 void CObservation2DRangeScan::setScanIntensity(const size_t i, const int val)
527 {
528  ASSERT_BELOW_(i,m_intensity.size());
529  m_intensity[i] = val;
530 }
531 
533 {
534  ASSERT_BELOW_(i,m_validRange.size());
535  return m_validRange[i] != 0;
536 }
537 void CObservation2DRangeScan::setScanRangeValidity(const size_t i, const bool val)
538 {
539  ASSERT_BELOW_(i,m_validRange.size());
540  m_validRange[i] = val ? 1:0;
541 }
542 
544 {
545  const size_t capacity = mrpt::utils::length2length4N(len);
546  m_scan.reserve(capacity);
547  m_intensity.reserve(capacity);
548  m_validRange.reserve(capacity);
549 
550  m_scan.resize(len);
551  m_intensity.resize(len);
552  m_validRange.resize(len);
553 }
554 
555 void CObservation2DRangeScan::resizeScanAndAssign(const size_t len, const float rangeVal, const bool rangeValidity, const int32_t rangeIntensity)
556 {
557  const size_t capacity = mrpt::utils::length2length4N(len);
558  m_scan.reserve(capacity);
559  m_intensity.reserve(capacity);
560  m_validRange.reserve(capacity);
561 
562  m_scan.assign(len, rangeVal);
563  m_validRange.assign(len, rangeValidity);
564  m_intensity.assign(len, rangeIntensity);
565 }
566 
568 {
569  return m_scan.size();
570 }
571 
572 void CObservation2DRangeScan::loadFromVectors(size_t nRays, const float *scanRanges, const char *scanValidity )
573 {
574  ASSERT_(scanRanges);
575  ASSERT_(scanValidity);
576  resizeScan(nRays);
577  for (size_t i=0;i<nRays;i++) {
578  m_scan[i] = scanRanges[i];
579  m_validRange[i] = scanValidity[i];
580  }
581 }
582 
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
Definition: zip.h:16
virtual const mrpt::utils::TRuntimeClassId * GetRuntimeClass() const
Returns information about the class of an object in runtime.
void OBS_IMPEXP(* ptr_internal_build_points_map_from_scan2D)(const mrpt::obs::CObservation2DRangeScan &obs, mrpt::maps::CMetricMapPtr &out_map, const void *insertOps)
float beamAperture
The aperture of each beam, in radians, used to insert "thick" rays in the occupancy grid...
bool isHorizontal(const double tolerance=0) const
Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards)...
Definition: CPose3D.cpp:633
void getScanProperties(T2DScanProperties &p) const
Fill out a T2DScanProperties structure with the parameters of this scan.
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
void setScanRange(const size_t i, const float val)
std::vector< std::pair< mrpt::math::CPolygon, std::pair< double, double > > > TListExclusionAreasWithRanges
Used in filterByExclusionAreas.
#define ASSERT_BELOW_(__A, __B)
Scalar * iterator
Definition: eigen_plugins.h:23
void WriteBuffer(const void *Buffer, size_t Count)
Writes a block of bytes to the stream from Buffer.
Definition: CStream.cpp:67
bool OBS_IMPEXP operator<(const T2DScanProperties &a, const T2DScanProperties &b)
Order operator, so T2DScanProperties can appear in associative STL containers.
void setScanHasIntensity(bool setHasIntensityFlag)
Marks this scan as having or not intensity data.
STL namespace.
const Scalar * const_iterator
Definition: eigen_plugins.h:24
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
void getDescriptionAsText(std::ostream &o) const MRPT_OVERRIDE
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
int32_t getScanIntensity(const size_t i) const
GLenum GLsizei len
Definition: glext.h:4349
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. 80m, 50m,...)
void WriteBufferFixEndianness(const T *ptr, size_t ElementCount)
Writes a sequence of elemental datatypes, taking care of reordering their bytes from the running arch...
Definition: CStream.h:139
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
Definition: CPose3D.cpp:427
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
T length2length4N(T len)
Returns the smaller number >=len such that it&#39;s a multiple of 4.
#define M_PIf
void readFromStream(mrpt::utils::CStream &in, int version)
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
#define MRPT_END
mrpt::math::CMatrixDouble44 getHomogeneousMatrixVal() const
Definition: CPose3D.h:173
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.
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
void setScanIntensity(const size_t i, const int val)
T wrapTo2Pi(T a)
Modifies the given angle to translate it into the [0,2pi[ range.
Definition: wrap2pi.h:40
std::vector< int32_t > m_intensity
The intensity values of the scan. If available, must have same length than validRange.
This namespace contains representation of robot actions and observations.
int val
Definition: mrpt_jpeglib.h:953
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< char > > validRange
It&#39;s false (=0) on no reflected rays, referenced to elements in scan.
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:21
GLubyte GLubyte b
Definition: glext.h:5575
#define IMPLEMENTS_MEXPLUS_FROM(complete_type)
bool m_has_intensity
Whether the intensity values are present or not. If not, space is saved during serialization.
int version
Definition: mrpt_jpeglib.h:898
#define DEG2RAD
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...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
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 writeToStream(mrpt::utils::CStream &out, int *getVersion) const
Introduces a pure virtual method responsible for writing to a CStream.
#define MRPT_START
__int32 int32_t
Definition: rptypes.h:48
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
#define RAD2DEG
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based time...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
virtual mxArray * writeToMatlab() const
Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.
Definition: CSerializable.h:79
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:72
Declares a class that represents any robot&#39;s observation.
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...
GLuint in
Definition: glext.h:6301
float aperture
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees)...
#define ASSERT_(f)
std::vector< float > m_scan
The range values of the scan, in meters. Must have same length than validRange.
void loadFromVectors(size_t nRays, const float *scanRanges, const char *scanValidity)
void internal_buildAuxPointsMap(const void *options=NULL) const
Internal method, used from buildAuxPointsMap()
mrpt::maps::CMetricMapPtr m_cachedMap
A points map, build only under demand by the methods getAuxPointsMap() and buildAuxPointsMap().
bool hasIntensity() const
Return true if scan has intensity.
GLenum GLint x
Definition: glext.h:3516
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< float > > scan
The range values of the scan, in meters. Must have same length than validRange.
void filterByExclusionAreas(const TListExclusionAreas &areas)
Mark as invalid sensed points that fall within any of a set of "exclusion areas", given in coordinate...
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:30
bool rightToLeft
Angles storage order: true=counterclockwise; false=clockwise.
unsigned __int32 uint32_t
Definition: rptypes.h:49
GLubyte GLubyte GLubyte a
Definition: glext.h:5575
GLfloat GLfloat p
Definition: glext.h:5587
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
struct mxArray_tag mxArray
Forward declaration for mxArray (avoid #including as much as possible to speed up compiling) ...
Definition: CSerializable.h:17
bool rightToLeft
The scanning direction: true=counterclockwise; false=clockwise.
virtual void getDescriptionAsText(std::ostream &o) const
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
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.5.5 Git: e06b63dbf Fri Dec 1 14:41:11 2017 +0100 at lun oct 28 01:31:35 CET 2019