MRPT  2.0.2
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). 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:

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, mrpt::maps::CPointsMap, mrpt::hwdrivers::CVelodyneScanner

Definition at line 81 of file CObservationVelodyneScan.h.

#include <mrpt/obs/CObservationVelodyneScan.h>

Inheritance diagram for mrpt::obs::CObservationVelodyneScan:

Classes

struct  laser_return_t
 
struct  PointCloudStorageWrapper
 Derive from this class to generate pointclouds into custom containers. More...
 
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

void getSensorPose (mrpt::poses::CPose3D &out_sensorPose) const override
 A general method to retrieve the sensor pose on the robot. More...
 
void setSensorPose (const mrpt::poses::CPose3D &newSensorPose) override
 A general method to change the sensor pose on the robot. More...
 
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. More...
 
template<class METRICMAP >
bool insertObservationInto (METRICMAP *theMap, const mrpt::poses::CPose3D *robotPose=nullptr) 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...
 
std::string getDescriptionAsTextValue () const
 Return by value version of getDescriptionAsText(std::ostream&) 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...
 
Related to conversion to 3D point cloud
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). More...
 
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. 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 for polymorphic hierarchies
mrpt::rtti::CObject::Ptr duplicateGetSmartPtr () const
 Makes a deep copy of the object and returns a smart pointer to it. More...
 

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 uint16_t ROTATION_MAX_UNITS
 hundredths of degrees More...
 
static constexpr float ROTATION_RESOLUTION = 0.01f
 degrees More...
 
static constexpr float DISTANCE_MAX = 130.0f
 meters More...
 
static constexpr float DISTANCE_RESOLUTION = 0.002f
 meters More...
 
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 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
 

Protected Member Functions

void swap (CObservation &o)
 Swap with another observation, ONLY the data defined here in the base class CObservation. More...
 
CSerializable virtual methods
uint8_t serializeGetVersion () const override
 Must return the current versioning number of the object. More...
 
void serializeTo (mrpt::serialization::CArchive &out) const override
 Pure virtual method for writing (serializing) to an abstract archive. More...
 
void serializeFrom (mrpt::serialization::CArchive &in, uint8_t serial_version) override
 Pure virtual method for reading (deserializing) from an abstract archive. More...
 
CSerializable virtual methods
virtual void serializeTo (CSchemeArchiveBase &out) const
 Virtual method for writing (serializing) to an abstract schema based archive. More...
 
virtual void serializeFrom (CSchemeArchiveBase &in)
 Virtual method for reading (deserializing) from an abstract schema based archive. More...
 

Data common to any observation

mrpt::system::TTimeStamp timestamp {mrpt::system::now()}
 The associated UTC time-stamp. 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

using Ptr = std::shared_ptr< mrpt::obs ::CObservationVelodyneScan >
 
using ConstPtr = std::shared_ptr< const mrpt::obs ::CObservationVelodyneScan >
 
using UniquePtr = std::unique_ptr< mrpt::obs ::CObservationVelodyneScan >
 
using ConstUniquePtr = std::unique_ptr< const mrpt::obs ::CObservationVelodyneScan >
 
static const mrpt::rtti::TRuntimeClassId runtimeClassId
 
static constexpr const char * className = "mrpt::obs" "::" "CObservationVelodyneScan"
 
static const mrpt::rtti::TRuntimeClassId_GetBaseClass ()
 
static constexpr auto getClassName ()
 
static const mrpt::rtti::TRuntimeClassIdGetRuntimeClassIdStatic ()
 
static std::shared_ptr< CObjectCreateObject ()
 
template<typename... Args>
static Ptr Create (Args &&... args)
 
template<typename Alloc , typename... Args>
static Ptr CreateAlloc (const Alloc &alloc, Args &&... args)
 
template<typename... Args>
static UniquePtr CreateUnique (Args &&... args)
 
virtual const mrpt::rtti::TRuntimeClassIdGetRuntimeClass () const override
 Returns information about the class of an object in runtime. More...
 
virtual mrpt::rtti::CObjectclone () const override
 Returns a deep copy (clone) of the object, indepently of its class. More...
 

Scan data

double minRange {1.0}
 The maximum range allowed by the device, in meters (e.g. More...
 
double maxRange {130.0}
 
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. More...
 
mrpt::system::TTimeStamp originalReceivedTimestamp {INVALID_TIMESTAMP}
 The local computer-based timestamp based on the reception of the message in the computer. More...
 
bool has_satellite_timestamp {false}
 If true, CObservation::timestamp has been generated from accurate satellite 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 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...
 

Member Typedef Documentation

◆ ConstPtr

Definition at line 83 of file CObservationVelodyneScan.h.

◆ ConstUniquePtr

Definition at line 83 of file CObservationVelodyneScan.h.

◆ Ptr

A type for the associated smart pointer

Definition at line 83 of file CObservationVelodyneScan.h.

◆ UniquePtr

Definition at line 83 of file CObservationVelodyneScan.h.

Member Function Documentation

◆ _GetBaseClass()

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

◆ clone()

virtual mrpt::rtti::CObject* mrpt::obs::CObservationVelodyneScan::clone ( ) const
overridevirtual

Returns a deep copy (clone) of the object, indepently of its class.

Implements mrpt::rtti::CObject.

◆ Create()

template<typename... Args>
static Ptr mrpt::obs::CObservationVelodyneScan::Create ( Args &&...  args)
inlinestatic

Definition at line 83 of file CObservationVelodyneScan.h.

Referenced by mrpt::hwdrivers::CVelodyneScanner::getNextObservation().

Here is the caller graph for this function:

◆ CreateAlloc()

template<typename Alloc , typename... Args>
static Ptr mrpt::obs::CObservationVelodyneScan::CreateAlloc ( const Alloc &  alloc,
Args &&...  args 
)
inlinestatic

Definition at line 83 of file CObservationVelodyneScan.h.

◆ CreateObject()

static std::shared_ptr<CObject> mrpt::obs::CObservationVelodyneScan::CreateObject ( )
static

◆ CreateUnique()

template<typename... Args>
static UniquePtr mrpt::obs::CObservationVelodyneScan::CreateUnique ( Args &&...  args)
inlinestatic

Definition at line 83 of file CObservationVelodyneScan.h.

◆ duplicateGetSmartPtr()

mrpt::rtti::CObject::Ptr CObject::duplicateGetSmartPtr ( ) const
inlineinherited

Makes a deep copy of the object and returns a smart pointer to it.

Definition at line 204 of file CObject.h.

References mrpt::rtti::CObject::clone().

Referenced by mrpt::obs::CRawlog::insert().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ generatePointCloud() [1/2]

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

Definition at line 431 of file CObservationVelodyneScan.cpp.

References mrpt::obs::CObservationVelodyneScan::TPointCloud::azimuth, mrpt::obs::gnss::azimuth, mrpt::obs::CObservationVelodyneScan::TPointCloud::clear(), mrpt::obs::CObservationVelodyneScan::TGeneratePointCloudParameters::generatePerPointAzimuth, mrpt::obs::CObservationVelodyneScan::TGeneratePointCloudParameters::generatePerPointTimestamp, mrpt::obs::CObservationVelodyneScan::TGeneratePointCloudParameters::generatePointsForLaserID, mrpt::obs::CObservationVelodyneScan::TPointCloud::intensity, mrpt::obs::CObservationVelodyneScan::TPointCloud::laser_id, params, point_cloud, mrpt::obs::CObservationVelodyneScan::TPointCloud::pointsForLaserID, mrpt::obs::CObservationVelodyneScan::TPointCloud::reserve(), ROTATION_MAX_UNITS, mrpt::round(), mrpt::obs::CObservationVelodyneScan::TPointCloud::timestamp, mrpt::obs::CObservationVelodyneScan::TPointCloud::x, mrpt::obs::CObservationVelodyneScan::TPointCloud::y, and mrpt::obs::CObservationVelodyneScan::TPointCloud::z.

Referenced by mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), and mrpt::maps::CPointsMap::internal_insertObservation().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ generatePointCloud() [2/2]

void Velo::generatePointCloud ( PointCloudStorageWrapper dest,
const TGeneratePointCloudParameters params = TGeneratePointCloudParameters() 
)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 425 of file CObservationVelodyneScan.cpp.

References params, and velodyne_scan_to_pointcloud().

Here is the call graph for this function:

◆ generatePointCloudAlongSE3Trajectory()

void Velo::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
[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 495 of file CObservationVelodyneScan.cpp.

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

Here is the call graph for this function:

◆ getClassName()

static constexpr auto mrpt::obs::CObservationVelodyneScan::getClassName ( )
inlinestatic

Definition at line 83 of file CObservationVelodyneScan.h.

◆ getDescriptionAsText()

void Velo::getDescriptionAsText ( std::ostream &  o) const
overridevirtual

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 114 of file CObservationVelodyneScan.cpp.

References mrpt::format().

Here is the call graph for this function:

◆ getDescriptionAsTextValue()

std::string CObservation::getDescriptionAsTextValue ( ) const
inherited

Return by value version of getDescriptionAsText(std::ostream&)

Definition at line 59 of file CObservation.cpp.

◆ getOriginalReceivedTimeStamp()

mrpt::system::TTimeStamp Velo::getOriginalReceivedTimeStamp ( ) const
overridevirtual

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 38 of file CObservationVelodyneScan.cpp.

◆ GetRuntimeClass()

virtual const mrpt::rtti::TRuntimeClassId* mrpt::obs::CObservationVelodyneScan::GetRuntimeClass ( ) const
overridevirtual

Returns information about the class of an object in runtime.

Reimplemented from mrpt::obs::CObservation.

◆ GetRuntimeClassIdStatic()

static const mrpt::rtti::TRuntimeClassId& mrpt::obs::CObservationVelodyneScan::GetRuntimeClassIdStatic ( )
static

◆ 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 24 of file CObservation.cpp.

References mrpt::poses::CPose3D::asTPose().

Here is the call graph for this function:

◆ getSensorPose() [2/2]

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

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

References sensorPose.

◆ getTimeStamp()

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

Returns CObservation::timestamp for all kind of observations.

See also
getOriginalReceivedTimeStamp()

Definition at line 66 of file CObservation.h.

References mrpt::obs::CObservation::timestamp.

◆ insertObservationInto()

template<class METRICMAP >
bool mrpt::obs::CObservation::insertObservationInto ( METRICMAP *  theMap,
const mrpt::poses::CPose3D robotPose = nullptr 
) 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 nullptr (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 99 of file 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, mrpt::obs::CObservationStereoImages, mrpt::obs::CObservationImage, and mrpt::obs::CObservationPointCloud.

Definition at line 157 of file CObservation.h.

Referenced by mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation().

Here is the caller graph for this function:

◆ serializeFrom() [1/2]

virtual void mrpt::serialization::CSerializable::serializeFrom ( CSchemeArchiveBase in)
inlineprotectedvirtualinherited

Virtual method for reading (deserializing) from an abstract schema based archive.

Definition at line 74 of file CSerializable.h.

References mrpt::serialization::CSerializable::GetRuntimeClass(), and THROW_EXCEPTION.

Here is the call graph for this function:

◆ serializeFrom() [2/2]

void Velo::serializeFrom ( mrpt::serialization::CArchive in,
uint8_t  serial_version 
)
overrideprotectedvirtual

Pure virtual method for reading (deserializing) from an abstract archive.

Users don't call this method directly. Instead, use stream >> object;.

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 I/O error

Implements mrpt::serialization::CSerializable.

Definition at line 66 of file CObservationVelodyneScan.cpp.

References MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION, and mrpt::serialization::CArchive::ReadBuffer().

Here is the call graph for this function:

◆ serializeGetVersion()

uint8_t Velo::serializeGetVersion ( ) const
overrideprotectedvirtual

Must return the current versioning number of the object.

Start in zero for new classes, and increments each time there is a change in the stored format.

Implements mrpt::serialization::CSerializable.

Definition at line 43 of file CObservationVelodyneScan.cpp.

◆ serializeTo() [1/2]

virtual void mrpt::serialization::CSerializable::serializeTo ( CSchemeArchiveBase out) const
inlineprotectedvirtualinherited

Virtual method for writing (serializing) to an abstract schema based archive.

Definition at line 64 of file CSerializable.h.

References mrpt::serialization::CSerializable::GetRuntimeClass(), and THROW_EXCEPTION.

Here is the call graph for this function:

◆ serializeTo() [2/2]

void Velo::serializeTo ( mrpt::serialization::CArchive out) const
overrideprotectedvirtual

Pure virtual method for writing (serializing) to an abstract archive.

Users don't call this method directly. Instead, use stream << object;.

Exceptions
std::exceptionOn any I/O error

Implements mrpt::serialization::CSerializable.

Definition at line 44 of file CObservationVelodyneScan.cpp.

References out.

◆ 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 31 of file CObservation.cpp.

◆ setSensorPose() [2/2]

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

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

References sensorPose.

◆ 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 36 of file CObservation.cpp.

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

Referenced by mrpt::obs::CObservationStereoImages::swap().

Here is the caller graph for this function:

◆ 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, and mrpt::obs::CObservationPointCloud.

Definition at line 164 of file CObservation.h.

◆ writeToMatlab()

virtual mxArray* mrpt::serialization::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 nullptr is class does not support conversion to MATLAB.

Definition at line 90 of file CSerializable.h.

Member Data Documentation

◆ BLOCK_DATA_SIZE

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

Definition at line 91 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 216 of file CObservationVelodyneScan.h.

Referenced by mrpt::obs::CObservationRotatingScan::fromVelodyne(), and velodyne_scan_to_pointcloud().

◆ className

constexpr const char* mrpt::obs::CObservationVelodyneScan::className = "mrpt::obs" "::" "CObservationVelodyneScan"
static

Definition at line 83 of file CObservationVelodyneScan.h.

◆ DISTANCE_MAX

constexpr float mrpt::obs::CObservationVelodyneScan::DISTANCE_MAX = 130.0f
static

meters

Definition at line 97 of file CObservationVelodyneScan.h.

◆ DISTANCE_RESOLUTION

constexpr float mrpt::obs::CObservationVelodyneScan::DISTANCE_RESOLUTION = 0.002f
static

◆ has_satellite_timestamp

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

Definition at line 225 of file CObservationVelodyneScan.h.

Referenced by mrpt::obs::CObservationRotatingScan::fromVelodyne().

◆ LOWER_BANK

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

◆ maxRange

double mrpt::obs::CObservationVelodyneScan::maxRange {130.0}

◆ minRange

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

Definition at line 207 of file CObservationVelodyneScan.h.

Referenced by mrpt::obs::CObservationRotatingScan::fromVelodyne(), and velodyne_scan_to_pointcloud().

◆ originalReceivedTimestamp

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

Definition at line 221 of file CObservationVelodyneScan.h.

Referenced by mrpt::obs::CObservationRotatingScan::fromVelodyne().

◆ PACKET_SIZE

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

Definition at line 107 of file CObservationVelodyneScan.h.

◆ PACKET_STATUS_SIZE

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

Definition at line 110 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 263 of file CObservationVelodyneScan.h.

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

◆ POS_PACKET_SIZE

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

Definition at line 108 of file CObservationVelodyneScan.h.

◆ RAW_SCAN_SIZE

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

Definition at line 89 of file CObservationVelodyneScan.h.

◆ RETMODE_DUAL

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

◆ RETMODE_LAST

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

Definition at line 114 of file CObservationVelodyneScan.h.

◆ RETMODE_STRONGEST

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

Definition at line 113 of file CObservationVelodyneScan.h.

◆ ROTATION_MAX_UNITS

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

hundredths of degrees

Definition at line 93 of file CObservationVelodyneScan.h.

Referenced by generatePointCloud(), and velodyne_scan_to_pointcloud().

◆ ROTATION_RESOLUTION

constexpr float mrpt::obs::CObservationVelodyneScan::ROTATION_RESOLUTION = 0.01f
static

degrees

Definition at line 96 of file CObservationVelodyneScan.h.

◆ runtimeClassId

const mrpt::rtti::TRuntimeClassId mrpt::obs::CObservationVelodyneScan::runtimeClassId
staticprotected

Definition at line 83 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 212 of file CObservationVelodyneScan.h.

Referenced by mrpt::obs::CObservationRotatingScan::fromVelodyne(), and velodyne_scan_to_pointcloud().

◆ SCANS_PER_BLOCK

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

◆ SCANS_PER_FIRING

const int mrpt::obs::CObservationVelodyneScan::SCANS_PER_FIRING = 16
static

◆ SCANS_PER_PACKET

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

◆ sensorLabel

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

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

Definition at line 62 of file CObservation.h.

Referenced by mrpt::ros1bridge::convert(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), 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::apps::RawlogGrabberApp::dump_GPS_mode_info(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::obs::CObservationRotatingScan::fromScan2D(), mrpt::obs::CObservationRotatingScan::fromVelodyne(), mrpt::hwdrivers::CRaePID::getFullInfo(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CWirelessPower::getObservation(), mrpt::hwdrivers::CImpinjRFID::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::obs::CObservation6DFeatures::serializeFrom(), mrpt::obs::CObservationPointCloud::serializeFrom(), mrpt::obs::CObservation6DFeatures::serializeTo(), mrpt::obs::CObservationPointCloud::serializeTo(), mrpt::obs::CObservation::swap(), and mrpt::ros1bridge::toROS().

◆ sensorPose

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

◆ SIZE_BLOCK

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

Definition at line 88 of file CObservationVelodyneScan.h.

◆ timestamp

mrpt::system::TTimeStamp mrpt::obs::CObservation::timestamp {mrpt::system::now()}
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 60 of file CObservation.h.

Referenced by mrpt::ros1bridge::convert(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::hwdrivers::CSICKTim561Eth::decodeScan(), 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::ros1bridge::fromROS(), mrpt::obs::CObservationRotatingScan::fromScan2D(), mrpt::obs::CObservationRotatingScan::fromVelodyne(), 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::CImageGrabber_OpenCV::getObservation(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), mrpt::hwdrivers::CImageGrabber_dc1394::getObservation(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::hwdrivers::CDUO3DCamera::getObservations(), mrpt::obs::CObservation::getOriginalReceivedTimeStamp(), mrpt::obs::CObservation::getTimeStamp(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::hwdrivers::CGPSInterface::parse_NMEA(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), mrpt::obs::CObservation6DFeatures::serializeFrom(), mrpt::obs::CObservationPointCloud::serializeFrom(), mrpt::obs::CObservation6DFeatures::serializeTo(), mrpt::obs::CObservationPointCloud::serializeTo(), mrpt::maps::CLandmarksMap::simulateBeaconReadings(), mrpt::maps::CLandmarksMap::simulateRangeBearingReadings(), mrpt::obs::CObservation::swap(), mrpt::ros1bridge::toROS(), and velodyne_scan_to_pointcloud().

◆ UPPER_BANK

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

Blocks 0-31.

Definition at line 101 of file CObservationVelodyneScan.h.

Referenced by velodyne_scan_to_pointcloud().




Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020