49 : minAzimuth_deg(0.0),
50 maxAzimuth_deg(360.0),
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()),
65 isolatedPointsFilterDistance(2.0f),
68 filterOutIsolatedPoints(false),
69 dualKeepStrongest(true),
71 generatePerPointTimestamp(false),
72 generatePerPointAzimuth(false)
76 CObservationVelodyneScan::TGeneratePointCloudSE3Results::
77 TGeneratePointCloudSE3Results()
78 : num_points(0), num_correctly_inserted_points(0)
181 o <<
"Homogeneous matrix for the sensor 3D pose, relative to robot base:\n";
186 o <<
"Raw packet count: " <<
scan_packets.size() <<
"\n";
207 virtual void add_point(
208 double pt_x,
double pt_y,
double pt_z,
uint8_t pt_intensity,
231 const int minAzimuth_int =
round(
params.minAzimuth_deg * 100);
232 const int maxAzimuth_int =
round(
params.maxAzimuth_deg * 100);
233 const float realMinDist =
235 const float realMaxDist =
237 const int16_t isolatedPointsFilterDistance_units =
238 params.isolatedPointsFilterDistance /
244 for (
size_t iPkt = 0; iPkt < scan.
scan_packets.size(); iPkt++)
255 (us_pkt_this >= us_pkt0)
256 ? (us_pkt_this - us_pkt0)
257 : (1000000UL * 3600UL + us_pkt_this - us_pkt0);
264 int median_azimuth_diff;
268 const int nBlocksPerAzimuth =
273 std::vector<int> diffs(
284 diffs[i] = localDiff;
290 median_azimuth_diff =
298 if ((num_lasers != 64 &&
306 cerr <<
"[CObservationVelodyneScan] skipping invalid packet: " 308 << block <<
" header value is " 318 const bool block_is_dual_2nd_ranges =
321 ((block & 0x01) != 0));
322 const bool block_is_dual_last_ranges =
325 ((block & 0x01) == 0));
335 static_cast<uint8_t>(dsr + dsr_offset);
339 bool firingWithinBlock =
false;
340 if (num_lasers == 16)
345 firingWithinBlock =
true;
355 if (block_is_dual_2nd_ranges)
360 if (!
params.dualKeepStrongest)
continue;
362 if (block_is_dual_last_ranges && !
params.dualKeepLast)
continue;
369 if (distance < realMinDist || distance > realMaxDist)
continue;
372 if (
params.filterOutIsolatedPoints)
374 bool pass_filter =
true;
382 std::abs(dist_this - dist_prev) >
383 isolatedPointsFilterDistance_units)
391 std::abs(dist_this - dist_next) >
392 isolatedPointsFilterDistance_units)
395 if (!pass_filter)
continue;
400 double timestampadjustment =
402 double blockdsr0 = 0.0;
403 double nextblockdsr0 = 1.0;
413 block / 2, laserId, firingWithinBlock);
421 block, laserId, firingWithinBlock);
443 median_azimuth_diff * ((timestampadjustment - blockdsr0) /
444 (nextblockdsr0 - blockdsr0)));
446 const float azimuth_corrected_f =
447 azimuth_raw_f + azimuthadjustment;
448 const int azimuth_corrected =
449 ((int)
round(azimuth_corrected_f)) %
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))))
467 float xy_distance =
distance * cos_vert_angle;
468 if (vert_offset) xy_distance += vert_offset * sin_vert_angle;
470 const int azimuth_corrected_for_lut =
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];
481 xy_distance * cos_azimuth +
482 horz_offset * sin_azimuth,
483 -(xy_distance * sin_azimuth -
484 horz_offset * cos_azimuth),
485 distance * sin_vert_angle + vert_offset);
487 bool add_point =
true;
494 if (
params.filterBynROI &&
500 if (!add_point)
continue;
506 azimuth_corrected_f);
520 PointCloudStorageWrapper_Inner(
523 : me_(me), params_(
p)
529 double pt_x,
double pt_y,
double pt_z,
uint8_t pt_intensity,
542 const int azimuth_corrected =
551 PointCloudStorageWrapper_Inner my_pc_wrap(*
this,
params);
558 std::vector<mrpt::math::TPointXYZIu8>& out_points,
571 std::vector<mrpt::math::TPointXYZIu8>& out_points_;
575 bool last_query_valid_;
577 PointCloudStorageWrapper_SE3_Interp(
580 std::vector<mrpt::math::TPointXYZIu8>& out_points,
583 vehicle_path_(vehicle_path),
584 out_points_(out_points),
585 results_stats_(results_stats),
587 last_query_valid_(
false)
591 double pt_x,
double pt_y,
double pt_z,
uint8_t pt_intensity,
596 if (last_query_tim_ != tim)
598 last_query_tim_ = tim;
599 vehicle_path_.
interpolate(tim, last_query_, last_query_valid_);
602 if (last_query_valid_)
608 global_sensor_pose.
composePoint(pt_x, pt_y, pt_z, gx, gy, gz);
609 out_points_.push_back(
617 PointCloudStorageWrapper_SE3_Interp my_pc_wrap(
618 *
this, vehicle_path, out_points, results_stats);
634 std::vector<float> d;
638 std::vector<float> d;
642 std::vector<float> d;
646 std::vector<uint8_t> d;
650 std::vector<mrpt::system::TTimeStamp> d;
654 std::vector<float> d;
Results for generatePointCloudAlongSE3Trajectory()
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
size_t num_points
Number of points in the observation.
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...
double verticalOffsetCorrection
raw_block_t blocks[BLOCKS_PER_PACKET]
const float HDR32_FIRING_TOFFSET
CObservationVelodyneScan()
static void velodyne_scan_to_pointcloud(const CObservationVelodyneScan &scan, const CObservationVelodyneScan::TGeneratePointCloudParameters ¶ms, PointCloudStorageWrapper &out_pc)
uint32_t gps_timestamp
us from top of hour
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.
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.
static const uint8_t RETMODE_DUAL
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...
void generatePointCloudAlongSE3Trajectory(const mrpt::poses::CPose3DInterpolator &vehicle_path, std::vector< mrpt::math::TPointXYZIu8 > &out_points, TGeneratePointCloudSE3Results &results_stats, const TGeneratePointCloudParameters ¶ms=defaultPointCloudParams)
An alternative to generatePointCloud() for cases where the motion of the sensor as it grabs one scan ...
mrpt::math::CVectorFloat ccos
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...
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).
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...
mrpt::math::CMatrixDouble44 getHomogeneousMatrixVal() const
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 ¶ms=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.
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.
bool generatePerPointTimestamp
(Default:false) If true, populate the vector timestamp
static const int BLOCKS_PER_PACKET
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
std::vector< uint8_t > intensity
Color [0,255].
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
mrpt::math::CVectorFloat csin
laser_return_t laser_returns[SCANS_PER_BLOCK]
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).
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.
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...
double distanceCorrection
uint8_t laser_return_mode
0x37: strongest, 0x38: last, 0x39: dual return
int round(const T value)
Returns the closer integer (int) to x.
static const float DISTANCE_RESOLUTION
meters
const int SCANS_PER_FIRING
double horizontalOffsetCorrection
void clear()
Sets all vectors to zero length.
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) ...
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.
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
Auxiliary class used to refactor CObservationVelodyneScan::generatePointCloud()
XYZ point (double) + Intensity(u8)
GLenum const GLfloat * params
static const float ROTATION_RESOLUTION
degrees
double VLP16AdjustTimeStamp(int firingblock, int dsr, int firingwithinblock)
[us]
static const int SCANS_PER_BLOCK
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
const float VLP16_FIRING_TOFFSET
virtual ~CObservationVelodyneScan()
virtual void getDescriptionAsText(std::ostream &o) const
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...