Main MRPT website > C++ reference for MRPT 1.9.9
CObservationVelodyneScan.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 
14 #include <mrpt/utils/round.h>
15 #include <mrpt/utils/CStream.h>
16 
17 using namespace std;
18 using namespace mrpt::obs;
19 
20 // This must be added to any CSerializable class implementation file.
22 
24 
25 const float CObservationVelodyneScan::ROTATION_RESOLUTION =
26  0.01f; /**< degrees */
27 const float CObservationVelodyneScan::DISTANCE_MAX = 130.0f; /**< meters */
28 const float CObservationVelodyneScan::DISTANCE_RESOLUTION =
29  0.002f; /**< meters */
30 const float CObservationVelodyneScan::DISTANCE_MAX_UNITS =
31  (CObservationVelodyneScan::DISTANCE_MAX /
32  CObservationVelodyneScan::DISTANCE_RESOLUTION +
33  1.0f);
34 
35 const int SCANS_PER_FIRING = 16;
36 
37 const float VLP16_BLOCK_TDURATION = 110.592f; // [us]
38 const float VLP16_DSR_TOFFSET = 2.304f; // [us]
39 const float VLP16_FIRING_TOFFSET = 55.296f; // [us]
40 
41 const float HDR32_DSR_TOFFSET = 1.152f; // [us]
42 const float HDR32_FIRING_TOFFSET = 46.08f; // [us]
43 
44 const CObservationVelodyneScan::TGeneratePointCloudParameters
45  CObservationVelodyneScan::defaultPointCloudParams;
46 
47 CObservationVelodyneScan::TGeneratePointCloudParameters::
49  : minAzimuth_deg(0.0),
50  maxAzimuth_deg(360.0),
51  minDistance(1.0f),
52  maxDistance(std::numeric_limits<float>::max()),
53  ROI_x_min(-std::numeric_limits<float>::max()),
54  ROI_x_max(+std::numeric_limits<float>::max()),
55  ROI_y_min(-std::numeric_limits<float>::max()),
56  ROI_y_max(+std::numeric_limits<float>::max()),
57  ROI_z_min(-std::numeric_limits<float>::max()),
58  ROI_z_max(+std::numeric_limits<float>::max()),
59  nROI_x_min(.0f),
60  nROI_x_max(.0f),
61  nROI_y_min(.0f),
62  nROI_y_max(.0f),
63  nROI_z_min(.0f),
64  nROI_z_max(.0f),
65  isolatedPointsFilterDistance(2.0f),
66  filterByROI(false),
67  filterBynROI(false),
68  filterOutIsolatedPoints(false),
69  dualKeepStrongest(true),
70  dualKeepLast(true),
71  generatePerPointTimestamp(false),
72  generatePerPointAzimuth(false)
73 {
74 }
75 
76 CObservationVelodyneScan::TGeneratePointCloudSE3Results::
77  TGeneratePointCloudSE3Results()
78  : num_points(0), num_correctly_inserted_points(0)
79 {
80 }
81 
83  : minRange(1.0),
84  maxRange(130.0),
85  sensorPose(),
88 {
89 }
90 
94 {
96 }
97 
98 /*---------------------------------------------------------------
99  Implements the writing to a CStream capability of CSerializable objects
100  ---------------------------------------------------------------*/
102  mrpt::utils::CStream& out, int* version) const
103 {
104  if (version)
105  *version = 1;
106  else
107  {
108  out << timestamp << sensorLabel;
109 
110  out << minRange << maxRange << sensorPose;
111  {
112  uint32_t N = scan_packets.size();
113  out << N;
114  if (N)
115  out.WriteBuffer(&scan_packets[0], sizeof(scan_packets[0]) * N);
116  }
117  {
119  out << N;
120  if (N)
121  out.WriteBuffer(
123  sizeof(calibration.laser_corrections[0]) * N);
124  }
125  out << point_cloud.x << point_cloud.y << point_cloud.z
127  out << has_satellite_timestamp; // v1
128  }
129 }
130 
131 /*---------------------------------------------------------------
132  Implements the reading from a CStream capability of CSerializable objects
133  ---------------------------------------------------------------*/
135  mrpt::utils::CStream& in, int version)
136 {
137  switch (version)
138  {
139  case 0:
140  case 1:
141  {
142  in >> timestamp >> sensorLabel;
143 
144  in >> minRange >> maxRange >> sensorPose;
145  {
146  uint32_t N;
147  in >> N;
148  scan_packets.resize(N);
149  if (N)
150  in.ReadBuffer(
151  &scan_packets[0], sizeof(scan_packets[0]) * N);
152  }
153  {
154  uint32_t N;
155  in >> N;
156  calibration.laser_corrections.resize(N);
157  if (N)
158  in.ReadBuffer(
160  sizeof(calibration.laser_corrections[0]) * N);
161  }
164  if (version >= 1)
166  else
168  (this->timestamp != this->originalReceivedTimestamp);
169  }
170  break;
171  default:
173  };
174 
175  // m_cachedMap.clear();
176 }
177 
179 {
181  o << "Homogeneous matrix for the sensor 3D pose, relative to robot base:\n";
182  o << sensorPose.getHomogeneousMatrixVal() << "\n" << sensorPose << endl;
183 
184  o << format("Sensor min/max range: %.02f / %.02f m\n", minRange, maxRange);
185 
186  o << "Raw packet count: " << scan_packets.size() << "\n";
187 }
188 
189 /** [us] */
190 double HDL32AdjustTimeStamp(int firingblock, int dsr)
191 {
192  return (firingblock * HDR32_FIRING_TOFFSET) + (dsr * HDR32_DSR_TOFFSET);
193 }
194 /** [us] */
195 double VLP16AdjustTimeStamp(int firingblock, int dsr, int firingwithinblock)
196 {
197  return (firingblock * VLP16_BLOCK_TDURATION) + (dsr * VLP16_DSR_TOFFSET) +
198  (firingwithinblock * VLP16_FIRING_TOFFSET);
199 }
200 
201 /** Auxiliary class used to refactor
202  * CObservationVelodyneScan::generatePointCloud() */
204 {
205  /** Process the insertion of a new (x,y,z) point to the cloud, in
206  * sensor-centric coordinates, with the exact timestamp of that LIDAR ray */
207  virtual void add_point(
208  double pt_x, double pt_y, double pt_z, uint8_t pt_intensity,
209  const mrpt::system::TTimeStamp& tim, const float azimuth) = 0;
210 };
211 
213  const CObservationVelodyneScan& scan,
215  PointCloudStorageWrapper& out_pc)
216 {
217  // Initially based on code from ROS velodyne & from
218  // vtkVelodyneHDLReader::vtkInternal::ProcessHDLPacket().
219  using mrpt::utils::round;
220 
221  // Access to sin/cos table:
222  mrpt::obs::T2DScanProperties scan_props;
223  scan_props.aperture = 2 * M_PI;
225  scan_props.rightToLeft = true;
226  // The LUT contains sin/cos values for angles in this order: [180deg ... 0
227  // deg ... -180 deg]
230 
231  const int minAzimuth_int = round(params.minAzimuth_deg * 100);
232  const int maxAzimuth_int = round(params.maxAzimuth_deg * 100);
233  const float realMinDist =
234  std::max(static_cast<float>(scan.minRange), params.minDistance);
235  const float realMaxDist =
236  std::min(params.maxDistance, static_cast<float>(scan.maxRange));
237  const int16_t isolatedPointsFilterDistance_units =
238  params.isolatedPointsFilterDistance /
240 
241  // This is: 16,32,64 depending on the LIDAR model
242  const size_t num_lasers = scan.calibration.laser_corrections.size();
243 
244  for (size_t iPkt = 0; iPkt < scan.scan_packets.size(); iPkt++)
245  {
247  &scan.scan_packets[iPkt];
248 
249  mrpt::system::TTimeStamp pkt_tim; // Find out timestamp of this pkt
250  {
251  const uint32_t us_pkt0 = scan.scan_packets[0].gps_timestamp;
252  const uint32_t us_pkt_this = raw->gps_timestamp;
253  // Handle the case of time counter reset by new hour 00:00:00
254  const uint32_t us_ellapsed =
255  (us_pkt_this >= us_pkt0)
256  ? (us_pkt_this - us_pkt0)
257  : (1000000UL * 3600UL + us_pkt_this - us_pkt0);
258  pkt_tim =
259  mrpt::system::timestampAdd(scan.timestamp, us_ellapsed * 1e-6);
260  }
261 
262  // Take the median rotational speed as a good value for interpolating
263  // the missing azimuths:
264  int median_azimuth_diff;
265  {
266  // In dual return, the azimuth rate is actually twice this
267  // estimation:
268  const int nBlocksPerAzimuth =
269  (raw->laser_return_mode ==
271  ? 2
272  : 1;
273  std::vector<int> diffs(
275  nBlocksPerAzimuth);
276  for (int i = 0; i < CObservationVelodyneScan::BLOCKS_PER_PACKET -
277  nBlocksPerAzimuth;
278  ++i)
279  {
281  raw->blocks[i + nBlocksPerAzimuth].rotation -
282  raw->blocks[i].rotation) %
284  diffs[i] = localDiff;
285  }
286  std::nth_element(
287  diffs.begin(),
289  diffs.end()); // Calc median
290  median_azimuth_diff =
292  }
293 
294  for (int block = 0; block < CObservationVelodyneScan::BLOCKS_PER_PACKET;
295  block++) // Firings per packet
296  {
297  // ignore packets with mangled or otherwise different contents
298  if ((num_lasers != 64 &&
300  raw->blocks[block].header) ||
301  (raw->blocks[block].header !=
303  raw->blocks[block].header !=
305  {
306  cerr << "[CObservationVelodyneScan] skipping invalid packet: "
307  "block "
308  << block << " header value is "
309  << raw->blocks[block].header;
310  continue;
311  }
312 
313  const int dsr_offset = (raw->blocks[block].header ==
315  ? 32
316  : 0;
317  const float azimuth_raw_f = (float)(raw->blocks[block].rotation);
318  const bool block_is_dual_2nd_ranges =
319  (raw->laser_return_mode ==
321  ((block & 0x01) != 0));
322  const bool block_is_dual_last_ranges =
323  (raw->laser_return_mode ==
325  ((block & 0x01) == 0));
326 
327  for (int dsr = 0, k = 0; dsr < SCANS_PER_FIRING; dsr++, k++)
328  {
329  if (!raw->blocks[block]
330  .laser_returns[k]
331  .distance) // Invalid return?
332  continue;
333 
334  const uint8_t rawLaserId =
335  static_cast<uint8_t>(dsr + dsr_offset);
336  uint8_t laserId = rawLaserId;
337 
338  // Detect VLP-16 data and adjust laser id if necessary
339  bool firingWithinBlock = false;
340  if (num_lasers == 16)
341  {
342  if (laserId >= 16)
343  {
344  laserId -= 16;
345  firingWithinBlock = true;
346  }
347  }
348 
349  ASSERT_BELOW_(laserId, num_lasers)
351  scan.calibration.laser_corrections[laserId];
352 
353  // In dual return, if the distance is equal in both ranges,
354  // ignore one of them:
355  if (block_is_dual_2nd_ranges)
356  {
357  if (raw->blocks[block].laser_returns[k].distance ==
358  raw->blocks[block - 1].laser_returns[k].distance)
359  continue; // duplicated point
360  if (!params.dualKeepStrongest) continue;
361  }
362  if (block_is_dual_last_ranges && !params.dualKeepLast) continue;
363 
364  // Return distance:
365  const float distance =
366  raw->blocks[block].laser_returns[k].distance *
368  calib.distanceCorrection;
369  if (distance < realMinDist || distance > realMaxDist) continue;
370 
371  // Isolated points filtering:
372  if (params.filterOutIsolatedPoints)
373  {
374  bool pass_filter = true;
375  const int16_t dist_this =
376  raw->blocks[block].laser_returns[k].distance;
377  if (k > 0)
378  {
379  const int16_t dist_prev =
380  raw->blocks[block].laser_returns[k - 1].distance;
381  if (!dist_prev ||
382  std::abs(dist_this - dist_prev) >
383  isolatedPointsFilterDistance_units)
384  pass_filter = false;
385  }
386  if (k < (SCANS_PER_FIRING - 1))
387  {
388  const int16_t dist_next =
389  raw->blocks[block].laser_returns[k + 1].distance;
390  if (!dist_next ||
391  std::abs(dist_this - dist_next) >
392  isolatedPointsFilterDistance_units)
393  pass_filter = false;
394  }
395  if (!pass_filter) continue; // Filter out this point
396  }
397 
398  // Azimuth correction: correct for the laser rotation as a
399  // function of timing during the firings
400  double timestampadjustment =
401  0.0; // [us] since beginning of scan
402  double blockdsr0 = 0.0;
403  double nextblockdsr0 = 1.0;
404  switch (num_lasers)
405  {
406  // VLP-16
407  case 16:
408  {
409  if (raw->laser_return_mode ==
411  {
412  timestampadjustment = VLP16AdjustTimeStamp(
413  block / 2, laserId, firingWithinBlock);
414  nextblockdsr0 =
415  VLP16AdjustTimeStamp(block / 2 + 1, 0, 0);
416  blockdsr0 = VLP16AdjustTimeStamp(block / 2, 0, 0);
417  }
418  else
419  {
420  timestampadjustment = VLP16AdjustTimeStamp(
421  block, laserId, firingWithinBlock);
422  nextblockdsr0 =
423  VLP16AdjustTimeStamp(block + 1, 0, 0);
424  blockdsr0 = VLP16AdjustTimeStamp(block, 0, 0);
425  }
426  }
427  break;
428  // HDL-32:
429  case 32:
430  timestampadjustment = HDL32AdjustTimeStamp(block, dsr);
431  nextblockdsr0 = HDL32AdjustTimeStamp(block + 1, 0);
432  blockdsr0 = HDL32AdjustTimeStamp(block, 0);
433  break;
434  case 64:
435  break;
436  default:
437  {
438  THROW_EXCEPTION("Error: unhandled LIDAR model!")
439  }
440  };
441 
442  const int azimuthadjustment = mrpt::utils::round(
443  median_azimuth_diff * ((timestampadjustment - blockdsr0) /
444  (nextblockdsr0 - blockdsr0)));
445 
446  const float azimuth_corrected_f =
447  azimuth_raw_f + azimuthadjustment;
448  const int azimuth_corrected =
449  ((int)round(azimuth_corrected_f)) %
451 
452  // Filter by azimuth:
453  if (!((minAzimuth_int < maxAzimuth_int &&
454  azimuth_corrected >= minAzimuth_int &&
455  azimuth_corrected <= maxAzimuth_int) ||
456  (minAzimuth_int > maxAzimuth_int &&
457  (azimuth_corrected <= maxAzimuth_int ||
458  azimuth_corrected >= minAzimuth_int))))
459  continue;
460 
461  // Vertical axis mis-alignment calibration:
462  const float cos_vert_angle = calib.cosVertCorrection;
463  const float sin_vert_angle = calib.sinVertCorrection;
464  const float horz_offset = calib.horizontalOffsetCorrection;
465  const float vert_offset = calib.verticalOffsetCorrection;
466 
467  float xy_distance = distance * cos_vert_angle;
468  if (vert_offset) xy_distance += vert_offset * sin_vert_angle;
469 
470  const int azimuth_corrected_for_lut =
471  (azimuth_corrected +
474  const float cos_azimuth =
475  lut_sincos.ccos[azimuth_corrected_for_lut];
476  const float sin_azimuth =
477  lut_sincos.csin[azimuth_corrected_for_lut];
478 
479  // Compute raw position
480  const mrpt::math::TPoint3Df pt(
481  xy_distance * cos_azimuth +
482  horz_offset * sin_azimuth, // MRPT +X = Velodyne +Y
483  -(xy_distance * sin_azimuth -
484  horz_offset * cos_azimuth), // MRPT +Y = Velodyne -X
485  distance * sin_vert_angle + vert_offset);
486 
487  bool add_point = true;
488  if (params.filterByROI &&
489  (pt.x > params.ROI_x_max || pt.x < params.ROI_x_min ||
490  pt.y > params.ROI_y_max || pt.y < params.ROI_y_min ||
491  pt.z > params.ROI_z_max || pt.z < params.ROI_z_min))
492  add_point = false;
493 
494  if (params.filterBynROI &&
495  (pt.x <= params.nROI_x_max && pt.x >= params.nROI_x_min &&
496  pt.y <= params.nROI_y_max && pt.y >= params.nROI_y_min &&
497  pt.z <= params.nROI_z_max && pt.z >= params.nROI_z_min))
498  add_point = false;
499 
500  if (!add_point) continue;
501 
502  // Insert point:
503  out_pc.add_point(
504  pt.x, pt.y, pt.z,
505  raw->blocks[block].laser_returns[k].intensity, pkt_tim,
506  azimuth_corrected_f);
507 
508  } // end for k,dsr=[0,31]
509  } // end for each block [0,11]
510  } // end for each data packet
511 }
512 
515 {
516  struct PointCloudStorageWrapper_Inner : public PointCloudStorageWrapper
517  {
519  const TGeneratePointCloudParameters& params_;
520  PointCloudStorageWrapper_Inner(
523  : me_(me), params_(p)
524  {
525  // Reset point cloud:
526  me_.point_cloud.clear();
527  }
528  void add_point(
529  double pt_x, double pt_y, double pt_z, uint8_t pt_intensity,
530  const mrpt::system::TTimeStamp& tim, const float azimuth) override
531  {
532  me_.point_cloud.x.push_back(pt_x);
533  me_.point_cloud.y.push_back(pt_y);
534  me_.point_cloud.z.push_back(pt_z);
535  me_.point_cloud.intensity.push_back(pt_intensity);
536  if (params_.generatePerPointTimestamp)
537  {
538  me_.point_cloud.timestamp.push_back(tim);
539  }
540  if (params_.generatePerPointAzimuth)
541  {
542  const int azimuth_corrected =
543  ((int)round(azimuth)) %
545  me_.point_cloud.azimuth.push_back(
546  azimuth_corrected * ROTATION_RESOLUTION);
547  }
548  }
549  };
550 
551  PointCloudStorageWrapper_Inner my_pc_wrap(*this, params);
552 
553  velodyne_scan_to_pointcloud(*this, params, my_pc_wrap);
554 }
555 
557  const mrpt::poses::CPose3DInterpolator& vehicle_path,
558  std::vector<mrpt::math::TPointXYZIu8>& out_points,
559  TGeneratePointCloudSE3Results& results_stats,
561 {
562  // Pre-alloc mem:
563  out_points.reserve(
564  out_points.size() +
566 
567  struct PointCloudStorageWrapper_SE3_Interp : public PointCloudStorageWrapper
568  {
570  const mrpt::poses::CPose3DInterpolator& vehicle_path_;
571  std::vector<mrpt::math::TPointXYZIu8>& out_points_;
572  TGeneratePointCloudSE3Results& results_stats_;
573  mrpt::system::TTimeStamp last_query_tim_;
574  mrpt::poses::CPose3D last_query_;
575  bool last_query_valid_;
576 
577  PointCloudStorageWrapper_SE3_Interp(
579  const mrpt::poses::CPose3DInterpolator& vehicle_path,
580  std::vector<mrpt::math::TPointXYZIu8>& out_points,
581  TGeneratePointCloudSE3Results& results_stats)
582  : me_(me),
583  vehicle_path_(vehicle_path),
584  out_points_(out_points),
585  results_stats_(results_stats),
586  last_query_tim_(INVALID_TIMESTAMP),
587  last_query_valid_(false)
588  {
589  }
590  void add_point(
591  double pt_x, double pt_y, double pt_z, uint8_t pt_intensity,
592  const mrpt::system::TTimeStamp& tim, const float azimuth) override
593  {
594  // Use a cache since it's expected that the same timestamp is
595  // queried several times in a row:
596  if (last_query_tim_ != tim)
597  {
598  last_query_tim_ = tim;
599  vehicle_path_.interpolate(tim, last_query_, last_query_valid_);
600  }
601 
602  if (last_query_valid_)
603  {
604  mrpt::poses::CPose3D global_sensor_pose(
606  global_sensor_pose.composeFrom(last_query_, me_.sensorPose);
607  double gx, gy, gz;
608  global_sensor_pose.composePoint(pt_x, pt_y, pt_z, gx, gy, gz);
609  out_points_.push_back(
610  mrpt::math::TPointXYZIu8(gx, gy, gz, pt_intensity));
611  ++results_stats_.num_correctly_inserted_points;
612  }
613  ++results_stats_.num_points;
614  }
615  };
616 
617  PointCloudStorageWrapper_SE3_Interp my_pc_wrap(
618  *this, vehicle_path, out_points, results_stats);
619  velodyne_scan_to_pointcloud(*this, params, my_pc_wrap);
620 }
621 
623 {
624  x.clear();
625  y.clear();
626  z.clear();
627  intensity.clear();
628  timestamp.clear();
629  azimuth.clear();
630 }
632 {
633  {
634  std::vector<float> d;
635  x.swap(d);
636  }
637  {
638  std::vector<float> d;
639  y.swap(d);
640  }
641  {
642  std::vector<float> d;
643  z.swap(d);
644  }
645  {
646  std::vector<uint8_t> d;
647  intensity.swap(d);
648  }
649  {
650  std::vector<mrpt::system::TTimeStamp> d;
651  timestamp.swap(d);
652  }
653  {
654  std::vector<float> d;
655  azimuth.swap(d);
656  }
657 }
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:32
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
const TSinCosValues & getSinCosForScan(const CObservation2DRangeScan &scan) const
Return two vectors with the cos and the sin of the angles for each of the rays in a scan...
GLdouble GLdouble z
Definition: glext.h:3872
#define min(a, b)
const float HDR32_FIRING_TOFFSET
static void velodyne_scan_to_pointcloud(const CObservationVelodyneScan &scan, const CObservationVelodyneScan::TGeneratePointCloudParameters &params, PointCloudStorageWrapper &out_pc)
std::vector< mrpt::system::TTimeStamp > timestamp
Timestamp for each point (if generatePerPointTimestamp=true in TGeneratePointCloudParameters), or empty vector if not populated (default).
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
std::vector< float > azimuth
Original azimuth of each point (if generatePerPointAzimuth=true, empty otherwise ) ...
static const uint16_t LOWER_BANK
Blocks 32-63.
mrpt::system::TTimeStamp originalReceivedTimestamp
The local computer-based timestamp based on the reception of the message in the computer.
#define THROW_EXCEPTION(msg)
#define ASSERT_BELOW_(__A, __B)
void WriteBuffer(const void *Buffer, size_t Count)
Writes a block of bytes to the stream from Buffer.
Definition: CStream.cpp:64
bool generatePerPointAzimuth
(Default:false) If true, populate the vector azimuth
void writeToStream(mrpt::utils::CStream &out, int *getVersion) const override
Introduces a pure virtual method responsible for writing to a CStream.
mrpt::obs::VelodyneCalibration calibration
The calibration data for the LIDAR device.
void clear_deep()
Like clear(), but also enforcing freeing memory.
bool has_satellite_timestamp
If true, CObservation::timestamp has been generated from accurate satellite clock.
STL namespace.
#define M_PI
Definition: bits.h:92
const float VLP16_DSR_TOFFSET
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot/vehicle frame of reference.
pose_t & interpolate(mrpt::system::TTimeStamp t, pose_t &out_interp, bool &out_valid_interp) const
Returns the pose at a given time, or interpolates using splines if there is not an exact match...
static const uint16_t ROTATION_MAX_UNITS
hundredths of degrees
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
unsigned char uint8_t
Definition: rptypes.h:41
void generatePointCloudAlongSE3Trajectory(const mrpt::poses::CPose3DInterpolator &vehicle_path, std::vector< mrpt::math::TPointXYZIu8 > &out_points, TGeneratePointCloudSE3Results &results_stats, const TGeneratePointCloudParameters &params=defaultPointCloudParams)
An alternative to generatePointCloud() for cases where the motion of the sensor as it grabs one scan ...
TPointCloud point_cloud
Optionally, raw data can be converted into a 3D point cloud (local coordinates wrt the sensor...
double minRange
The maximum range allowed by the device, in meters (e.g.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const override
By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accura...
Lightweight 3D point (float version).
__int16 int16_t
Definition: rptypes.h:43
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
Definition: CPose3D.cpp:639
mrpt::math::CMatrixDouble44 getHomogeneousMatrixVal() const
Definition: CPose3D.h:229
const float HDR32_DSR_TOFFSET
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.
A smart look-up-table (LUT) of sin/cos values for 2D laser scans.
std::vector< PerLaserCalib > laser_corrections
CSinCosLookUpTableFor2DScans velodyne_sincos_tables
void generatePointCloud(const TGeneratePointCloudParameters &params=defaultPointCloudParams)
Generates the point cloud into the point cloud data fields in CObservationVelodyneScan::point_cloud w...
This namespace contains representation of robot actions and observations.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:19
size_t num_correctly_inserted_points
Number of points for which a valid interpolated SE(3) pose could be determined.
void readFromStream(mrpt::utils::CStream &in, int version) override
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
uint16_t header
Block id: UPPER_BANK or LOWER_BANK.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:16
bool generatePerPointTimestamp
(Default:false) If true, populate the vector timestamp
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
Definition: CObservation.h:60
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:58
A pair of vectors with the cos and sin values.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
One unit of data from the scanner (the payload of one UDP DATA packet)
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:41
static const uint16_t UPPER_BANK
Blocks 0-31.
const float VLP16_BLOCK_TDURATION
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=nullptr, 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:453
GLuint in
Definition: glext.h:7274
uint8_t laser_return_mode
0x37: strongest, 0x38: last, 0x39: dual return
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:25
static const float DISTANCE_RESOLUTION
meters
const int SCANS_PER_FIRING
GLenum GLint GLint y
Definition: glext.h:3538
This class stores a time-stamped trajectory in SE(3) (CPose3D poses).
mrpt::system::TTimeStamp timestampAdd(const mrpt::system::TTimeStamp tim, const double num_seconds)
Shifts a timestamp the given amount of seconds (>0: forwards in time, <0: backwards) ...
Definition: datetime.cpp:198
uint16_t rotation
0-35999, divide by 100 to get degrees
std::vector< TVelodyneRawPacket > scan_packets
The main content of this object: raw data packet from the LIDAR.
GLenum GLint x
Definition: glext.h:3538
double HDL32AdjustTimeStamp(int firingblock, int dsr)
[us]
virtual void add_point(double pt_x, double pt_y, double pt_z, uint8_t pt_intensity, const mrpt::system::TTimeStamp &tim, const float azimuth)=0
Process the insertion of a new (x,y,z) point to the cloud, in sensor-centric coordinates, with the exact timestamp of that LIDAR ray.
bool rightToLeft
Angles storage order: true=counterclockwise; false=clockwise.
unsigned __int32 uint32_t
Definition: rptypes.h:47
Auxiliary class used to refactor CObservationVelodyneScan::generatePointCloud()
XYZ point (double) + Intensity(u8)
GLfloat GLfloat p
Definition: glext.h:6305
GLenum const GLfloat * params
Definition: glext.h:3534
static const float ROTATION_RESOLUTION
degrees
double VLP16AdjustTimeStamp(int firingblock, int dsr, int firingwithinblock)
[us]
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
Definition: geometry.cpp:1885
const float VLP16_FIRING_TOFFSET
virtual void getDescriptionAsText(std::ostream &o) const
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...



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