Main MRPT website > C++ reference for MRPT 1.5.7
List of all members | Classes | Public Member Functions | Static Public Member Functions | Static Public Attributes | 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

voidoperator new (size_t size)
 
voidoperator new[] (size_t size)
 
void operator delete (void *ptr) throw ()
 
void operator delete[] (void *ptr) throw ()
 
void operator delete (void *memory, void *ptr) throw ()
 
voidoperator new (size_t size, const std::nothrow_t &) throw ()
 
void operator delete (void *ptr, const std::nothrow_t &) throw ()
 
 CObservationVelodyneScan ()
 
virtual ~CObservationVelodyneScan ()
 
void getSensorPose (mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
 A general method to retrieve the sensor pose on the robot. More...
 
void setSensorPose (const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
 A general method to change the sensor pose on the robot. More...
 
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. More...
 
template<class METRICMAP >
bool insertObservationInto (METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose=NULL) const
 This method is equivalent to: More...
 
void getSensorPose (mrpt::math::TPose3D &out_sensorPose) const
 A general method to retrieve the sensor pose on the robot. More...
 
void setSensorPose (const mrpt::math::TPose3D &newSensorPose)
 A general method to change the sensor pose on the robot. More...
 
virtual mxArraywriteToMatlab () const
 Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More...
 
CObjectclone () const
 Cloning interface for smart pointers. More...
 
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. More...
 
virtual void unload ()
 Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect). More...
 
RTTI classes and functions
mrpt::utils::CObjectPtr duplicateGetSmartPtr () const
 Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More...
 

Static Public Member Functions

static voidoperator new (size_t size, void *ptr)
 

Static Public Attributes

static const mrpt::utils::TRuntimeClassId classCObject
 
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 = 0.01f
 degrees More...
 
static const uint16_t ROTATION_MAX_UNITS = 36000
 hundredths of degrees More...
 
static const float DISTANCE_MAX = 130.0f
 meters More...
 
static const float DISTANCE_RESOLUTION = 0.002f
 meters More...
 
static const float DISTANCE_MAX_UNITS = (CObservationVelodyneScan::DISTANCE_MAX / CObservationVelodyneScan::DISTANCE_RESOLUTION + 1.0f)
 
static const uint16_t UPPER_BANK = 0xeeff
 Blocks 0-31. More...
 
static const uint16_t LOWER_BANK = 0xddff
 Blocks 32-63. More...
 
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
static const mrpt::utils::TRuntimeClassId classCObservation
 
RTTI stuff
static const mrpt::utils::TRuntimeClassId classCSerializable
 

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. More...
 
CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const
 Introduces a pure virtual method responsible for writing to a CStream. More...
 
void readFromStream (mrpt::utils::CStream &in, int version)
 Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More...
 

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. More...
 
std::string sensorLabel
 An arbitrary label that can be used to identify the sensor. More...
 
mrpt::system::TTimeStamp getTimeStamp () const
 Returns CObservation::timestamp for all kind of observations. More...
 

RTTI stuff

typedef CObservationVelodyneScanPtr Ptr
 
typedef CObservationVelodyneScanPtr ConstPtr
 
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
 Returns information about the class of an object in runtime. More...
 
virtual mrpt::utils::CObjectduplicate () const
 Returns a copy of the object, indepently of its class. More...
 
static mrpt::utils::CObjectCreateObject ()
 
static CObservationVelodyneScanPtr Create ()
 

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. More...
 
mrpt::poses::CPose3D sensorPose
 The 6D pose of the sensor on the robot/vehicle frame of reference. More...
 
std::vector< TVelodyneRawPacketscan_packets
 The main content of this object: raw data packet from the LIDAR. More...
 
mrpt::obs::VelodyneCalibration calibration
 The calibration data for the LIDAR device. See mrpt::hwdrivers::CVelodyneScanner and mrpt::obs::VelodyneCalibration for details. More...
 
mrpt::system::TTimeStamp originalReceivedTimestamp
 The local computer-based timestamp based on the reception of the message in the computer. More...
 
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. More...
 
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. More...
 
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. More...
 

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

Member Typedef Documentation

◆ ConstPtr

typedef CObservationVelodyneScanPtr mrpt::obs::CObservationVelodyneScan::ConstPtr

Definition at line 59 of file CObservationVelodyneScan.h.

◆ Ptr

typedef CObservationVelodyneScanPtr mrpt::obs::CObservationVelodyneScan::Ptr

A typedef for the associated smart pointer

Definition at line 59 of file CObservationVelodyneScan.h.

Constructor & Destructor Documentation

◆ CObservationVelodyneScan()

CObservationVelodyneScan::CObservationVelodyneScan ( )

Definition at line 78 of file CObservationVelodyneScan.cpp.

◆ ~CObservationVelodyneScan()

CObservationVelodyneScan::~CObservationVelodyneScan ( )
virtual

Definition at line 87 of file CObservationVelodyneScan.cpp.

Member Function Documentation

◆ _GetBaseClass()

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

◆ clone()

CObject* mrpt::utils::CObject::clone ( ) const
inlineinherited

Cloning interface for smart pointers.

Definition at line 133 of file CObject.h.

◆ 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

Returns a copy of the object, indepently of its class.

Implements mrpt::utils::CObject.

◆ duplicateGetSmartPtr()

mrpt::utils::CObjectPtr CObject::duplicateGetSmartPtr ( ) const
inlineinherited

Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer).

Definition at line 162 of file CObject.h.

References mrpt::utils::CObjectPtr.

Referenced by mrpt::obs::CRawlog::addActions(), mrpt::slam::CIncrementalMapPartitioner::addMapFrame(), and mrpt::obs::CRawlog::addObservations().

◆ generatePointCloud()

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

◆ generatePointCloudAlongSE3Trajectory()

void 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

Definition at line 429 of file CObservationVelodyneScan.cpp.

References mrpt::obs::gnss::azimuth, BLOCKS_PER_PACKET, mrpt::poses::CPose3D::composeFrom(), mrpt::poses::CPose3D::composePoint(), mrpt::poses::CPoseInterpolatorBase< DIM >::interpolate(), INVALID_TIMESTAMP, MRPT_OVERRIDE, mrpt::obs::CObservationVelodyneScan::TGeneratePointCloudSE3Results::num_correctly_inserted_points, mrpt::obs::CObservationVelodyneScan::TGeneratePointCloudSE3Results::num_points, scan_packets, SCANS_PER_BLOCK, sensorPose, mrpt::poses::UNINITIALIZED_POSE, and velodyne_scan_to_pointcloud().

◆ getDescriptionAsText()

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

Definition at line 160 of file CObservationVelodyneScan.cpp.

References mrpt::format(), mrpt::obs::CObservation::getDescriptionAsText(), mrpt::poses::CPose3D::getHomogeneousMatrixVal(), maxRange, minRange, scan_packets, and sensorPose.

◆ getOriginalReceivedTimeStamp()

mrpt::system::TTimeStamp 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.

Definition at line 91 of file CObservationVelodyneScan.cpp.

References originalReceivedTimestamp.

◆ GetRuntimeClass()

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

Returns information about the class of an object in runtime.

Reimplemented from mrpt::obs::CObservation.

◆ getSensorPose() [1/2]

void 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

Definition at line 38 of file CObservation.cpp.

◆ 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 217 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 56 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: Maps and observations compatibility matrix

See also
CMetricMap, CMetricMap::insertObservation

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

Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference().

◆ 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 119 of file obs/CObservation.h.

◆ operator delete() [1/3]

void mrpt::obs::CObservationVelodyneScan::operator delete ( void ptr)
throw (
)
inline

Definition at line 59 of file CObservationVelodyneScan.h.

◆ operator delete() [2/3]

void mrpt::obs::CObservationVelodyneScan::operator delete ( void memory,
void ptr 
)
throw (
)
inline

Definition at line 59 of file CObservationVelodyneScan.h.

◆ operator delete() [3/3]

void mrpt::obs::CObservationVelodyneScan::operator delete ( void ptr,
const std::nothrow_t &   
)
throw (
)
inline

Definition at line 59 of file CObservationVelodyneScan.h.

◆ operator delete[]()

void mrpt::obs::CObservationVelodyneScan::operator delete[] ( void ptr)
throw (
)
inline

Definition at line 59 of file CObservationVelodyneScan.h.

◆ operator new() [1/3]

void* mrpt::obs::CObservationVelodyneScan::operator new ( size_t  size,
const std::nothrow_t &   
)
throw (
)
inline

Definition at line 59 of file CObservationVelodyneScan.h.

◆ operator new() [2/3]

void* mrpt::obs::CObservationVelodyneScan::operator new ( size_t  size)
inline

Definition at line 59 of file CObservationVelodyneScan.h.

◆ operator new() [3/3]

static void* mrpt::obs::CObservationVelodyneScan::operator new ( size_t  size,
void ptr 
)
inlinestatic

Definition at line 59 of file CObservationVelodyneScan.h.

◆ operator new[]()

void* mrpt::obs::CObservationVelodyneScan::operator new[] ( size_t  size)
inline

Definition at line 59 of file CObservationVelodyneScan.h.

◆ readFromStream()

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

Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.

Parameters
inThe input binary stream where the object data must read from.
versionThe version of the object stored in the stream: use this version number in your code to know how to read the incoming data.
Exceptions
std::exceptionOn any error, see CStream::ReadBuffer
See also
CStream

Implements mrpt::utils::CSerializable.

Definition at line 125 of file CObservationVelodyneScan.cpp.

References calibration, has_satellite_timestamp, mrpt::obs::CObservationVelodyneScan::TPointCloud::intensity, mrpt::obs::VelodyneCalibration::laser_corrections, maxRange, minRange, MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, originalReceivedTimestamp, point_cloud, scan_packets, mrpt::obs::CObservation::sensorLabel, sensorPose, mrpt::obs::CObservation::timestamp, version, mrpt::obs::CObservationVelodyneScan::TPointCloud::x, mrpt::obs::CObservationVelodyneScan::TPointCloud::y, and mrpt::obs::CObservationVelodyneScan::TPointCloud::z.

◆ setSensorPose() [1/2]

void 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

Definition at line 45 of file CObservation.cpp.

◆ 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 218 of file CObservationVelodyneScan.h.

◆ swap()

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

Definition at line 50 of file CObservation.cpp.

References mrpt::obs::CObservation::sensorLabel, and mrpt::obs::CObservation::timestamp.

Referenced by mrpt::obs::CObservationStereoImages::swap(), and mrpt::obs::CObservation3DRangeScan::swap().

◆ 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 123 of file obs/CObservation.h.

◆ writeToMatlab()

virtual mxArray* mrpt::utils::CSerializable::writeToMatlab ( ) const
inlinevirtualinherited

Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.

Returns
A new mxArray (caller is responsible of memory freeing) or NULL is class does not support conversion to MATLAB.

Definition at line 79 of file CSerializable.h.

◆ writeToStream()

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

Introduces a pure virtual method responsible for writing to a CStream.

This can not be used directly be users, instead use "stream << object;" for writing it to a stream.

Parameters
outThe output binary stream where object must be dumped.
getVersionIf NULL, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data.
Exceptions
std::exceptionOn any error, see CStream::WriteBuffer
See also
CStream

Implements mrpt::utils::CSerializable.

Definition at line 98 of file CObservationVelodyneScan.cpp.

References calibration, has_satellite_timestamp, mrpt::obs::CObservationVelodyneScan::TPointCloud::intensity, mrpt::obs::VelodyneCalibration::laser_corrections, maxRange, minRange, point_cloud, scan_packets, mrpt::obs::CObservation::sensorLabel, sensorPose, mrpt::obs::CObservation::timestamp, version, mrpt::utils::CStream::WriteBuffer(), mrpt::obs::CObservationVelodyneScan::TPointCloud::x, mrpt::obs::CObservationVelodyneScan::TPointCloud::y, and mrpt::obs::CObservationVelodyneScan::TPointCloud::z.

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

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

Referenced by readFromStream(), velodyne_scan_to_pointcloud(), and writeToStream().

◆ classCObject

const mrpt::utils::TRuntimeClassId mrpt::utils::CObject::classCObject
staticinherited

Definition at line 118 of file CObject.h.

◆ classCObservation

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

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

◆ classCObservationVelodyneScan

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

Definition at line 59 of file CObservationVelodyneScan.h.

◆ classCSerializable

const mrpt::utils::TRuntimeClassId mrpt::utils::CSerializable::classCSerializable
staticinherited

Definition at line 42 of file CSerializable.h.

◆ classinfo

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

Definition at line 59 of file CObservationVelodyneScan.h.

◆ defaultPointCloudParams

const CObservationVelodyneScan::TGeneratePointCloudParameters CObservationVelodyneScan::defaultPointCloudParams
static

Definition at line 183 of file CObservationVelodyneScan.h.

◆ DISTANCE_MAX

const float CObservationVelodyneScan::DISTANCE_MAX = 130.0f
static

meters

Definition at line 75 of file CObservationVelodyneScan.h.

◆ DISTANCE_MAX_UNITS

const float CObservationVelodyneScan::DISTANCE_MAX_UNITS = (CObservationVelodyneScan::DISTANCE_MAX / CObservationVelodyneScan::DISTANCE_RESOLUTION + 1.0f)
static

Definition at line 77 of file CObservationVelodyneScan.h.

◆ DISTANCE_RESOLUTION

const float CObservationVelodyneScan::DISTANCE_RESOLUTION = 0.002f
static

meters

Definition at line 76 of file CObservationVelodyneScan.h.

Referenced by velodyne_scan_to_pointcloud().

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

Referenced by readFromStream(), and writeToStream().

◆ LOWER_BANK

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

Blocks 32-63.

Definition at line 80 of file CObservationVelodyneScan.h.

Referenced by velodyne_scan_to_pointcloud().

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

Referenced by getDescriptionAsText(), readFromStream(), velodyne_scan_to_pointcloud(), and writeToStream().

◆ minRange

double mrpt::obs::CObservationVelodyneScan::minRange

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

Referenced by getOriginalReceivedTimeStamp(), and readFromStream().

◆ 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 157 of file CObservationVelodyneScan.h.

Referenced by generatePointCloud(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::CPointsMap::loadFromVelodyneScan(), readFromStream(), and writeToStream().

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

Referenced by velodyne_scan_to_pointcloud().

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

Referenced by generatePointCloud(), and velodyne_scan_to_pointcloud().

◆ ROTATION_RESOLUTION

const float CObservationVelodyneScan::ROTATION_RESOLUTION = 0.01f
static

degrees

Definition at line 72 of file CObservationVelodyneScan.h.

Referenced by generatePointCloud().

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

Referenced by generatePointCloudAlongSE3Trajectory(), getDescriptionAsText(), readFromStream(), velodyne_scan_to_pointcloud(), and writeToStream().

◆ SCANS_PER_BLOCK

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

Definition at line 69 of file CObservationVelodyneScan.h.

Referenced by generatePointCloudAlongSE3Trajectory().

◆ 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 53 of file obs/CObservation.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2Sensor::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CImpinjRFID::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::obs::CObservation6DFeatures::readFromStream(), mrpt::obs::CObservationStereoImages::readFromStream(), mrpt::obs::CObservation2DRangeScan::readFromStream(), readFromStream(), mrpt::obs::CObservation3DRangeScan::readFromStream(), mrpt::obs::CObservation::swap(), mrpt::obs::CObservationGPS::swap(), mrpt::obs::CObservation6DFeatures::writeToStream(), mrpt::obs::CObservationStereoImages::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().

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

Referenced by generatePointCloudAlongSE3Trajectory(), getDescriptionAsText(), mrpt::maps::CPointsMap::loadFromVelodyneScan(), readFromStream(), and writeToStream().

◆ 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 52 of file obs/CObservation.h.

Referenced by mrpt::obs::carmen_log_parse_line(), mrpt::obs::CObservationVelodyneScan::TPointCloud::clear_deep(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CLMS100Eth::decodeScan(), mrpt::detectors::CObjectDetection::detectObjects(), mrpt::hwdrivers::CRaePID::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::obs::CObservationGasSensors::CMOSmodel::get_GasDistribution_estimation(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::COpenNI2_RGBD360::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::obs::CObservationGasSensors::CMOSmodel::inverse_MOSmodeling(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::obs::CObservationGasSensors::CMOSmodel::noise_filtering(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::obs::CObservation6DFeatures::readFromStream(), mrpt::obs::CObservationStereoImages::readFromStream(), mrpt::obs::CObservation2DRangeScan::readFromStream(), readFromStream(), mrpt::obs::CObservation3DRangeScan::readFromStream(), mrpt::obs::CObservationGasSensors::CMOSmodel::save_log_map(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::obs::CObservation::swap(), mrpt::obs::CObservationGPS::swap(), velodyne_scan_to_pointcloud(), mrpt::obs::CObservation6DFeatures::writeToStream(), mrpt::obs::CObservationStereoImages::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().

◆ UPPER_BANK

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

Blocks 0-31.

Definition at line 79 of file CObservationVelodyneScan.h.

Referenced by velodyne_scan_to_pointcloud().




Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019