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 Velo::ROTATION_RESOLUTION = 0.01f; /**< degrees */
32 const float Velo::DISTANCE_MAX = 130.0f; /**< meters */
33 const float Velo::DISTANCE_RESOLUTION = 0.002f; /**< meters */
34 const float Velo::DISTANCE_MAX_UNITS =
35  (Velo::DISTANCE_MAX / Velo::DISTANCE_RESOLUTION + 1.0f);
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 double HDR32_DSR_TOFFSET = 1.152; // [us]
42 const double HDR32_FIRING_TOFFSET = 46.08; // [us]
43 
44 mrpt::system::TTimeStamp Velo::getOriginalReceivedTimeStamp() const
45 {
46  return originalReceivedTimestamp;
47 }
48 
49 uint8_t Velo::serializeGetVersion() const { return 2; }
51 {
52  out << timestamp << sensorLabel;
53  out << minRange << maxRange << sensorPose;
54  out.WriteAs<uint32_t>(scan_packets.size());
55  if (!scan_packets.empty())
56  out.WriteBuffer(
57  &scan_packets[0], sizeof(scan_packets[0]) * scan_packets.size());
58  out.WriteAs<uint32_t>(calibration.laser_corrections.size());
59  if (!calibration.laser_corrections.empty())
60  out.WriteBuffer(
61  &calibration.laser_corrections[0],
62  sizeof(calibration.laser_corrections[0]) *
63  calibration.laser_corrections.size());
64  out << point_cloud.x << point_cloud.y << point_cloud.z
65  << point_cloud.intensity;
66  out << has_satellite_timestamp; // v1
67  // v2:
68  out << point_cloud.timestamp << point_cloud.azimuth << point_cloud.laser_id
69  << point_cloud.pointsForLaserID;
70 }
71 
73 {
74  switch (version)
75  {
76  case 0:
77  case 1:
78  case 2:
79  {
80  in >> timestamp >> sensorLabel;
81 
82  in >> minRange >> maxRange >> sensorPose;
83  {
84  uint32_t N;
85  in >> N;
86  scan_packets.resize(N);
87  if (N)
88  in.ReadBuffer(
89  &scan_packets[0], sizeof(scan_packets[0]) * N);
90  }
91  {
92  uint32_t N;
93  in >> N;
94  calibration.laser_corrections.resize(N);
95  if (N)
96  in.ReadBuffer(
97  &calibration.laser_corrections[0],
98  sizeof(calibration.laser_corrections[0]) * N);
99  }
100  point_cloud.clear();
101  in >> point_cloud.x >> point_cloud.y >> point_cloud.z >>
102  point_cloud.intensity;
103  if (version >= 1)
104  in >> has_satellite_timestamp;
105  else
106  has_satellite_timestamp =
107  (this->timestamp != this->originalReceivedTimestamp);
108  if (version >= 2)
109  in >> point_cloud.timestamp >> point_cloud.azimuth >>
110  point_cloud.laser_id >> point_cloud.pointsForLaserID;
111  }
112  break;
113  default:
115  };
116 
117  // m_cachedMap.clear();
118 }
119 
120 void Velo::getDescriptionAsText(std::ostream& o) const
121 {
122  CObservation::getDescriptionAsText(o);
123  o << "Homogeneous matrix for the sensor 3D pose, relative to robot base:\n";
124  o << sensorPose.getHomogeneousMatrixVal<mrpt::math::CMatrixDouble44>()
125  << "\n"
126  << sensorPose << endl;
127  o << format("Sensor min/max range: %.02f / %.02f m\n", minRange, maxRange);
128  o << "Raw packet count: " << scan_packets.size() << "\n";
129 }
130 
131 /** [us] */
132 static double HDL32AdjustTimeStamp(int firingblock, int dsr)
133 {
134  return (firingblock * HDR32_FIRING_TOFFSET) + (dsr * HDR32_DSR_TOFFSET);
135 }
136 /** [us] */
137 static double VLP16AdjustTimeStamp(
138  int firingblock, int dsr, int firingwithinblock)
139 {
140  return (firingblock * VLP16_BLOCK_TDURATION) + (dsr * VLP16_DSR_TOFFSET) +
141  (firingwithinblock * VLP16_FIRING_TOFFSET);
142 }
143 
145  const Velo& scan, const Velo::TGeneratePointCloudParameters& params,
147 {
148  // Initially based on code from ROS velodyne & from
149  // vtkVelodyneHDLReader::vtkInternal::ProcessHDLPacket().
150  using mrpt::round;
151 
152  // Access to sin/cos table:
153  mrpt::obs::T2DScanProperties scan_props;
154  scan_props.aperture = 2 * M_PI;
155  scan_props.nRays = Velo::ROTATION_MAX_UNITS;
156  scan_props.rightToLeft = true;
157  // The LUT contains sin/cos values for angles in this order: [180deg ... 0
158  // deg ... -180 deg]
161 
162  const int minAzimuth_int = round(params.minAzimuth_deg * 100);
163  const int maxAzimuth_int = round(params.maxAzimuth_deg * 100);
164  const float realMinDist =
165  std::max(static_cast<float>(scan.minRange), params.minDistance);
166  const float realMaxDist =
167  std::min(params.maxDistance, static_cast<float>(scan.maxRange));
168  const auto isolatedPointsFilterDistance_units = mrpt::round(
169  params.isolatedPointsFilterDistance / Velo::DISTANCE_RESOLUTION);
170 
171  // This is: 16,32,64 depending on the LIDAR model
172  const size_t num_lasers = scan.calibration.laser_corrections.size();
173 
174  out_pc.resizeLaserCount(num_lasers);
175  out_pc.reserve(
176  Velo::SCANS_PER_BLOCK * scan.scan_packets.size() *
178  16);
179 
180  for (size_t iPkt = 0; iPkt < scan.scan_packets.size(); iPkt++)
181  {
182  const Velo::TVelodyneRawPacket* raw = &scan.scan_packets[iPkt];
183 
184  mrpt::system::TTimeStamp pkt_tim; // Find out timestamp of this pkt
185  {
186  const uint32_t us_pkt0 = scan.scan_packets[0].gps_timestamp;
187  const uint32_t us_pkt_this = raw->gps_timestamp;
188  // Handle the case of time counter reset by new hour 00:00:00
189  const uint32_t us_ellapsed =
190  (us_pkt_this >= us_pkt0)
191  ? (us_pkt_this - us_pkt0)
192  : (1000000UL * 3600UL + us_pkt_this - us_pkt0);
193  pkt_tim =
194  mrpt::system::timestampAdd(scan.timestamp, us_ellapsed * 1e-6);
195  }
196 
197  // Take the median rotational speed as a good value for interpolating
198  // the missing azimuths:
199  int median_azimuth_diff;
200  {
201  // In dual return, the azimuth rate is actually twice this
202  // estimation:
203  const unsigned int nBlocksPerAzimuth =
204  (raw->laser_return_mode == Velo::RETMODE_DUAL) ? 2 : 1;
205  const size_t nDiffs = Velo::BLOCKS_PER_PACKET - nBlocksPerAzimuth;
206  std::vector<int> diffs(nDiffs);
207  for (size_t i = 0; i < nDiffs; ++i)
208  {
209  int localDiff = (Velo::ROTATION_MAX_UNITS +
210  raw->blocks[i + nBlocksPerAzimuth].rotation -
211  raw->blocks[i].rotation) %
213  diffs[i] = localDiff;
214  }
215  std::nth_element(
216  diffs.begin(), diffs.begin() + Velo::BLOCKS_PER_PACKET / 2,
217  diffs.end()); // Calc median
218  median_azimuth_diff = diffs[Velo::BLOCKS_PER_PACKET / 2];
219  }
220 
221  // Firings per packet
222  for (int block = 0; block < Velo::BLOCKS_PER_PACKET; block++)
223  {
224  // ignore packets with mangled or otherwise different contents
225  if ((num_lasers != 64 &&
226  Velo::UPPER_BANK != raw->blocks[block].header) ||
227  (raw->blocks[block].header != Velo::UPPER_BANK &&
228  raw->blocks[block].header != Velo::LOWER_BANK))
229  {
230  cerr << "[Velo] skipping invalid packet: block " << block
231  << " header value is " << raw->blocks[block].header;
232  continue;
233  }
234 
235  const int dsr_offset =
236  (raw->blocks[block].header == Velo::LOWER_BANK) ? 32 : 0;
237  const auto azimuth_raw_f =
238  static_cast<float>(raw->blocks[block].rotation);
239  const bool block_is_dual_2nd_ranges =
241  ((block & 0x01) != 0));
242  const bool block_is_dual_last_ranges =
244  ((block & 0x01) == 0));
245 
246  for (int dsr = 0, k = 0; dsr < Velo::SCANS_PER_FIRING; dsr++, k++)
247  {
248  if (!raw->blocks[block]
249  .laser_returns[k]
250  .distance) // Invalid return?
251  continue;
252 
253  const auto rawLaserId = static_cast<uint8_t>(dsr + dsr_offset);
254  uint8_t laserId = rawLaserId;
255 
256  // Detect VLP-16 data and adjust laser id if necessary
257  bool firingWithinBlock = false;
258  if (num_lasers == 16)
259  {
260  if (laserId >= 16)
261  {
262  laserId -= 16;
263  firingWithinBlock = true;
264  }
265  }
266 
267  ASSERT_BELOW_(laserId, num_lasers);
269  scan.calibration.laser_corrections[laserId];
270 
271  // In dual return, if the distance is equal in both ranges,
272  // ignore one of them:
273  if (block_is_dual_2nd_ranges)
274  {
275  if (raw->blocks[block].laser_returns[k].distance ==
276  raw->blocks[block - 1].laser_returns[k].distance)
277  continue; // duplicated point
278  if (!params.dualKeepStrongest) continue;
279  }
280  if (block_is_dual_last_ranges && !params.dualKeepLast) continue;
281 
282  // Return distance:
283  const float distance =
284  raw->blocks[block].laser_returns[k].distance *
286  calib.distanceCorrection;
287  if (distance < realMinDist || distance > realMaxDist) continue;
288 
289  // Isolated points filtering:
290  if (params.filterOutIsolatedPoints)
291  {
292  bool pass_filter = true;
293  const int16_t dist_this =
294  raw->blocks[block].laser_returns[k].distance;
295  if (k > 0)
296  {
297  const int16_t dist_prev =
298  raw->blocks[block].laser_returns[k - 1].distance;
299  if (!dist_prev ||
300  std::abs(dist_this - dist_prev) >
301  isolatedPointsFilterDistance_units)
302  pass_filter = false;
303  }
304  if (k < (Velo::SCANS_PER_FIRING - 1))
305  {
306  const int16_t dist_next =
307  raw->blocks[block].laser_returns[k + 1].distance;
308  if (!dist_next ||
309  std::abs(dist_this - dist_next) >
310  isolatedPointsFilterDistance_units)
311  pass_filter = false;
312  }
313  if (!pass_filter) continue; // Filter out this point
314  }
315 
316  // Azimuth correction: correct for the laser rotation as a
317  // function of timing during the firings
318  double timestampadjustment =
319  0.0; // [us] since beginning of scan
320  double blockdsr0 = 0.0;
321  double nextblockdsr0 = 1.0;
322  switch (num_lasers)
323  {
324  // VLP-16
325  case 16:
326  {
328  {
329  timestampadjustment = VLP16AdjustTimeStamp(
330  block / 2, laserId, firingWithinBlock);
331  nextblockdsr0 =
332  VLP16AdjustTimeStamp(block / 2 + 1, 0, 0);
333  blockdsr0 = VLP16AdjustTimeStamp(block / 2, 0, 0);
334  }
335  else
336  {
337  timestampadjustment = VLP16AdjustTimeStamp(
338  block, laserId, firingWithinBlock);
339  nextblockdsr0 =
340  VLP16AdjustTimeStamp(block + 1, 0, 0);
341  blockdsr0 = VLP16AdjustTimeStamp(block, 0, 0);
342  }
343  }
344  break;
345  // HDL-32:
346  case 32:
347  timestampadjustment = HDL32AdjustTimeStamp(block, dsr);
348  nextblockdsr0 = HDL32AdjustTimeStamp(block + 1, 0);
349  blockdsr0 = HDL32AdjustTimeStamp(block, 0);
350  break;
351  case 64:
352  break;
353  default:
354  {
355  THROW_EXCEPTION("Error: unhandled LIDAR model!");
356  }
357  };
358 
359  const int azimuthadjustment = mrpt::round(
360  median_azimuth_diff * ((timestampadjustment - blockdsr0) /
361  (nextblockdsr0 - blockdsr0)));
362 
363  const float azimuth_corrected_f =
364  azimuth_raw_f + azimuthadjustment;
365  const int azimuth_corrected =
366  ((int)round(azimuth_corrected_f)) %
368 
369  // Filter by azimuth:
370  if (!((minAzimuth_int < maxAzimuth_int &&
371  azimuth_corrected >= minAzimuth_int &&
372  azimuth_corrected <= maxAzimuth_int) ||
373  (minAzimuth_int > maxAzimuth_int &&
374  (azimuth_corrected <= maxAzimuth_int ||
375  azimuth_corrected >= minAzimuth_int))))
376  continue;
377 
378  // Vertical axis mis-alignment calibration:
379  const float cos_vert_angle =
380  static_cast<float>(calib.cosVertCorrection);
381  const float sin_vert_angle =
382  static_cast<float>(calib.sinVertCorrection);
383  const float horz_offset =
384  static_cast<float>(calib.horizontalOffsetCorrection);
385  const float vert_offset =
386  static_cast<float>(calib.verticalOffsetCorrection);
387 
388  float xy_distance = distance * cos_vert_angle;
389  if (vert_offset != .0f)
390  xy_distance += vert_offset * sin_vert_angle;
391 
392  const int azimuth_corrected_for_lut =
393  (azimuth_corrected + (Velo::ROTATION_MAX_UNITS / 2)) %
395  const float cos_azimuth =
396  lut_sincos.ccos[azimuth_corrected_for_lut];
397  const float sin_azimuth =
398  lut_sincos.csin[azimuth_corrected_for_lut];
399 
400  // Compute raw position
401  const mrpt::math::TPoint3Df pt(
402  xy_distance * cos_azimuth +
403  horz_offset * sin_azimuth, // MRPT +X = Velodyne +Y
404  -(xy_distance * sin_azimuth -
405  horz_offset * cos_azimuth), // MRPT +Y = Velodyne -X
406  distance * sin_vert_angle + vert_offset);
407 
408  bool add_point = true;
409  if (params.filterByROI &&
410  (pt.x > params.ROI_x_max || pt.x < params.ROI_x_min ||
411  pt.y > params.ROI_y_max || pt.y < params.ROI_y_min ||
412  pt.z > params.ROI_z_max || pt.z < params.ROI_z_min))
413  add_point = false;
414 
415  if (params.filterBynROI &&
416  (pt.x <= params.nROI_x_max && pt.x >= params.nROI_x_min &&
417  pt.y <= params.nROI_y_max && pt.y >= params.nROI_y_min &&
418  pt.z <= params.nROI_z_max && pt.z >= params.nROI_z_min))
419  add_point = false;
420 
421  if (!add_point) continue;
422 
423  // Insert point:
424  out_pc.add_point(
425  pt.x, pt.y, pt.z,
426  raw->blocks[block].laser_returns[k].intensity, pkt_tim,
427  azimuth_corrected_f, laserId);
428 
429  } // end for k,dsr=[0,31]
430  } // end for each block [0,11]
431  } // end for each data packet
432 }
433 
436 {
437  velodyne_scan_to_pointcloud(*this, params, dest);
438 }
439 
441 {
442  struct PointCloudStorageWrapper_Inner : public PointCloudStorageWrapper
443  {
444  Velo& me_;
445  const TGeneratePointCloudParameters& params_;
446  PointCloudStorageWrapper_Inner(
448  : me_(me), params_(p)
449  {
450  // Reset point cloud:
451  me_.point_cloud.clear();
452  }
453 
454  void resizeLaserCount(std::size_t n) override
455  {
456  me_.point_cloud.pointsForLaserID.resize(n);
457  }
458 
459  void reserve(std::size_t n) override
460  {
461  me_.point_cloud.reserve(n);
462  if (!me_.point_cloud.pointsForLaserID.empty())
463  {
464  const std::size_t n_per_ring =
465  100 + n / (me_.point_cloud.pointsForLaserID.size());
466  for (auto& v : me_.point_cloud.pointsForLaserID)
467  v.reserve(n_per_ring);
468  }
469  }
470 
471  void add_point(
472  float pt_x, float pt_y, float pt_z, uint8_t pt_intensity,
473  const mrpt::system::TTimeStamp& tim, const float azimuth,
474  uint16_t laser_id) override
475  {
476  const auto idx = me_.point_cloud.x.size();
477  me_.point_cloud.x.push_back(pt_x);
478  me_.point_cloud.y.push_back(pt_y);
479  me_.point_cloud.z.push_back(pt_z);
480  me_.point_cloud.intensity.push_back(pt_intensity);
481  if (params_.generatePerPointTimestamp)
482  {
483  me_.point_cloud.timestamp.push_back(tim);
484  }
485  if (params_.generatePerPointAzimuth)
486  {
487  const int azimuth_corrected =
489  me_.point_cloud.azimuth.push_back(
490  azimuth_corrected * ROTATION_RESOLUTION);
491  }
492  me_.point_cloud.laser_id.push_back(laser_id);
493  if (params_.generatePointsForLaserID)
494  me_.point_cloud.pointsForLaserID[laser_id].push_back(idx);
495  }
496  };
497 
498  PointCloudStorageWrapper_Inner my_pc_wrap(*this, params);
499  point_cloud.clear();
500 
501  generatePointCloud(my_pc_wrap, params);
502 }
503 
505  const mrpt::poses::CPose3DInterpolator& vehicle_path,
506  std::vector<mrpt::math::TPointXYZIu8>& out_points,
507  TGeneratePointCloudSE3Results& results_stats,
509 {
510  struct PointCloudStorageWrapper_SE3_Interp : public PointCloudStorageWrapper
511  {
512  Velo& me_;
513  const mrpt::poses::CPose3DInterpolator& vehicle_path_;
514  std::vector<mrpt::math::TPointXYZIu8>& out_points_;
515  TGeneratePointCloudSE3Results& results_stats_;
516  mrpt::system::TTimeStamp last_query_tim_;
517  mrpt::poses::CPose3D last_query_;
518  bool last_query_valid_;
519 
520  void reserve(std::size_t n) override
521  {
522  out_points_.reserve(out_points_.size() + n);
523  }
524 
525  PointCloudStorageWrapper_SE3_Interp(
526  Velo& me, const mrpt::poses::CPose3DInterpolator& vehicle_path,
527  std::vector<mrpt::math::TPointXYZIu8>& out_points,
528  TGeneratePointCloudSE3Results& results_stats)
529  : me_(me),
530  vehicle_path_(vehicle_path),
531  out_points_(out_points),
532  results_stats_(results_stats),
533  last_query_tim_(INVALID_TIMESTAMP),
534  last_query_valid_(false)
535  {
536  }
537  void add_point(
538  float pt_x, float pt_y, float pt_z, uint8_t pt_intensity,
539  const mrpt::system::TTimeStamp& tim,
540  [[maybe_unused]] const float azimuth,
541  [[maybe_unused]] uint16_t laser_id) override
542  {
543  // Use a cache since it's expected that the same timestamp is
544  // queried several times in a row:
545  if (last_query_tim_ != tim)
546  {
547  last_query_tim_ = tim;
548  vehicle_path_.interpolate(tim, last_query_, last_query_valid_);
549  }
550 
551  if (last_query_valid_)
552  {
553  mrpt::poses::CPose3D global_sensor_pose(
555  global_sensor_pose.composeFrom(last_query_, me_.sensorPose);
556  double gx, gy, gz;
557  global_sensor_pose.composePoint(pt_x, pt_y, pt_z, gx, gy, gz);
558  out_points_.emplace_back(gx, gy, gz, pt_intensity);
559  ++results_stats_.num_correctly_inserted_points;
560  }
561  ++results_stats_.num_points;
562  }
563  };
564 
565  PointCloudStorageWrapper_SE3_Interp my_pc_wrap(
566  *this, vehicle_path, out_points, results_stats);
567  velodyne_scan_to_pointcloud(*this, params, my_pc_wrap);
568 }
569 
571 {
572  x.clear();
573  y.clear();
574  z.clear();
575  intensity.clear();
576  timestamp.clear();
577  azimuth.clear();
578  laser_id.clear();
579  pointsForLaserID.clear();
580 }
582 {
584 
585  deep_clear(x);
586  deep_clear(y);
587  deep_clear(z);
588  deep_clear(intensity);
589  deep_clear(timestamp);
591  deep_clear(laser_id);
592  deep_clear(pointsForLaserID);
593 }
594 
595 void Velo::TPointCloud::reserve(std::size_t n)
596 {
597  x.reserve(n);
598  y.reserve(n);
599  z.reserve(n);
600  intensity.reserve(n);
601  timestamp.reserve(n);
602  azimuth.reserve(n);
603  laser_id.reserve(n);
604  pointsForLaserID.reserve(64); // ring number
605 }
606 
607 // 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
#define min(a, b)
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 __int16 uint16_t
Definition: rptypes.h:47
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixed< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixed< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixed< 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:367
#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.
static const float DISTANCE_RESOLUTION
meters
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 WriteAs(const TYPE_FROM_ACTUAL &value)
Definition: CArchive.h:158
void WriteBuffer(const void *Buffer, size_t Count)
Writes a block of bytes to the stream from Buffer.
Definition: CArchive.cpp:49
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
unsigned char uint8_t
Definition: rptypes.h:44
#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
__int16 int16_t
Definition: rptypes.h:46
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:562
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:84
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
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.
unsigned __int32 uint32_t
Definition: rptypes.h:50
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: 1de0e027c Sat Sep 14 16:15:22 2019 +0200 at sáb sep 14 16:20:14 CEST 2019