22 class CPose3DInterpolator;
119 #pragma pack(push, 1) 188 std::vector<float>
x,
y,
z;
205 inline std::size_t
size()
const {
return x.size(); }
284 float pt_x,
float pt_y,
float pt_z,
uint8_t pt_intensity,
303 const TGeneratePointCloudParameters&
params =
304 TGeneratePointCloudParameters());
308 PointCloudStorageWrapper& dest,
309 const TGeneratePointCloudParameters&
params =
310 TGeneratePointCloudParameters());
337 std::vector<mrpt::math::TPointXYZIu8>& out_points,
338 TGeneratePointCloudSE3Results& results_stats,
339 const TGeneratePointCloudParameters&
params =
340 TGeneratePointCloudParameters());
353 std::ostream& o)
const override;
Results for generatePointCloudAlongSE3Trajectory()
static const int SIZE_BLOCK
size_t num_points
Number of points in the observation.
float ROI_x_min
The limits of the 3D box (default=infinity) in sensor (not vehicle) local coordinates for the ROI fil...
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
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
raw_block_t blocks[BLOCKS_PER_PACKET]
bool filterOutIsolatedPoints
(Default:false) Simple filter to remove spurious returns (e.g.
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).
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.
static const uint8_t RETMODE_LAST
static const float DISTANCE_RESOLUTION
meters
bool generatePerPointAzimuth
(Default:false) If true, populate the vector azimuth
mrpt::obs::VelodyneCalibration calibration
The calibration data for the LIDAR device.
bool has_satellite_timestamp
If true, CObservation::timestamp has been generated from accurate satellite clock.
static const uint8_t RETMODE_DUAL
bool filterByROI
Enable ROI filter (Default:false): add points inside a given 3D box.
void generatePointCloud(const TGeneratePointCloudParameters ¶ms=TGeneratePointCloudParameters())
Generates the point cloud into the point cloud data fields in CObservationVelodyneScan::point_cloud w...
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot/vehicle frame of reference.
TGeneratePointCloudParameters()
char NMEA_GPRMC[72+234]
the full $GPRMC message, as received by Velodyne, terminated with "\r\n\0"
static const uint16_t ROTATION_MAX_UNITS
hundredths of degrees
double minAzimuth_deg
Minimum azimuth, in degrees (Default=0).
double maxAzimuth_deg
Minimum azimuth, in degrees (Default=360).
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...
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.
static const float ROTATION_RESOLUTION
degrees
std::vector< int16_t > laser_id
Laser ID ("ring number") for each point (0-15 for a VLP-16, etc.)
mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const override
By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accura...
static const int POS_PACKET_SIZE
float isolatedPointsFilterDistance
(Default:2.0 meters) Minimum distance between a point and its two neighbors to be considered an inval...
static const float DISTANCE_MAX_UNITS
void reserve(std::size_t n)
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.
static const int SCANS_PER_PACKET
float minDistance
Minimum (default=1.0f) and maximum (default: Infinity) distances/ranges for a point to be considered...
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.
uint16_t header
Block id: UPPER_BANK or LOWER_BANK.
Payload of one POSITION packet.
See point_cloud and scan_packets.
bool generatePerPointTimestamp
(Default:false) If true, populate the vector timestamp
#define MRPT_DECLARE_TTYPENAME_PTR_NAMESPACE(_TYPE, __NS)
void clear_deep()
Like clear(), but also enforcing freeing memory.
virtual void reserve(std::size_t n)
static const int BLOCKS_PER_PACKET
static const int PACKET_SIZE
std::vector< uint8_t > intensity
Color [0,255].
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
bool generatePointsForLaserID
(Default:false) If true, populate pointsForLaserID
laser_return_t laser_returns[SCANS_PER_BLOCK]
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.
uint8_t velodyne_model_ID
0x21: HDL-32E, 0x22: VLP-16
static const uint16_t UPPER_BANK
Blocks 0-31.
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
virtual void resizeLaserCount([[maybe_unused]] std::size_t n)
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).
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
This class stores a time-stamped trajectory in SE(3) (CPose3D poses).
static const int RAW_SCAN_SIZE
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.
bool dualKeepStrongest
(Default:true) In VLP16 dual mode, keep both or just one of the returns.
float nROI_x_min
The limits of the 3D box (default=0) in sensor (not vehicle) local coordinates for the nROI filter...
unsigned __int32 uint32_t
static const float DISTANCE_MAX
meters
static const int BLOCK_DATA_SIZE
GLenum const GLfloat * params
static const int SCANS_PER_BLOCK
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
static const int PACKET_STATUS_SIZE
static const uint8_t RETMODE_STRONGEST
bool filterBynROI
Enable nROI filter (Default:false): do NOT add points inside a given 3D box.