Class CObservationVelodyneScan

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class CObservationVelodyneScan : public mrpt::obs::CObservation

A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LIDAR scanners. A scan comprises one or more “velodyne packets” (refer to Velodyne user manual). Normally, a full 360 degrees sweep is included in one observation object. Note that if a pointcloud is generated inside this class, each point is annotated with per-point information about its exact azimuth and laser_id (ring number), an information that is loss when inserting the observation in a regular mrpt::maps::CPointsMap.

Main data fields:

Dual return mode is supported (see mrpt::hwdrivers::CVelodyneScanner).

Axes convention for point cloud (x,y,z) coordinates:

../../output_staging/generated/doxygen/xml/velodyne_axes.jpg

If it can be assumed that the sensor moves SLOWLY through the environment (i.e. its pose can be approximated to be the same since the beginning to the end of one complete scan) then this observation can be converted / loaded into the following other classes:

Otherwise, the following API exists for accurate reconstruction of the sensor path in SE(3) over time:

Note that this object has two timestamp fields:

Note

New in MRPT 1.4.0

Raw scan fixed parameters

static const int SIZE_BLOCK = 100
static const int RAW_SCAN_SIZE = 3
static const int SCANS_PER_BLOCK = 32
static const int BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE)
static const uint16_t ROTATION_MAX_UNITS = 36000

hundredths of degrees

static constexpr float ROTATION_RESOLUTION = 0.01f

degrees

static constexpr float DISTANCE_MAX = 130.0f

meters

static constexpr float DISTANCE_RESOLUTION = 0.002f

meters

static const uint16_t UPPER_BANK = 0xeeff

Blocks 0-31

static const uint16_t LOWER_BANK = 0xddff

Blocks 32-63

static const int SCANS_PER_FIRING = 16
static const int PACKET_SIZE = 1206
static const int POS_PACKET_SIZE = 512
static const int BLOCKS_PER_PACKET = 12
static const int PACKET_STATUS_SIZE = 4
static const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET)
static const uint8_t RETMODE_STRONGEST = 0x37
static const uint8_t RETMODE_LAST = 0x38
static const uint8_t RETMODE_DUAL = 0x39

Scan data

double minRange = {1.0}

The maximum range allowed by the device, in meters (e.g. 100m). Stored here by the driver while capturing based on the sensor model.

double maxRange = {130.0}
mrpt::poses::CPose3D sensorPose

The 6D pose of the sensor on the robot/vehicle frame of reference

std::vector<TVelodyneRawPacket> scan_packets

The main content of this object: raw data packet from the LIDAR.

See also

point_cloud

mrpt::obs::VelodyneCalibration calibration

The calibration data for the LIDAR device. See mrpt::hwdrivers::CVelodyneScanner and mrpt::obs::VelodyneCalibration for details.

mrpt::system::TTimeStamp originalReceivedTimestamp = {INVALID_TIMESTAMP}

The local computer-based timestamp based on the reception of the message in the computer.

See also

has_satellite_timestamp, CObservation::timestamp in the base class, which should contain the accurate satellite-based UTC timestamp.

bool has_satellite_timestamp = {false}

If true, CObservation::timestamp has been generated from accurate satellite clock. Otherwise, no GPS data is available and timestamps are based on the local computer clock.

TPointCloud point_cloud

Optionally, raw data can be converted into a 3D point cloud (local coordinates wrt the sensor, not the vehicle) with intensity (graylevel) information. See axes convention in mrpt::obs::CObservationVelodyneScan

virtual mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const override

By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accurate UTC timing of readings, this contains the computer-based timestamp of reception, which may be slightly different than timestamp

See also

getTimeStamp()

void generatePointCloud(const TGeneratePointCloudParameters &params = TGeneratePointCloudParameters())

Generates the point cloud into the point cloud data fields in CObservationVelodyneScan::point_cloud where it is stored in local coordinates wrt the sensor (neither the vehicle nor the world). So, this method does not take into account the possible motion of the sensor through the world as it collects LIDAR scans. For high dynamics, see the more costly API generatePointCloudAlongSE3Trajectory()

Note

Points with ranges out of [minRange,maxRange] are discarded; as well, other filters are available in params.

void generatePointCloud(PointCloudStorageWrapper &dest, const TGeneratePointCloudParameters &params = TGeneratePointCloudParameters())
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 (360 deg horiz FOV) cannot be ignored.

Parameters:
  • vehicle_path[in] Timestamped sequence of known poses for the VEHICLE. Recall that the sensor has a relative pose wrt the vehicle according to CObservationVelodyneScan::getSensorPose() & CObservationVelodyneScan::setSensorPose()

  • out_points[out] The generated points, in the same coordinates frame than vehicle_path. Points are APPENDED to the list, so prevous contents are kept.

  • results_stats[out] Stats

  • params[in] Filtering and other parameters

Delayed-load manual control methods.

virtual void unload() const override

Frees the memory of cached point clouds

Public Functions

inline virtual void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override

A general method to retrieve the sensor pose on the robot. Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.

See also

setSensorPose

inline virtual void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override

A general method to change the sensor pose on the robot. Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.

See also

getSensorPose

virtual void getDescriptionAsText(std::ostream &o) const override

Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.

Note

If overried by derived classes, call base CObservation::getDescriptionAsText() first to show common information.

Note

This is the text that appears in RawLogViewer when selecting an object in the dataset

struct laser_return_t

Public Functions

inline uint16_t distance() const
inline uint8_t intensity() const
struct PointCloudStorageWrapper

Derive from this class to generate pointclouds into custom containers.

Public Functions

inline virtual void reserve(std::size_t n)
inline virtual void resizeLaserCount([[maybe_unused]] 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

struct raw_block_t

Raw Velodyne data block. Each block contains data from either the upper or lower laser bank. The device returns three times as many upper bank blocks.

Public Functions

inline uint16_t header() const
inline uint16_t rotation() const

Public Members

laser_return_t laser_returns[SCANS_PER_BLOCK]
struct TGeneratePointCloudParameters

Public Functions

TGeneratePointCloudParameters()

Public Members

double minAzimuth_deg = {.0}

Minimum azimuth, in degrees (Default=0). Points will be generated only the the area of interest [minAzimuth, maxAzimuth]

double maxAzimuth_deg = {360.}

Minimum azimuth, in degrees (Default=360). Points will be generated only the the area of interest [minAzimuth, maxAzimuth]

float minDistance = {1.0f}

Minimum (default=1.0f) and maximum (default: Infinity) distances/ranges for a point to be considered. Points must pass this (application specific) condition and also the minRange/maxRange values in CObservationVelodyneScan (sensor-specific).

float maxDistance = {std::numeric_limits<float>::max()}
float ROI_x_min = {-std::numeric_limits<float>::max()}

The limits of the 3D box (default=infinity) in sensor (not vehicle) local coordinates for the ROI filter

See also

filterByROI

float ROI_x_max = {std::numeric_limits<float>::max()}
float ROI_y_min = {-std::numeric_limits<float>::max()}
float ROI_y_max = {std::numeric_limits<float>::max()}
float ROI_z_min = {-std::numeric_limits<float>::max()}
float ROI_z_max = {std::numeric_limits<float>::max()}
float nROI_x_min = {0}

The limits of the 3D box (default=0) in sensor (not vehicle) local coordinates for the nROI filter

See also

filterBynROI

float nROI_x_max = {0}
float nROI_y_min = {0}
float nROI_y_max = {0}
float nROI_z_min = {0}
float nROI_z_max = {0}
float isolatedPointsFilterDistance = {2.0f}

(Default:2.0 meters) Minimum distance between a point and its two neighbors to be considered an invalid point.

bool filterByROI = {false}

Enable ROI filter (Default:false): add points inside a given 3D box

bool filterBynROI = {false}

Enable nROI filter (Default:false): do NOT add points inside a given 3D box

bool filterOutIsolatedPoints = {false}

(Default:false) Simple filter to remove spurious returns (e.g. Sun reflected on large water extensions)

bool dualKeepStrongest = {true}

(Default:true) In VLP16 dual mode, keep both or just one of the returns.

bool dualKeepLast = {true}
bool generatePerPointTimestamp = {false}

(Default:false) If true, populate the vector timestamp

bool generatePerPointAzimuth = {false}

(Default:false) If true, populate the vector azimuth

bool generatePointsForLaserID = {false}

(Default:false) If true, populate pointsForLaserID

struct TGeneratePointCloudSE3Results

Results for generatePointCloudAlongSE3Trajectory()

Public Members

size_t num_points = {0}

Number of points in the observation

size_t num_correctly_inserted_points = {0}

Number of points for which a valid interpolated SE(3) pose could be determined

struct TPointCloud

See point_cloud and scan_packets

Public Functions

inline std::size_t size() const
void reserve(std::size_t n)
void clear()

Sets all vectors to zero length

void clear_deep()

Like clear(), but also enforcing freeing memory

Public Members

std::vector<float> x
std::vector<float> y
std::vector<float> z
std::vector<uint8_t> intensity

Color [0,255]

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 )

std::vector<int16_t> laser_id

Laser ID (“ring number”) for each point (0-15 for a VLP-16, etc.)

std::vector<std::vector<uint64_t>> pointsForLaserID

The list of point indices (in x,y,z,…) generated for each laserID (ring number). Generated only if generatePointsForLaserID=true in TGeneratePointCloudParameters

struct TVelodynePositionPacket

Payload of one POSITION packet

Public Functions

inline uint32_t gps_timestamp() const
inline uint32_t unused2() const

Public Members

char unused1[198]
char NMEA_GPRMC[72 + 234]

the full $GPRMC message, as received by Velodyne, terminated with “\r\n\0”

struct TVelodyneRawPacket

One unit of data from the scanner (the payload of one UDP DATA packet)

Public Functions

inline uint32_t gps_timestamp() const

Public Members

raw_block_t blocks[BLOCKS_PER_PACKET]
uint8_t laser_return_mode

0x37: strongest, 0x38: last, 0x39: dual return

uint8_t velodyne_model_ID

0x21: HDL-32E, 0x22: VLP-16