40 return originalReceivedTimestamp;
46 out << timestamp << sensorLabel;
47 out << minRange << maxRange << sensorPose;
48 out.WriteAs<uint32_t>(scan_packets.size());
49 if (!scan_packets.empty())
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())
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;
62 out << point_cloud.timestamp << point_cloud.azimuth << point_cloud.laser_id
63 << point_cloud.pointsForLaserID;
74 in >> timestamp >> sensorLabel;
76 in >> minRange >> maxRange >> sensorPose;
80 scan_packets.resize(N);
83 &scan_packets[0],
sizeof(scan_packets[0]) * N);
88 calibration.laser_corrections.resize(N);
91 &calibration.laser_corrections[0],
92 sizeof(calibration.laser_corrections[0]) * N);
95 in >> point_cloud.x >> point_cloud.y >> point_cloud.z >>
96 point_cloud.intensity;
98 in >> has_satellite_timestamp;
100 has_satellite_timestamp =
101 (this->timestamp != this->originalReceivedTimestamp);
103 in >> point_cloud.timestamp >> point_cloud.azimuth >>
104 point_cloud.laser_id >> point_cloud.pointsForLaserID;
116 CObservation::getDescriptionAsText(o);
117 o <<
"Homogeneous matrix for the sensor 3D pose, relative to robot base:\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";
132 int firingblock,
int dsr,
int firingwithinblock)
156 const int minAzimuth_int =
round(
params.minAzimuth_deg * 100);
157 const int maxAzimuth_int =
round(
params.maxAzimuth_deg * 100);
158 const float realMinDist =
160 const float realMaxDist =
162 const auto isolatedPointsFilterDistance_units =
mrpt::round(
174 for (
size_t iPkt = 0; iPkt < scan.
scan_packets.size(); iPkt++)
180 const uint32_t us_pkt0 = scan.
scan_packets[0].gps_timestamp();
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);
193 int median_azimuth_diff;
197 const unsigned int nBlocksPerAzimuth =
200 std::vector<int> diffs(nDiffs);
201 for (
size_t i = 0; i < nDiffs; ++i)
207 diffs[i] = localDiff;
219 if ((num_lasers != 64 &&
224 cerr <<
"[Velo] skipping invalid packet: block " << block
229 const int dsr_offset =
232 const bool block_is_dual_2nd_ranges =
234 ((block & 0x01) != 0));
235 const bool block_is_dual_last_ranges =
237 ((block & 0x01) == 0));
246 const auto rawLaserId =
static_cast<uint8_t
>(dsr + dsr_offset);
247 uint8_t laserId = rawLaserId;
250 bool firingWithinBlock =
false;
251 if (num_lasers == 16)
256 firingWithinBlock =
true;
266 if (block_is_dual_2nd_ranges)
271 if (!
params.dualKeepStrongest)
continue;
273 if (block_is_dual_last_ranges && !
params.dualKeepLast)
continue;
280 if (distance < realMinDist || distance > realMaxDist)
continue;
283 if (
params.filterOutIsolatedPoints)
285 bool pass_filter =
true;
286 const int16_t dist_this =
290 const int16_t dist_prev =
293 std::abs(dist_this - dist_prev) >
294 isolatedPointsFilterDistance_units)
299 const int16_t dist_next =
302 std::abs(dist_this - dist_next) >
303 isolatedPointsFilterDistance_units)
306 if (!pass_filter)
continue;
311 double timestampadjustment =
313 double blockdsr0 = 0.0;
314 double nextblockdsr0 = 1.0;
323 block / 2, laserId, firingWithinBlock);
331 block, laserId, firingWithinBlock);
353 median_azimuth_diff * ((timestampadjustment - blockdsr0) /
354 (nextblockdsr0 - blockdsr0)));
356 const float azimuth_corrected_f =
357 azimuth_raw_f + azimuthadjustment;
358 const int azimuth_corrected =
359 ((int)
round(azimuth_corrected_f)) %
363 if (!((minAzimuth_int < maxAzimuth_int &&
364 azimuth_corrected >= minAzimuth_int &&
365 azimuth_corrected <= maxAzimuth_int) ||
366 (minAzimuth_int > maxAzimuth_int &&
367 (azimuth_corrected <= maxAzimuth_int ||
368 azimuth_corrected >= minAzimuth_int))))
374 const float horz_offset =
376 const float vert_offset =
379 float xy_distance =
distance * cos_vert_angle;
380 if (vert_offset != .0f)
381 xy_distance += vert_offset * sin_vert_angle;
383 const int azimuth_corrected_for_lut =
386 const float cos_azimuth =
387 lut_sincos.
ccos[azimuth_corrected_for_lut];
388 const float sin_azimuth =
389 lut_sincos.
csin[azimuth_corrected_for_lut];
393 xy_distance * cos_azimuth +
394 horz_offset * sin_azimuth,
395 -(xy_distance * sin_azimuth -
396 horz_offset * cos_azimuth),
397 distance * sin_vert_angle + vert_offset);
399 bool add_point =
true;
406 if (
params.filterBynROI &&
412 if (!add_point)
continue;
418 azimuth_corrected_f, laserId);
437 PointCloudStorageWrapper_Inner(
439 : me_(me), params_(p)
445 void resizeLaserCount(std::size_t n)
override 450 void reserve(std::size_t n)
override 455 const std::size_t n_per_ring =
458 v.reserve(n_per_ring);
463 float pt_x,
float pt_y,
float pt_z, uint8_t pt_intensity,
465 uint16_t laser_id)
override 478 const int azimuth_corrected =
481 azimuth_corrected * ROTATION_RESOLUTION);
489 PointCloudStorageWrapper_Inner my_pc_wrap(*
this,
params);
492 generatePointCloud(my_pc_wrap,
params);
497 std::vector<mrpt::math::TPointXYZIu8>& out_points,
505 std::vector<mrpt::math::TPointXYZIu8>& out_points_;
509 bool last_query_valid_;
511 void reserve(std::size_t n)
override 513 out_points_.reserve(out_points_.size() + n);
516 PointCloudStorageWrapper_SE3_Interp(
518 std::vector<mrpt::math::TPointXYZIu8>& out_points,
521 vehicle_path_(vehicle_path),
522 out_points_(out_points),
523 results_stats_(results_stats),
525 last_query_valid_(
false)
529 float pt_x,
float pt_y,
float pt_z, uint8_t pt_intensity,
531 [[maybe_unused]]
const float azimuth,
532 [[maybe_unused]] uint16_t laser_id)
override 536 if (last_query_tim_ != tim)
538 last_query_tim_ = tim;
539 vehicle_path_.
interpolate(tim, last_query_, last_query_valid_);
542 if (last_query_valid_)
548 global_sensor_pose.
composePoint(pt_x, pt_y, pt_z, gx, gy, gz);
549 out_points_.emplace_back(gx, gy, gz, pt_intensity);
556 PointCloudStorageWrapper_SE3_Interp my_pc_wrap(
557 *
this, vehicle_path, out_points, results_stats);
570 pointsForLaserID.clear();
591 intensity.reserve(n);
592 timestamp.reserve(n);
595 pointsForLaserID.reserve(64);
static void velodyne_scan_to_pointcloud(const Velo &scan, const Velo::TGeneratePointCloudParameters ¶ms, Velo::PointCloudStorageWrapper &out_pc)
Results for generatePointCloudAlongSE3Trajectory()
size_t num_points
Number of points in the observation.
A compile-time fixed-size numeric matrix container.
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...
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
double verticalOffsetCorrection
raw_block_t blocks[BLOCKS_PER_PACKET]
#define THROW_EXCEPTION(msg)
std::string std::string format(std::string_view fmt, ARGS &&... args)
static double VLP16AdjustTimeStamp(int firingblock, int dsr, int firingwithinblock)
[us]
#define ASSERT_BELOW_(__A, __B)
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.
bool generatePerPointAzimuth
(Default:false) If true, populate the vector azimuth
mrpt::obs::VelodyneCalibration calibration
The calibration data for the LIDAR device.
mrpt::vision::TStereoCalibParams params
static const uint8_t RETMODE_DUAL
static const int SCANS_PER_FIRING
void generatePointCloud(const TGeneratePointCloudParameters ¶ms=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.
TGeneratePointCloudParameters()
static const uint16_t ROTATION_MAX_UNITS
hundredths of degrees
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
mrpt::math::CVectorFloat ccos
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
TPointCloud point_cloud
Optionally, raw data can be converted into a 3D point cloud (local coordinates wrt the sensor...
float d2f(const double d)
shortcut for static_cast<float>(double)
void generatePointCloudAlongSE3Trajectory(const mrpt::poses::CPose3DInterpolator &vehicle_path, std::vector< mrpt::math::TPointXYZIu8 > &out_points, TGeneratePointCloudSE3Results &results_stats, const TGeneratePointCloudParameters ¶ms=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.)
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...
Auxiliary struct that holds all the relevant geometry information about a 2D scan.
void reserve(std::size_t n)
uint8_t intensity() const
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.
void clear()
Sets all vectors to zero length.
size_t num_correctly_inserted_points
Number of points for which a valid interpolated SE(3) pose could be determined.
bool generatePerPointTimestamp
(Default:false) If true, populate the vector timestamp
void clear_deep()
Like clear(), but also enforcing freeing memory.
virtual void reserve(std::size_t n)
static const int BLOCKS_PER_PACKET
std::vector< uint8_t > intensity
Color [0,255].
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.
mrpt::math::CVectorFloat csin
laser_return_t laser_returns[SCANS_PER_BLOCK]
Virtual base class for "archives": classes abstracting I/O streams.
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).
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's observation.
static const uint16_t UPPER_BANK
Blocks 0-31.
void deep_clear(CONTAINER &c)
Deep clear for a std vector container.
uint32_t gps_timestamp() const
const float VLP16_BLOCK_TDURATION
double distanceCorrection
uint16_t distance() const
virtual void resizeLaserCount([[maybe_unused]] std::size_t n)
size_t ReadBuffer(void *Buffer, size_t Count)
Reads a block of bytes from the stream into Buffer.
uint8_t laser_return_mode
0x37: strongest, 0x38: last, 0x39: dual return
double horizontalOffsetCorrection
std::vector< std::vector< uint64_t > > pointsForLaserID
The list of point indices (in x,y,z,...) generated for each laserID (ring number).
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) ...
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...
Derive from this class to generate pointclouds into custom containers.
std::vector< TVelodyneRawPacket > scan_packets
The main content of this object: raw data packet from the LIDAR.
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
static const int SCANS_PER_BLOCK
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
uint16_t rotation() const
const float VLP16_FIRING_TOFFSET
int round(const T value)
Returns the closer integer (int) to x.