MRPT  1.9.9
CObservationVelodyneScan.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "obs-precomp.h" // Precompiled headers
11 
13 #include <mrpt/core/round.h>
18 #include <iostream>
19 
20 using namespace std;
21 using namespace mrpt::obs;
22 
23 // shortcut:
25 
26 // This must be added to any CSerializable class implementation file.
28 
30 
31 const float VLP16_BLOCK_TDURATION = 110.592f; // [us]
32 const float VLP16_DSR_TOFFSET = 2.304f; // [us]
33 const float VLP16_FIRING_TOFFSET = 55.296f; // [us]
34 
35 const double HDR32_DSR_TOFFSET = 1.152; // [us]
36 const double HDR32_FIRING_TOFFSET = 46.08; // [us]
37 
38 mrpt::system::TTimeStamp Velo::getOriginalReceivedTimeStamp() const
39 {
40  return originalReceivedTimestamp;
41 }
42 
43 uint8_t Velo::serializeGetVersion() const { return 2; }
45 {
46  out << timestamp << sensorLabel;
47  out << minRange << maxRange << sensorPose;
48  out.WriteAs<uint32_t>(scan_packets.size());
49  if (!scan_packets.empty())
50  out.WriteBuffer(
51  &scan_packets[0], sizeof(scan_packets[0]) * scan_packets.size());
52  out.WriteAs<uint32_t>(calibration.laser_corrections.size());
53  if (!calibration.laser_corrections.empty())
54  out.WriteBuffer(
55  &calibration.laser_corrections[0],
56  sizeof(calibration.laser_corrections[0]) *
57  calibration.laser_corrections.size());
58  out << point_cloud.x << point_cloud.y << point_cloud.z
59  << point_cloud.intensity;
60  out << has_satellite_timestamp; // v1
61  // v2:
62  out << point_cloud.timestamp << point_cloud.azimuth << point_cloud.laser_id
63  << point_cloud.pointsForLaserID;
64 }
65 
67 {
68  switch (version)
69  {
70  case 0:
71  case 1:
72  case 2:
73  {
74  in >> timestamp >> sensorLabel;
75 
76  in >> minRange >> maxRange >> sensorPose;
77  {
78  uint32_t N;
79  in >> N;
80  scan_packets.resize(N);
81  if (N)
82  in.ReadBuffer(
83  &scan_packets[0], sizeof(scan_packets[0]) * N);
84  }
85  {
86  uint32_t N;
87  in >> N;
88  calibration.laser_corrections.resize(N);
89  if (N)
90  in.ReadBuffer(
91  &calibration.laser_corrections[0],
92  sizeof(calibration.laser_corrections[0]) * N);
93  }
94  point_cloud.clear();
95  in >> point_cloud.x >> point_cloud.y >> point_cloud.z >>
96  point_cloud.intensity;
97  if (version >= 1)
98  in >> has_satellite_timestamp;
99  else
100  has_satellite_timestamp =
101  (this->timestamp != this->originalReceivedTimestamp);
102  if (version >= 2)
103  in >> point_cloud.timestamp >> point_cloud.azimuth >>
104  point_cloud.laser_id >> point_cloud.pointsForLaserID;
105  }
106  break;
107  default:
109  };
110 
111  // m_cachedMap.clear();
112 }
113 
114 void Velo::getDescriptionAsText(std::ostream& o) const
115 {
116  CObservation::getDescriptionAsText(o);
117  o << "Homogeneous matrix for the sensor 3D pose, relative to robot base:\n";
118  o << sensorPose.getHomogeneousMatrixVal<mrpt::math::CMatrixDouble44>()
119  << "\n"
120  << sensorPose << endl;
121  o << format("Sensor min/max range: %.02f / %.02f m\n", minRange, maxRange);
122  o << "Raw packet count: " << scan_packets.size() << "\n";
123 }
124 
125 /** [us] */
126 static double HDL32AdjustTimeStamp(int firingblock, int dsr)
127 {
128  return (firingblock * HDR32_FIRING_TOFFSET) + (dsr * HDR32_DSR_TOFFSET);
129 }
130 /** [us] */
131 static double VLP16AdjustTimeStamp(
132  int firingblock, int dsr, int firingwithinblock)
133 {
134  return (firingblock * VLP16_BLOCK_TDURATION) + (dsr * VLP16_DSR_TOFFSET) +
135  (firingwithinblock * VLP16_FIRING_TOFFSET);
136 }
137 
139  const Velo& scan, const Velo::TGeneratePointCloudParameters& params,
141 {
142  // Initially based on code from ROS velodyne & from
143  // vtkVelodyneHDLReader::vtkInternal::ProcessHDLPacket().
144  using mrpt::round;
145 
146  // Access to sin/cos table:
147  mrpt::obs::T2DScanProperties scan_props;
148  scan_props.aperture = 2 * M_PI;
149  scan_props.nRays = Velo::ROTATION_MAX_UNITS;
150  scan_props.rightToLeft = true;
151  // The LUT contains sin/cos values for angles in this order: [180deg ... 0
152  // deg ... -180 deg]
155 
156  const int minAzimuth_int = round(params.minAzimuth_deg * 100);
157  const int maxAzimuth_int = round(params.maxAzimuth_deg * 100);
158  const float realMinDist =
159  std::max(static_cast<float>(scan.minRange), params.minDistance);
160  const float realMaxDist =
161  std::min(params.maxDistance, static_cast<float>(scan.maxRange));
162  const auto isolatedPointsFilterDistance_units = mrpt::round(
163  params.isolatedPointsFilterDistance / Velo::DISTANCE_RESOLUTION);
164 
165  // This is: 16,32,64 depending on the LIDAR model
166  const size_t num_lasers = scan.calibration.laser_corrections.size();
167 
168  out_pc.resizeLaserCount(num_lasers);
169  out_pc.reserve(
170  Velo::SCANS_PER_BLOCK * scan.scan_packets.size() *
172  16);
173 
174  for (size_t iPkt = 0; iPkt < scan.scan_packets.size(); iPkt++)
175  {
176  const Velo::TVelodyneRawPacket* raw = &scan.scan_packets[iPkt];
177 
178  mrpt::system::TTimeStamp pkt_tim; // Find out timestamp of this pkt
179  {
180  const uint32_t us_pkt0 = scan.scan_packets[0].gps_timestamp;
181  const uint32_t us_pkt_this = raw->gps_timestamp;
182  // Handle the case of time counter reset by new hour 00:00:00
183  const uint32_t us_ellapsed =
184  (us_pkt_this >= us_pkt0)
185  ? (us_pkt_this - us_pkt0)
186  : (1000000UL * 3600UL + us_pkt_this - us_pkt0);
187  pkt_tim =
188  mrpt::system::timestampAdd(scan.timestamp, us_ellapsed * 1e-6);
189  }
190 
191  // Take the median rotational speed as a good value for interpolating
192  // the missing azimuths:
193  int median_azimuth_diff;
194  {
195  // In dual return, the azimuth rate is actually twice this
196  // estimation:
197  const unsigned int nBlocksPerAzimuth =
198  (raw->laser_return_mode == Velo::RETMODE_DUAL) ? 2 : 1;
199  const size_t nDiffs = Velo::BLOCKS_PER_PACKET - nBlocksPerAzimuth;
200  std::vector<int> diffs(nDiffs);
201  for (size_t i = 0; i < nDiffs; ++i)
202  {
203  int localDiff = (Velo::ROTATION_MAX_UNITS +
204  raw->blocks[i + nBlocksPerAzimuth].rotation -
205  raw->blocks[i].rotation) %
207  diffs[i] = localDiff;
208  }
209  std::nth_element(
210  diffs.begin(), diffs.begin() + Velo::BLOCKS_PER_PACKET / 2,
211  diffs.end()); // Calc median
212  median_azimuth_diff = diffs[Velo::BLOCKS_PER_PACKET / 2];
213  }
214 
215  // Firings per packet
216  for (int block = 0; block < Velo::BLOCKS_PER_PACKET; block++)
217  {
218  // ignore packets with mangled or otherwise different contents
219  if ((num_lasers != 64 &&
220  Velo::UPPER_BANK != raw->blocks[block].header) ||
221  (raw->blocks[block].header != Velo::UPPER_BANK &&
222  raw->blocks[block].header != Velo::LOWER_BANK))
223  {
224  cerr << "[Velo] skipping invalid packet: block " << block
225  << " header value is " << raw->blocks[block].header;
226  continue;
227  }
228 
229  const int dsr_offset =
230  (raw->blocks[block].header == Velo::LOWER_BANK) ? 32 : 0;
231  const auto azimuth_raw_f =
232  static_cast<float>(raw->blocks[block].rotation);
233  const bool block_is_dual_2nd_ranges =
235  ((block & 0x01) != 0));
236  const bool block_is_dual_last_ranges =
238  ((block & 0x01) == 0));
239 
240  for (int dsr = 0, k = 0; dsr < Velo::SCANS_PER_FIRING; dsr++, k++)
241  {
242  if (!raw->blocks[block]
243  .laser_returns[k]
244  .distance) // Invalid return?
245  continue;
246 
247  const auto rawLaserId = static_cast<uint8_t>(dsr + dsr_offset);
248  uint8_t laserId = rawLaserId;
249 
250  // Detect VLP-16 data and adjust laser id if necessary
251  bool firingWithinBlock = false;
252  if (num_lasers == 16)
253  {
254  if (laserId >= 16)
255  {
256  laserId -= 16;
257  firingWithinBlock = true;
258  }
259  }
260 
261  ASSERT_BELOW_(laserId, num_lasers);
263  scan.calibration.laser_corrections[laserId];
264 
265  // In dual return, if the distance is equal in both ranges,
266  // ignore one of them:
267  if (block_is_dual_2nd_ranges)
268  {
269  if (raw->blocks[block].laser_returns[k].distance ==
270  raw->blocks[block - 1].laser_returns[k].distance)
271  continue; // duplicated point
272  if (!params.dualKeepStrongest) continue;
273  }
274  if (block_is_dual_last_ranges && !params.dualKeepLast) continue;
275 
276  // Return distance:
277  const float distance =
278  raw->blocks[block].laser_returns[k].distance *
280  calib.distanceCorrection;
281  if (distance < realMinDist || distance > realMaxDist) continue;
282 
283  // Isolated points filtering:
284  if (params.filterOutIsolatedPoints)
285  {
286  bool pass_filter = true;
287  const int16_t dist_this =
288  raw->blocks[block].laser_returns[k].distance;
289  if (k > 0)
290  {
291  const int16_t dist_prev =
292  raw->blocks[block].laser_returns[k - 1].distance;
293  if (!dist_prev ||
294  std::abs(dist_this - dist_prev) >
295  isolatedPointsFilterDistance_units)
296  pass_filter = false;
297  }
298  if (k < (Velo::SCANS_PER_FIRING - 1))
299  {
300  const int16_t dist_next =
301  raw->blocks[block].laser_returns[k + 1].distance;
302  if (!dist_next ||
303  std::abs(dist_this - dist_next) >
304  isolatedPointsFilterDistance_units)
305  pass_filter = false;
306  }
307  if (!pass_filter) continue; // Filter out this point
308  }
309 
310  // Azimuth correction: correct for the laser rotation as a
311  // function of timing during the firings
312  double timestampadjustment =
313  0.0; // [us] since beginning of scan
314  double blockdsr0 = 0.0;
315  double nextblockdsr0 = 1.0;
316  switch (num_lasers)
317  {
318  // VLP-16
319  case 16:
320  {
322  {
323  timestampadjustment = VLP16AdjustTimeStamp(
324  block / 2, laserId, firingWithinBlock);
325  nextblockdsr0 =
326  VLP16AdjustTimeStamp(block / 2 + 1, 0, 0);
327  blockdsr0 = VLP16AdjustTimeStamp(block / 2, 0, 0);
328  }
329  else
330  {
331  timestampadjustment = VLP16AdjustTimeStamp(
332  block, laserId, firingWithinBlock);
333  nextblockdsr0 =
334  VLP16AdjustTimeStamp(block + 1, 0, 0);
335  blockdsr0 = VLP16AdjustTimeStamp(block, 0, 0);
336  }
337  }
338  break;
339  // HDL-32:
340  case 32:
341  timestampadjustment = HDL32AdjustTimeStamp(block, dsr);
342  nextblockdsr0 = HDL32AdjustTimeStamp(block + 1, 0);
343  blockdsr0 = HDL32AdjustTimeStamp(block, 0);
344  break;
345  case 64:
346  break;
347  default:
348  {
349  THROW_EXCEPTION("Error: unhandled LIDAR model!");
350  }
351  };
352 
353  const int azimuthadjustment = mrpt::round(
354  median_azimuth_diff * ((timestampadjustment - blockdsr0) /
355  (nextblockdsr0 - blockdsr0)));
356 
357  const float azimuth_corrected_f =
358  azimuth_raw_f + azimuthadjustment;
359  const int azimuth_corrected =
360  ((int)round(azimuth_corrected_f)) %
362 
363  // Filter by azimuth:
364  if (!((minAzimuth_int < maxAzimuth_int &&
365  azimuth_corrected >= minAzimuth_int &&
366  azimuth_corrected <= maxAzimuth_int) ||
367  (minAzimuth_int > maxAzimuth_int &&
368  (azimuth_corrected <= maxAzimuth_int ||
369  azimuth_corrected >= minAzimuth_int))))
370  continue;
371 
372  // Vertical axis mis-alignment calibration:
373  const float cos_vert_angle =
374  static_cast<float>(calib.cosVertCorrection);
375  const float sin_vert_angle =
376  static_cast<float>(calib.sinVertCorrection);
377  const float horz_offset =
378  static_cast<float>(calib.horizontalOffsetCorrection);
379  const float vert_offset =
380  static_cast<float>(calib.verticalOffsetCorrection);
381 
382  float xy_distance = distance * cos_vert_angle;
383  if (vert_offset != .0f)
384  xy_distance += vert_offset * sin_vert_angle;
385 
386  const int azimuth_corrected_for_lut =
387  (azimuth_corrected + (Velo::ROTATION_MAX_UNITS / 2)) %
389  const float cos_azimuth =
390  lut_sincos.ccos[azimuth_corrected_for_lut];
391  const float sin_azimuth =
392  lut_sincos.csin[azimuth_corrected_for_lut];
393 
394  // Compute raw position
395  const mrpt::math::TPoint3Df pt(
396  xy_distance * cos_azimuth +
397  horz_offset * sin_azimuth, // MRPT +X = Velodyne +Y
398  -(xy_distance * sin_azimuth -
399  horz_offset * cos_azimuth), // MRPT +Y = Velodyne -X
400  distance * sin_vert_angle + vert_offset);
401 
402  bool add_point = true;
403  if (params.filterByROI &&
404  (pt.x > params.ROI_x_max || pt.x < params.ROI_x_min ||
405  pt.y > params.ROI_y_max || pt.y < params.ROI_y_min ||
406  pt.z > params.ROI_z_max || pt.z < params.ROI_z_min))
407  add_point = false;
408 
409  if (params.filterBynROI &&
410  (pt.x <= params.nROI_x_max && pt.x >= params.nROI_x_min &&
411  pt.y <= params.nROI_y_max && pt.y >= params.nROI_y_min &&
412  pt.z <= params.nROI_z_max && pt.z >= params.nROI_z_min))
413  add_point = false;
414 
415  if (!add_point) continue;
416 
417  // Insert point:
418  out_pc.add_point(
419  pt.x, pt.y, pt.z,
420  raw->blocks[block].laser_returns[k].intensity, pkt_tim,
421  azimuth_corrected_f, laserId);
422 
423  } // end for k,dsr=[0,31]
424  } // end for each block [0,11]
425  } // end for each data packet
426 }
427 
430 {
431  velodyne_scan_to_pointcloud(*this, params, dest);
432 }
433 
435 {
436  struct PointCloudStorageWrapper_Inner : public PointCloudStorageWrapper
437  {
438  Velo& me_;
439  const TGeneratePointCloudParameters& params_;
440  PointCloudStorageWrapper_Inner(
442  : me_(me), params_(p)
443  {
444  // Reset point cloud:
445  me_.point_cloud.clear();
446  }
447 
448  void resizeLaserCount(std::size_t n) override
449  {
450  me_.point_cloud.pointsForLaserID.resize(n);
451  }
452 
453  void reserve(std::size_t n) override
454  {
455  me_.point_cloud.reserve(n);
456  if (!me_.point_cloud.pointsForLaserID.empty())
457  {
458  const std::size_t n_per_ring =
459  100 + n / (me_.point_cloud.pointsForLaserID.size());
460  for (auto& v : me_.point_cloud.pointsForLaserID)
461  v.reserve(n_per_ring);
462  }
463  }
464 
465  void add_point(
466  float pt_x, float pt_y, float pt_z, uint8_t pt_intensity,
467  const mrpt::system::TTimeStamp& tim, const float azimuth,
468  uint16_t laser_id) override
469  {
470  const auto idx = me_.point_cloud.x.size();
471  me_.point_cloud.x.push_back(pt_x);
472  me_.point_cloud.y.push_back(pt_y);
473  me_.point_cloud.z.push_back(pt_z);
474  me_.point_cloud.intensity.push_back(pt_intensity);
475  if (params_.generatePerPointTimestamp)
476  {
477  me_.point_cloud.timestamp.push_back(tim);
478  }
479  if (params_.generatePerPointAzimuth)
480  {
481  const int azimuth_corrected =
483  me_.point_cloud.azimuth.push_back(
484  azimuth_corrected * ROTATION_RESOLUTION);
485  }
486  me_.point_cloud.laser_id.push_back(laser_id);
487  if (params_.generatePointsForLaserID)
488  me_.point_cloud.pointsForLaserID[laser_id].push_back(idx);
489  }
490  };
491 
492  PointCloudStorageWrapper_Inner my_pc_wrap(*this, params);
493  point_cloud.clear();
494 
495  generatePointCloud(my_pc_wrap, params);
496 }
497 
499  const mrpt::poses::CPose3DInterpolator& vehicle_path,
500  std::vector<mrpt::math::TPointXYZIu8>& out_points,
501  TGeneratePointCloudSE3Results& results_stats,
503 {
504  struct PointCloudStorageWrapper_SE3_Interp : public PointCloudStorageWrapper
505  {
506  Velo& me_;
507  const mrpt::poses::CPose3DInterpolator& vehicle_path_;
508  std::vector<mrpt::math::TPointXYZIu8>& out_points_;
509  TGeneratePointCloudSE3Results& results_stats_;
510  mrpt::system::TTimeStamp last_query_tim_;
511  mrpt::poses::CPose3D last_query_;
512  bool last_query_valid_;
513 
514  void reserve(std::size_t n) override
515  {
516  out_points_.reserve(out_points_.size() + n);
517  }
518 
519  PointCloudStorageWrapper_SE3_Interp(
520  Velo& me, const mrpt::poses::CPose3DInterpolator& vehicle_path,
521  std::vector<mrpt::math::TPointXYZIu8>& out_points,
522  TGeneratePointCloudSE3Results& results_stats)
523  : me_(me),
524  vehicle_path_(vehicle_path),
525  out_points_(out_points),
526  results_stats_(results_stats),
527  last_query_tim_(INVALID_TIMESTAMP),
528  last_query_valid_(false)
529  {
530  }
531  void add_point(
532  float pt_x, float pt_y, float pt_z, uint8_t pt_intensity,
533  const mrpt::system::TTimeStamp& tim,
534  [[maybe_unused]] const float azimuth,
535  [[maybe_unused]] uint16_t laser_id) override
536  {
537  // Use a cache since it's expected that the same timestamp is
538  // queried several times in a row:
539  if (last_query_tim_ != tim)
540  {
541  last_query_tim_ = tim;
542  vehicle_path_.interpolate(tim, last_query_, last_query_valid_);
543  }
544 
545  if (last_query_valid_)
546  {
547  mrpt::poses::CPose3D global_sensor_pose(
549  global_sensor_pose.composeFrom(last_query_, me_.sensorPose);
550  double gx, gy, gz;
551  global_sensor_pose.composePoint(pt_x, pt_y, pt_z, gx, gy, gz);
552  out_points_.emplace_back(gx, gy, gz, pt_intensity);
553  ++results_stats_.num_correctly_inserted_points;
554  }
555  ++results_stats_.num_points;
556  }
557  };
558 
559  PointCloudStorageWrapper_SE3_Interp my_pc_wrap(
560  *this, vehicle_path, out_points, results_stats);
561  velodyne_scan_to_pointcloud(*this, params, my_pc_wrap);
562 }
563 
565 {
566  x.clear();
567  y.clear();
568  z.clear();
569  intensity.clear();
570  timestamp.clear();
571  azimuth.clear();
572  laser_id.clear();
573  pointsForLaserID.clear();
574 }
576 {
578 
579  deep_clear(x);
580  deep_clear(y);
581  deep_clear(z);
582  deep_clear(intensity);
583  deep_clear(timestamp);
585  deep_clear(laser_id);
586  deep_clear(pointsForLaserID);
587 }
588 
589 void Velo::TPointCloud::reserve(std::size_t n)
590 {
591  x.reserve(n);
592  y.reserve(n);
593  z.reserve(n);
594  intensity.reserve(n);
595  timestamp.reserve(n);
596  azimuth.reserve(n);
597  laser_id.reserve(n);
598  pointsForLaserID.reserve(64); // ring number
599 }
600 
601 // Default ctor. Do NOT move to the .h, that causes build errors.
static void velodyne_scan_to_pointcloud(const Velo &scan, const Velo::TGeneratePointCloudParameters &params, Velo::PointCloudStorageWrapper &out_pc)
A compile-time fixed-size numeric matrix container.
Definition: CMatrixFixed.h:33
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
const double HDR32_FIRING_TOFFSET
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:3879
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
static double VLP16AdjustTimeStamp(int firingblock, int dsr, int firingwithinblock)
[us]
#define ASSERT_BELOW_(__A, __B)
Definition: exceptions.h:149
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)
To be added to 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.
GLenum GLsizei n
Definition: glext.h:5136
bool generatePerPointAzimuth
(Default:false) If true, populate the vector azimuth
mrpt::obs::VelodyneCalibration calibration
The calibration data for the LIDAR device.
STL namespace.
void generatePointCloud(const TGeneratePointCloudParameters &params=TGeneratePointCloudParameters())
Generates the point cloud into the point cloud data fields in CObservationVelodyneScan::point_cloud w...
const float VLP16_DSR_TOFFSET
void serializeTo(mrpt::serialization::CArchive &out) const override
Pure virtual method for writing (serializing) to an abstract archive.
static double HDL32AdjustTimeStamp(int firingblock, int dsr)
[us]
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot/vehicle frame of reference.
static const uint16_t ROTATION_MAX_UNITS
hundredths of degrees
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
Definition: exceptions.h:97
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:40
TPointCloud point_cloud
Optionally, raw data can be converted into a 3D point cloud (local coordinates wrt the sensor...
void generatePointCloudAlongSE3Trajectory(const mrpt::poses::CPose3DInterpolator &vehicle_path, std::vector< mrpt::math::TPointXYZIu8 > &out_points, TGeneratePointCloudSE3Results &results_stats, const TGeneratePointCloudParameters &params=TGeneratePointCloudParameters())
An alternative to generatePointCloud() for cases where the motion of the sensor as it grabs one scan ...
double minRange
The maximum range allowed by the device, in meters (e.g.
std::vector< int16_t > laser_id
Laser ID ("ring number") for each point (0-15 for a VLP-16, etc.)
Lightweight 3D point (float version).
Definition: TPoint3D.h:21
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:572
Auxiliary struct that holds all the relevant geometry information about a 2D scan.
virtual void add_point(float pt_x, float pt_y, float pt_z, uint8_t pt_intensity, const mrpt::system::TTimeStamp &tim, const float azimuth, uint16_t laser_id)=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.
A smart look-up-table (LUT) of sin/cos values for 2D laser scans.
std::vector< PerLaserCalib > laser_corrections
static CSinCosLookUpTableFor2DScans velodyne_sincos_tables
void serializeFrom(mrpt::serialization::CArchive &in, uint8_t serial_version) override
Pure virtual method for reading (deserializing) from an abstract archive.
This namespace contains representation of robot actions and observations.
size_t num_correctly_inserted_points
Number of points for which a valid interpolated SE(3) pose could be determined.
uint16_t header
Block id: UPPER_BANK or LOWER_BANK.
bool generatePerPointTimestamp
(Default:false) If true, populate the vector timestamp
void clear_deep()
Like clear(), but also enforcing freeing memory.
const GLdouble * v
Definition: glext.h:3684
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool generatePointsForLaserID
(Default:false) If true, populate pointsForLaserID
pose_t & interpolate(const mrpt::Clock::time_point &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...
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:60
Virtual base class for "archives": classes abstracting I/O streams.
Definition: CArchive.h:54
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:85
mrpt::vision::TStereoCalibResults out
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:43
static const uint16_t UPPER_BANK
Blocks 0-31.
void deep_clear(CONTAINER &c)
Deep clear for a std vector container.
const float VLP16_BLOCK_TDURATION
virtual void resizeLaserCount([[maybe_unused]] std::size_t n)
GLuint in
Definition: glext.h:7391
uint8_t laser_return_mode
0x37: strongest, 0x38: last, 0x39: dual return
std::vector< std::vector< uint64_t > > pointsForLaserID
The list of point indices (in x,y,z,...) generated for each laserID (ring number).
GLenum GLint GLint y
Definition: glext.h:3542
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.h:146
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt, 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...
GLenum GLsizei GLenum format
Definition: glext.h:3535
Derive from this class to generate pointclouds into custom containers.
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:3542
uint8_t serializeGetVersion() const override
Must return the current versioning number of the object.
const double HDR32_DSR_TOFFSET
bool rightToLeft
Angles storage order: true=counterclockwise; false=clockwise.
static constexpr float DISTANCE_RESOLUTION
meters
GLfloat GLfloat p
Definition: glext.h:6398
GLenum const GLfloat * params
Definition: glext.h:3538
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:43
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
Definition: geometry.cpp:1891
const float VLP16_FIRING_TOFFSET
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:23



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: cb560b230 Wed Nov 13 08:06:48 2019 +0100 at miƩ nov 13 08:15:10 CET 2019