Go to the documentation of this file.
9 #ifndef CObservationVelodyneScan_H
10 #define CObservationVelodyneScan_H
23 class CPose3DInterpolator;
114 #pragma pack(push, 1)
183 std::vector<float>
x,
y,
z;
194 inline size_t size()
const {
return x.size(); }
273 const TGeneratePointCloudParameters&
params =
274 TGeneratePointCloudParameters());
301 std::vector<mrpt::math::TPointXYZIu8>& out_points,
302 TGeneratePointCloudSE3Results& results_stats,
303 const TGeneratePointCloudParameters&
params =
304 TGeneratePointCloudParameters());
317 std::ostream& o)
const override;
static const uint8_t RETMODE_DUAL
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot/vehicle frame of reference.
uint16_t header
Block id: UPPER_BANK or LOWER_BANK.
static const int BLOCK_DATA_SIZE
laser_return_t laser_returns[SCANS_PER_BLOCK]
static const uint16_t UPPER_BANK
Blocks 0-31.
void clear_deep()
Like clear(), but also enforcing freeing memory.
unsigned __int16 uint16_t
mrpt::obs::VelodyneCalibration calibration
The calibration data for the LIDAR device.
bool filterOutIsolatedPoints
(Default:false) Simple filter to remove spurious returns (e.g.
void generatePointCloud(const TGeneratePointCloudParameters ¶ms=TGeneratePointCloudParameters())
Generates the point cloud into the point cloud data fields in CObservationVelodyneScan::point_cloud w...
bool dualKeepStrongest
(Default:true) In VLP16 dual mode, keep both or just one of the returns.
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 ...
One unit of data from the scanner (the payload of one UDP DATA packet)
float minDistance
Minimum (default=1.0f) and maximum (default: Infinity) distances/ranges for a point to be considered.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
double maxAzimuth_deg
Minimum azimuth, in degrees (Default=360).
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
float nROI_x_min
The limits of the 3D box (default=0) in sensor (not vehicle) local coordinates for the nROI filter.
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
bool filterBynROI
Enable nROI filter (Default:false): do NOT add points inside a given 3D box.
This namespace contains representation of robot actions and observations.
This class stores a time-stamped trajectory in SE(3) (CPose3D poses).
static const int SCANS_PER_BLOCK
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
mrpt::system::TTimeStamp originalReceivedTimestamp
The local computer-based timestamp based on the reception of the message in the computer.
TGeneratePointCloudParameters()
static const int SIZE_BLOCK
static const int PACKET_SIZE
uint8_t velodyne_model_ID
0x21: HDL-32E, 0x22: VLP-16
float ROI_x_min
The limits of the 3D box (default=infinity) in sensor (not vehicle) local coordinates for the ROI fil...
size_t num_correctly_inserted_points
Number of points for which a valid interpolated SE(3) pose could be determined.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
#define MRPT_DECLARE_TTYPENAME_PTR_NAMESPACE(_TYPE, __NS)
uint32_t gps_timestamp
us from top of hour
raw_block_t blocks[BLOCKS_PER_PACKET]
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
std::vector< uint8_t > intensity
Color [0,255].
static const float DISTANCE_MAX
meters
bool has_satellite_timestamp
If true, CObservation::timestamp has been generated from accurate satellite clock.
std::vector< mrpt::system::TTimeStamp > timestamp
Timestamp for each point (if generatePerPointTimestamp=true in TGeneratePointCloudParameters),...
size_t num_points
Number of points in the observation.
static const uint16_t ROTATION_MAX_UNITS
hundredths of degrees
double minAzimuth_deg
Minimum azimuth, in degrees (Default=0).
TPointCloud point_cloud
Optionally, raw data can be converted into a 3D point cloud (local coordinates wrt the sensor,...
static const float DISTANCE_RESOLUTION
meters
char NMEA_GPRMC[72+234]
the full $GPRMC message, as received by Velodyne, terminated with "\r\n\0"
std::vector< float > azimuth
Original azimuth of each point (if generatePerPointAzimuth=true, empty otherwise )
static const int SCANS_PER_PACKET
void clear()
Sets all vectors to zero length.
bool generatePerPointTimestamp
(Default:false) If true, populate the vector timestamp
mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const override
By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accura...
static const uint16_t LOWER_BANK
Blocks 32-63.
static const float DISTANCE_MAX_UNITS
static const uint8_t RETMODE_LAST
Payload of one POSITION packet.
static const float ROTATION_RESOLUTION
degrees
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
static const uint8_t RETMODE_STRONGEST
float isolatedPointsFilterDistance
(Default:2.0 meters) Minimum distance between a point and its two neighbors to be considered an inval...
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
uint16_t rotation
0-35999, divide by 100 to get degrees
double minRange
The maximum range allowed by the device, in meters (e.g.
std::vector< TVelodyneRawPacket > scan_packets
The main content of this object: raw data packet from the LIDAR.
Results for generatePointCloudAlongSE3Trajectory()
Declares a class that represents any robot's observation.
static const int RAW_SCAN_SIZE
uint8_t laser_return_mode
0x37: strongest, 0x38: last, 0x39: dual return
bool filterByROI
Enable ROI filter (Default:false): add points inside a given 3D box.
static const int POS_PACKET_SIZE
See point_cloud and scan_packets.
bool generatePerPointAzimuth
(Default:false) If true, populate the vector azimuth
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
static const int PACKET_STATUS_SIZE
unsigned __int32 uint32_t
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
GLenum const GLfloat * params
static const int BLOCKS_PER_PACKET
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |