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).
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:
Definition at line 56 of file CObservationVelodyneScan.h.
#include <mrpt/obs/CObservationVelodyneScan.h>
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 | |
void * | operator new (size_t size) |
void * | operator new[] (size_t size) |
void | operator delete (void *ptr) throw () |
void | operator delete[] (void *ptr) throw () |
void | operator delete (void *memory, void *ptr) throw () |
void * | operator 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 mxArray * | writeToMatlab () 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... | |
CObject * | clone () 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 void * | operator 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::TRuntimeClassId * | classinfo |
static const mrpt::utils::TRuntimeClassId * | _GetBaseClass () |
virtual const mrpt::utils::TRuntimeClassId * | GetRuntimeClass () const |
Returns information about the class of an object in runtime. More... | |
virtual mrpt::utils::CObject * | duplicate () const |
Returns a copy of the object, indepently of its class. More... | |
static mrpt::utils::CObject * | CreateObject () |
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< TVelodyneRawPacket > | scan_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 ¶ms=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 ¶ms=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... | |
typedef CObservationVelodyneScanPtr mrpt::obs::CObservationVelodyneScan::ConstPtr |
Definition at line 59 of file CObservationVelodyneScan.h.
typedef CObservationVelodyneScanPtr mrpt::obs::CObservationVelodyneScan::Ptr |
A typedef for the associated smart pointer
Definition at line 59 of file CObservationVelodyneScan.h.
CObservationVelodyneScan::CObservationVelodyneScan | ( | ) |
Definition at line 78 of file CObservationVelodyneScan.cpp.
|
virtual |
Definition at line 87 of file CObservationVelodyneScan.cpp.
|
staticprotected |
|
inlineinherited |
|
static |
Referenced by mrpt::hwdrivers::CVelodyneScanner::getNextObservation().
|
static |
|
virtual |
Returns a copy of the object, indepently of its class.
Implements mrpt::utils::CObject.
|
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().
void 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()
Definition at line 399 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::TPointCloud::intensity, MRPT_OVERRIDE, point_cloud, ROTATION_MAX_UNITS, ROTATION_RESOLUTION, mrpt::utils::round(), mrpt::obs::CObservationVelodyneScan::TPointCloud::timestamp, velodyne_scan_to_pointcloud(), mrpt::obs::CObservationVelodyneScan::TPointCloud::x, mrpt::obs::CObservationVelodyneScan::TPointCloud::y, and mrpt::obs::CObservationVelodyneScan::TPointCloud::z.
Referenced by mrpt::maps::CPointsMap::internal_insertObservation().
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.
[in] | vehicle_path | Timestamped sequence of known poses for the VEHICLE. Recall that the sensor has a relative pose wrt the vehicle according to CObservationVelodyneScan::getSensorPose() & CObservationVelodyneScan::setSensorPose() |
[out] | out_points | The generated points, in the same coordinates frame than vehicle_path. Points are APPENDED to the list, so prevous contents are kept. |
[out] | results_stats | Stats |
[in] | params | Filtering and other parameters |
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().
|
virtual |
Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
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.
|
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.
Reimplemented from mrpt::obs::CObservation.
Definition at line 91 of file CObservationVelodyneScan.cpp.
References originalReceivedTimestamp.
|
virtual |
Returns information about the class of an object in runtime.
Reimplemented from mrpt::obs::CObservation.
|
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.
Definition at line 38 of file CObservation.cpp.
|
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.
Implements mrpt::obs::CObservation.
Definition at line 217 of file CObservationVelodyneScan.h.
|
inlineinherited |
Returns CObservation::timestamp for all kind of observations.
Definition at line 56 of file obs/CObservation.h.
|
inlineinherited |
This method is equivalent to:
theMap | The map where this observation is to be inserted: the map will be updated. |
robotPose | The pose of the robot base for this observation, relative to the target metric map. Set to NULL (default) to use (0,0,0deg) |
See: Maps and observations compatibility matrix
Definition at line 77 of file obs/CObservation.h.
Referenced by mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference().
|
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.
Reimplemented in mrpt::obs::CObservation3DRangeScan.
Definition at line 119 of file obs/CObservation.h.
Definition at line 59 of file CObservationVelodyneScan.h.
|
inline |
Definition at line 59 of file CObservationVelodyneScan.h.
|
inline |
Definition at line 59 of file CObservationVelodyneScan.h.
Definition at line 59 of file CObservationVelodyneScan.h.
|
inline |
Definition at line 59 of file CObservationVelodyneScan.h.
|
inline |
Definition at line 59 of file CObservationVelodyneScan.h.
|
inlinestatic |
Definition at line 59 of file CObservationVelodyneScan.h.
|
inline |
Definition at line 59 of file CObservationVelodyneScan.h.
|
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.
in | The input binary stream where the object data must read from. |
version | The version of the object stored in the stream: use this version number in your code to know how to read the incoming data. |
std::exception | On any error, see CStream::ReadBuffer |
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.
|
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.
Definition at line 45 of file CObservation.cpp.
|
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.
Implements mrpt::obs::CObservation.
Definition at line 218 of file CObservationVelodyneScan.h.
|
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().
|
inlinevirtualinherited |
Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).
Reimplemented in mrpt::obs::CObservation3DRangeScan.
Definition at line 123 of file obs/CObservation.h.
|
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.
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.
|
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.
out | The output binary stream where object must be dumped. |
getVersion | If 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. |
std::exception | On any error, see CStream::WriteBuffer |
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.
|
staticprotected |
Definition at line 59 of file CObservationVelodyneScan.h.
|
static |
Definition at line 70 of file CObservationVelodyneScan.h.
|
static |
Definition at line 84 of file CObservationVelodyneScan.h.
Referenced by generatePointCloudAlongSE3Trajectory(), and velodyne_scan_to_pointcloud().
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().
|
staticinherited |
|
staticinherited |
Definition at line 43 of file obs/CObservation.h.
|
static |
Definition at line 59 of file CObservationVelodyneScan.h.
|
staticinherited |
Definition at line 42 of file CSerializable.h.
|
static |
Definition at line 59 of file CObservationVelodyneScan.h.
|
static |
Definition at line 183 of file CObservationVelodyneScan.h.
|
static |
meters
Definition at line 75 of file CObservationVelodyneScan.h.
|
static |
Definition at line 77 of file CObservationVelodyneScan.h.
|
static |
meters
Definition at line 76 of file CObservationVelodyneScan.h.
Referenced by velodyne_scan_to_pointcloud().
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().
|
static |
Blocks 32-63.
Definition at line 80 of file CObservationVelodyneScan.h.
Referenced by velodyne_scan_to_pointcloud().
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().
double mrpt::obs::CObservationVelodyneScan::minRange |
Definition at line 130 of file CObservationVelodyneScan.h.
Referenced by getDescriptionAsText(), readFromStream(), velodyne_scan_to_pointcloud(), and writeToStream().
mrpt::system::TTimeStamp mrpt::obs::CObservationVelodyneScan::originalReceivedTimestamp |
The local computer-based timestamp based on the reception of the message in the computer.
Definition at line 134 of file CObservationVelodyneScan.h.
Referenced by getOriginalReceivedTimeStamp(), and readFromStream().
|
static |
Definition at line 82 of file CObservationVelodyneScan.h.
|
static |
Definition at line 85 of file CObservationVelodyneScan.h.
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
Definition at line 157 of file CObservationVelodyneScan.h.
Referenced by generatePointCloud(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::CPointsMap::loadFromVelodyneScan(), readFromStream(), and writeToStream().
|
static |
Definition at line 83 of file CObservationVelodyneScan.h.
|
static |
Definition at line 68 of file CObservationVelodyneScan.h.
|
static |
Definition at line 90 of file CObservationVelodyneScan.h.
Referenced by velodyne_scan_to_pointcloud().
|
static |
Definition at line 89 of file CObservationVelodyneScan.h.
|
static |
Definition at line 88 of file CObservationVelodyneScan.h.
|
static |
hundredths of degrees
Definition at line 73 of file CObservationVelodyneScan.h.
Referenced by generatePointCloud(), and velodyne_scan_to_pointcloud().
|
static |
degrees
Definition at line 72 of file CObservationVelodyneScan.h.
Referenced by generatePointCloud().
std::vector<TVelodyneRawPacket> mrpt::obs::CObservationVelodyneScan::scan_packets |
The main content of this object: raw data packet from the LIDAR.
Definition at line 132 of file CObservationVelodyneScan.h.
Referenced by generatePointCloudAlongSE3Trajectory(), getDescriptionAsText(), readFromStream(), velodyne_scan_to_pointcloud(), and writeToStream().
|
static |
Definition at line 69 of file CObservationVelodyneScan.h.
Referenced by generatePointCloudAlongSE3Trajectory().
|
static |
Definition at line 86 of file CObservationVelodyneScan.h.
|
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().
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().
|
static |
Definition at line 67 of file CObservationVelodyneScan.h.
|
inherited |
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based timestamp of the sensor reading.
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().
|
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 |