Main MRPT website > C++ reference for MRPT 1.4.0
List of all members | Classes | Public Member Functions | Protected Member Functions
mrpt::obs::CObservationVelodyneScan Class Reference

Detailed Description

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).

Main data fields:


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

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
See also
CObservation, CPointsMap, CVelodyneScanner

Definition at line 56 of file CObservationVelodyneScan.h.

#include <mrpt/obs/CObservationVelodyneScan.h>

Inheritance diagram for mrpt::obs::CObservationVelodyneScan:
Inheritance graph

Classes

struct  laser_return_t
 
struct  raw_block_t
 Raw Velodyne data block. More...
 
struct  TGeneratePointCloudParameters
 
struct  TGeneratePointCloudSE3Results
 Results for generatePointCloudAlongSE3Trajectory() More...
 
struct  TPointCloud
 See point_cloud and scan_packets. More...
 
struct  TVelodynePositionPacket
 Payload of one POSITION packet. More...
 
struct  TVelodyneRawPacket
 One unit of data from the scanner (the payload of one UDP DATA packet) More...
 

Public Member Functions

 CObservationVelodyneScan ()
 
virtual ~CObservationVelodyneScan ()
 
void getSensorPose (mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
 A general method to retrieve the sensor pose on the robot.
 
void setSensorPose (const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
 A general method to change the sensor pose on the robot.
 
void getDescriptionAsText (std::ostream &o) const MRPT_OVERRIDE
 Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
 
template<class METRICMAP >
bool insertObservationInto (METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose=NULL) const
 This method is equivalent to:
 
void getSensorPose (mrpt::math::TPose3D &out_sensorPose) const
 A general method to retrieve the sensor pose on the robot.
 
void setSensorPose (const mrpt::math::TPose3D &newSensorPose)
 A general method to change the sensor pose on the robot.
 
Delayed-load manual control methods.
virtual void load () const
 Makes sure all images and other fields which may be externally stored are loaded in memory.
 
virtual void unload ()
 Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).
 

Static Public Attributes

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 float ROTATION_RESOLUTION
 
static const uint16_t ROTATION_MAX_UNITS = 36000
 hundredths of degrees
 
static const float DISTANCE_MAX
 meters
 
static const float DISTANCE_RESOLUTION
 meters
 
static const float DISTANCE_MAX_UNITS
 
static const uint16_t UPPER_BANK = 0xeeff
 Blocks 0-31.
 
static const uint16_t LOWER_BANK = 0xddff
 Blocks 32-63.
 
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
 
RTTI stuff <br>
static const mrpt::utils::TRuntimeClassId classCObservation
 

Protected Member Functions

void swap (CObservation &o)
 Swap with another observation, ONLY the data defined here in the base class CObservation. It's protected since it'll be only called from child classes that should know what else to swap appart from these common data.
 
CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const MRPT_OVERRIDE
 
void readFromStream (mrpt::utils::CStream &in, int version) MRPT_OVERRIDE
 

RTTI stuff <br>

typedef CObservationVelodyneScanPtr SmartPtr
 
static mrpt::utils::CLASSINIT _init_CObservationVelodyneScan
 
static mrpt::utils::TRuntimeClassId classCObservationVelodyneScan
 
static const mrpt::utils::TRuntimeClassIdclassinfo
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const MRPT_OVERRIDE
 
virtual mrpt::utils::CObjectduplicate () const MRPT_OVERRIDE
 
static mrpt::utils::CObjectCreateObject ()
 
static CObservationVelodyneScanPtr Create ()
 

Related to conversion to 3D point cloud

static const TGeneratePointCloudParameters defaultPointCloudParams
 
void generatePointCloud (const TGeneratePointCloudParameters &params=defaultPointCloudParams)
 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).
 
void generatePointCloudAlongSE3Trajectory (const mrpt::poses::CPose3DInterpolator &vehicle_path, std::vector< mrpt::math::TPointXYZIu8 > &out_points, TGeneratePointCloudSE3Results &results_stats, const TGeneratePointCloudParameters &params=defaultPointCloudParams)
 An alternative to generatePointCloud() for cases where the motion of the sensor as it grabs one scan (360 deg horiz FOV) cannot be ignored.
 

Scan data

double minRange
 
double maxRange
 The maximum range allowed by the device, in meters (e.g. 100m). Stored here by the driver while capturing based on the sensor model.
 
mrpt::poses::CPose3D sensorPose
 The 6D pose of the sensor on the robot/vehicle frame of reference.
 
std::vector< TVelodyneRawPacketscan_packets
 The main content of this object: raw data packet from the LIDAR.
 
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
 The local computer-based timestamp based on the reception of the message in the computer.
 
bool has_satellite_timestamp
 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.
 
mrpt::system::TTimeStamp getOriginalReceivedTimeStamp () const MRPT_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.
 

Data common to any observation

mrpt::system::TTimeStamp timestamp
 The associated UTC time-stamp. Where available, this should contain the accurate satellite-based timestamp of the sensor reading.
 
std::string sensorLabel
 An arbitrary label that can be used to identify the sensor.
 
mrpt::system::TTimeStamp getTimeStamp () const
 Returns CObservation::timestamp for all kind of observations.
 

Member Typedef Documentation

◆ SmartPtr

A typedef for the associated smart pointer

Definition at line 59 of file CObservationVelodyneScan.h.

Constructor & Destructor Documentation

◆ CObservationVelodyneScan()

mrpt::obs::CObservationVelodyneScan::CObservationVelodyneScan ( )

◆ ~CObservationVelodyneScan()

virtual mrpt::obs::CObservationVelodyneScan::~CObservationVelodyneScan ( )
virtual

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId * mrpt::obs::CObservationVelodyneScan::_GetBaseClass ( )
staticprotected

◆ Create()

static CObservationVelodyneScanPtr mrpt::obs::CObservationVelodyneScan::Create ( )
static

◆ CreateObject()

static mrpt::utils::CObject * mrpt::obs::CObservationVelodyneScan::CreateObject ( )
static

◆ duplicate()

virtual mrpt::utils::CObject * mrpt::obs::CObservationVelodyneScan::duplicate ( ) const
virtual

◆ generatePointCloud()

void mrpt::obs::CObservationVelodyneScan::generatePointCloud ( const TGeneratePointCloudParameters params = defaultPointCloudParams)

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.
See also
generatePointCloudAlongSE3Trajectory(), TGeneratePointCloudParameters

◆ generatePointCloudAlongSE3Trajectory()

void mrpt::obs::CObservationVelodyneScan::generatePointCloudAlongSE3Trajectory ( const mrpt::poses::CPose3DInterpolator vehicle_path,
std::vector< mrpt::math::TPointXYZIu8 > &  out_points,
TGeneratePointCloudSE3Results results_stats,
const TGeneratePointCloudParameters params = defaultPointCloudParams 
)

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
[in]vehicle_pathTimestamped 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]out_pointsThe generated points, in the same coordinates frame than vehicle_path. Points are APPENDED to the list, so prevous contents are kept.
[out]results_statsStats
[in]paramsFiltering and other parameters
See also
generatePointCloud(), TGeneratePointCloudParameters

◆ getDescriptionAsText()

void mrpt::obs::CObservationVelodyneScan::getDescriptionAsText ( std::ostream &  o) const
virtual

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.
This is the text that appears in RawLogViewer when selecting an object in the dataset

Reimplemented from mrpt::obs::CObservation.

◆ getOriginalReceivedTimeStamp()

mrpt::system::TTimeStamp mrpt::obs::CObservationVelodyneScan::getOriginalReceivedTimeStamp ( ) const
virtual

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()

Reimplemented from mrpt::obs::CObservation.

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId * mrpt::obs::CObservationVelodyneScan::GetRuntimeClass ( ) const
virtual

Reimplemented from mrpt::obs::CObservation.

◆ getSensorPose() [1/2]

void mrpt::obs::CObservation::getSensorPose ( mrpt::math::TPose3D out_sensorPose) const
inherited

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

◆ getSensorPose() [2/2]

void mrpt::obs::CObservationVelodyneScan::getSensorPose ( mrpt::poses::CPose3D out_sensorPose) const
inlinevirtual

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

Implements mrpt::obs::CObservation.

Definition at line 223 of file CObservationVelodyneScan.h.

◆ getTimeStamp()

mrpt::system::TTimeStamp mrpt::obs::CObservation::getTimeStamp ( ) const
inlineinherited

Returns CObservation::timestamp for all kind of observations.

See also
getOriginalReceivedTimeStamp()

Definition at line 63 of file obs/CObservation.h.

◆ insertObservationInto()

template<class METRICMAP >
bool mrpt::obs::CObservation::insertObservationInto ( METRICMAP *  theMap,
const mrpt::poses::CPose3D robotPose = NULL 
) const
inlineinherited

This method is equivalent to:

map->insertObservation(this, robotPose)
Parameters
theMapThe map where this observation is to be inserted: the map will be updated.
robotPoseThe pose of the robot base for this observation, relative to the target metric map. Set to NULL (default) to use (0,0,0deg)
Returns
Returns true if the map has been updated, or false if this observations has nothing to do with a metric map (for example, a sound observation).
See also
CMetricMap, CMetricMap::insertObservation

Definition at line 83 of file obs/CObservation.h.

◆ load()

virtual void mrpt::obs::CObservation::load ( ) const
inlinevirtualinherited

Makes sure all images and other fields which may be externally stored are loaded in memory.

Note that for all CImages, calling load() is not required since the images will be automatically loaded upon first access, so load() shouldn't be needed to be called in normal cases by the user. If all the data were alredy loaded or this object has no externally stored data fields, calling this method has no effects.

See also
unload

Reimplemented in mrpt::obs::CObservation3DRangeScan.

Definition at line 125 of file obs/CObservation.h.

◆ readFromStream()

void mrpt::obs::CObservationVelodyneScan::readFromStream ( mrpt::utils::CStream in,
int  version 
)
protected

◆ setSensorPose() [1/2]

void mrpt::obs::CObservation::setSensorPose ( const mrpt::math::TPose3D newSensorPose)
inherited

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

◆ setSensorPose() [2/2]

void mrpt::obs::CObservationVelodyneScan::setSensorPose ( const mrpt::poses::CPose3D newSensorPose)
inlinevirtual

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

Implements mrpt::obs::CObservation.

Definition at line 224 of file CObservationVelodyneScan.h.

◆ swap()

void mrpt::obs::CObservation::swap ( CObservation o)
protectedinherited

Swap with another observation, ONLY the data defined here in the base class CObservation. It's protected since it'll be only called from child classes that should know what else to swap appart from these common data.

◆ unload()

virtual void mrpt::obs::CObservation::unload ( )
inlinevirtualinherited

Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).

See also
load

Reimplemented in mrpt::obs::CObservation3DRangeScan.

Definition at line 129 of file obs/CObservation.h.

◆ writeToStream()

void mrpt::obs::CObservationVelodyneScan::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
protected

Member Data Documentation

◆ _init_CObservationVelodyneScan

mrpt::utils::CLASSINIT mrpt::obs::CObservationVelodyneScan::_init_CObservationVelodyneScan
staticprotected

Definition at line 59 of file CObservationVelodyneScan.h.

◆ BLOCK_DATA_SIZE

const int mrpt::obs::CObservationVelodyneScan::BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE)
static

Definition at line 70 of file CObservationVelodyneScan.h.

◆ BLOCKS_PER_PACKET

const int mrpt::obs::CObservationVelodyneScan::BLOCKS_PER_PACKET = 12
static

Definition at line 84 of file CObservationVelodyneScan.h.

◆ calibration

mrpt::obs::VelodyneCalibration mrpt::obs::CObservationVelodyneScan::calibration

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

Definition at line 133 of file CObservationVelodyneScan.h.

◆ classCObservation

const mrpt::utils::TRuntimeClassId mrpt::obs::CObservation::classCObservation
staticinherited

Definition at line 50 of file obs/CObservation.h.

◆ classCObservationVelodyneScan

mrpt::utils::TRuntimeClassId mrpt::obs::CObservationVelodyneScan::classCObservationVelodyneScan
static

Definition at line 59 of file CObservationVelodyneScan.h.

◆ classinfo

const mrpt::utils::TRuntimeClassId* mrpt::obs::CObservationVelodyneScan::classinfo
static

Definition at line 59 of file CObservationVelodyneScan.h.

◆ defaultPointCloudParams

const TGeneratePointCloudParameters mrpt::obs::CObservationVelodyneScan::defaultPointCloudParams
static

Definition at line 189 of file CObservationVelodyneScan.h.

◆ DISTANCE_MAX

const float mrpt::obs::CObservationVelodyneScan::DISTANCE_MAX
static

meters

Definition at line 75 of file CObservationVelodyneScan.h.

◆ DISTANCE_MAX_UNITS

const float mrpt::obs::CObservationVelodyneScan::DISTANCE_MAX_UNITS
static

Definition at line 77 of file CObservationVelodyneScan.h.

◆ DISTANCE_RESOLUTION

const float mrpt::obs::CObservationVelodyneScan::DISTANCE_RESOLUTION
static

meters

Definition at line 76 of file CObservationVelodyneScan.h.

◆ has_satellite_timestamp

bool mrpt::obs::CObservationVelodyneScan::has_satellite_timestamp

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.

Definition at line 135 of file CObservationVelodyneScan.h.

◆ LOWER_BANK

const uint16_t mrpt::obs::CObservationVelodyneScan::LOWER_BANK = 0xddff
static

Blocks 32-63.

Definition at line 80 of file CObservationVelodyneScan.h.

◆ maxRange

double mrpt::obs::CObservationVelodyneScan::maxRange

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

Definition at line 130 of file CObservationVelodyneScan.h.

◆ minRange

double mrpt::obs::CObservationVelodyneScan::minRange

Definition at line 130 of file CObservationVelodyneScan.h.

◆ originalReceivedTimestamp

mrpt::system::TTimeStamp mrpt::obs::CObservationVelodyneScan::originalReceivedTimestamp

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.

Definition at line 134 of file CObservationVelodyneScan.h.

◆ PACKET_SIZE

const int mrpt::obs::CObservationVelodyneScan::PACKET_SIZE = 1206
static

Definition at line 82 of file CObservationVelodyneScan.h.

◆ PACKET_STATUS_SIZE

const int mrpt::obs::CObservationVelodyneScan::PACKET_STATUS_SIZE = 4
static

Definition at line 85 of file CObservationVelodyneScan.h.

◆ point_cloud

TPointCloud mrpt::obs::CObservationVelodyneScan::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

See also
generatePointCloud()

Definition at line 165 of file CObservationVelodyneScan.h.

◆ POS_PACKET_SIZE

const int mrpt::obs::CObservationVelodyneScan::POS_PACKET_SIZE = 512
static

Definition at line 83 of file CObservationVelodyneScan.h.

◆ RAW_SCAN_SIZE

const int mrpt::obs::CObservationVelodyneScan::RAW_SCAN_SIZE = 3
static

Definition at line 68 of file CObservationVelodyneScan.h.

◆ RETMODE_DUAL

const uint8_t mrpt::obs::CObservationVelodyneScan::RETMODE_DUAL = 0x39
static

Definition at line 90 of file CObservationVelodyneScan.h.

◆ RETMODE_LAST

const uint8_t mrpt::obs::CObservationVelodyneScan::RETMODE_LAST = 0x38
static

Definition at line 89 of file CObservationVelodyneScan.h.

◆ RETMODE_STRONGEST

const uint8_t mrpt::obs::CObservationVelodyneScan::RETMODE_STRONGEST = 0x37
static

Definition at line 88 of file CObservationVelodyneScan.h.

◆ ROTATION_MAX_UNITS

const uint16_t mrpt::obs::CObservationVelodyneScan::ROTATION_MAX_UNITS = 36000
static

hundredths of degrees

Definition at line 73 of file CObservationVelodyneScan.h.

◆ ROTATION_RESOLUTION

const float mrpt::obs::CObservationVelodyneScan::ROTATION_RESOLUTION
static

Definition at line 72 of file CObservationVelodyneScan.h.

◆ scan_packets

std::vector<TVelodyneRawPacket> mrpt::obs::CObservationVelodyneScan::scan_packets

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

See also
point_cloud

Definition at line 132 of file CObservationVelodyneScan.h.

◆ SCANS_PER_BLOCK

const int mrpt::obs::CObservationVelodyneScan::SCANS_PER_BLOCK = 32
static

Definition at line 69 of file CObservationVelodyneScan.h.

◆ SCANS_PER_PACKET

const int mrpt::obs::CObservationVelodyneScan::SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET)
static

Definition at line 86 of file CObservationVelodyneScan.h.

◆ sensorLabel

std::string mrpt::obs::CObservation::sensorLabel
inherited

An arbitrary label that can be used to identify the sensor.

Definition at line 60 of file obs/CObservation.h.

◆ sensorPose

mrpt::poses::CPose3D mrpt::obs::CObservationVelodyneScan::sensorPose

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

Definition at line 131 of file CObservationVelodyneScan.h.

◆ SIZE_BLOCK

const int mrpt::obs::CObservationVelodyneScan::SIZE_BLOCK = 100
static

Definition at line 67 of file CObservationVelodyneScan.h.

◆ timestamp

mrpt::system::TTimeStamp mrpt::obs::CObservation::timestamp
inherited

The associated UTC time-stamp. Where available, this should contain the accurate satellite-based timestamp of the sensor reading.

See also
getOriginalReceivedTimeStamp(), getTimeStamp()

Definition at line 59 of file obs/CObservation.h.

◆ UPPER_BANK

const uint16_t mrpt::obs::CObservationVelodyneScan::UPPER_BANK = 0xeeff
static

Blocks 0-31.

Definition at line 79 of file CObservationVelodyneScan.h.




Page generated by Doxygen 1.9.6 for MRPT 1.4.0 SVN: at Wed Mar 22 04:35:51 UTC 2023