Class CObservationRotatingScan
Defined in File CObservationRotatingScan.h
Inheritance Relationships
Base Type
public mrpt::obs::CObservation(Class CObservation)
Class Documentation
-
class CObservationRotatingScan : public mrpt::obs::CObservation
A
CObservation-derived class for raw range data from a 2D or 3D rotating scanner. This class is the preferred alternative to CObservationVelodyneScan and CObservation2DRangeScan in MRPT 2.x, since it exposes range data as an organized matrix, more convenient for feature detection directly on “range images” and on points stored as a matrix in the member organizedPoints.Check out the main data fields in the list of members below.
Note that this object has two timestamp fields:
The standard
CObservation::timestampfield in the base class, which should contain the accurate satellite-based UTC timestamp if available, andthe field originalReceivedTimestamp, with the local computer-based timestamp based on the reception of the message in the computer.
Both timestamps correspond to the firing of the first laser in the scan, i.e. the first column in organizedPoints.
The reference frame for the 3D LIDAR is with +X pointing forward, +Z up.
Note
New in MRPT 2.0.0
Scan range data
-
uint16_t rowCount = {0}
Number of “Lidar rings” (e.g. 16 for a Velodyne VLP16, etc.). This should be constant for a given LiDAR scanner. All matrices defined below have this number of rows.
-
uint16_t columnCount = {0}
Number of lidar “firings” for this scan. It is assumed that firings occur at a fixed rate. Consecutive scans (“scan”=instance of this class) may have different number of firings, and different start and end azimuth. All matrices defined below have this number of columns.
-
mrpt::math::CMatrix_u16 rangeImage = {0, 0}
The NxM matrix of distances (ranges) for each direction (columns) and for each laser “ring” (rows). Matrix element are integers for efficiency of post-processing filters, etc. Zero means no return (i.e. invalid range). This member must be always provided, containing the ranges for the STRONGEST ray returns. To obtain ranges in meters, multiply this matrix by
rangeResolution.See also
-
mrpt::math::CMatrixDynamic<mrpt::math::TPoint3Df> organizedPoints = {0, 0}
If present, it contains all 3D points, in local coordinates wrt the sensor, for all !=0 entries in rangeImage.
-
mrpt::math::CMatrix_u8 intensityImage = {0, 0}
Optionally, an intensity channel. Matrix with a 0x0 size if not provided.
-
std::map<std::string, mrpt::math::CMatrix_u16> rangeOtherLayers
Optional additional layers, e.g. LAST return, etc. for lidars with multiple returns per firing. A descriptive name of what the alternative range means as std::map Key, e.g.
FIRST,SECOND.
-
double rangeResolution
Real-world scale (in meters) of integer units in range images (e.g. 0.002 means 1 range unit is 2 millimeters)
-
double startAzimuth = {-M_PI}
Azimuth of the first and last columns in
ranges, with respect to the sensor forward direction. Note that startAzimuth may be possitive or negative, and azimuthSpan can be too to reflect the direction of rotation of the scanner: >0 is CCW, <0 is CW.
-
double azimuthSpan = {2 * M_PI}
-
double sweepDuration = {.0}
Time (in seconds) that passed since
startAzimuth(first column) toendAzimuth(last column).
-
std::string lidarModel = {"UNKNOWN_SCANNER"}
The driver should fill in this observation
-
double minRange = {1.0}
The maximum range allowed by the device, in meters (e.g. 100m). Stored here by the driver while capturing based on the sensor model.
-
double maxRange = {130.0}
-
mrpt::poses::CPose3D sensorPose
The SE(3) pose of the sensor on the robot/vehicle frame of reference
-
mrpt::system::TTimeStamp originalReceivedTimestamp = {INVALID_TIMESTAMP}
The local computer-based timestamp based on the reception of the message in the computer.
See also
has_satellite_timestamp, CObservation::timestamp in the base class, which should contain the accurate satellite-based UTC timestamp.
-
bool has_satellite_timestamp = {false}
If true, CObservation::timestamp has been generated from accurate satellite clock. Otherwise, no GPS data is available and timestamps are based on the local computer clock.
“Convert from” API
-
void fromVelodyne(const mrpt::obs::CObservationVelodyneScan &o)
-
void fromScan2D(const mrpt::obs::CObservation2DRangeScan &o)
-
bool fromGeneric(const mrpt::obs::CObservation &o)
Will convert from another observation if it’s any of the supported source types (see fromVelodyne(), fromScan2D()) and return true, or will return false otherwise if there is no known way to convert from the passed object.
Delayed-load manual control methods.
-
virtual void load_impl() const override
Point cloud external storage functions
-
inline bool isExternallyStored() const
-
inline const std::string &getExternalStorageFile() const
-
void setAsExternalStorage(const std::string &fileName, const ExternalStorageFormat fmt)
-
inline void overrideExternalStorageFormatFlag(const ExternalStorageFormat fmt)
-
bool saveToTextFile(const std::string &filename) const
Write scan data to a plain text, each line has:
x y z range intensity row_idx col_idxFor each point in the organized point cloud. Invalid points (e.g. no lidar return) are stored as (x,y,z)=(0,0,0) and range=0.
- Returns:
true on success
-
bool loadFromTextFile(const std::string &filename)
Loads the range, intensity, and organizedPoints members from a plain text file in the format describd in saveToTextFile()
Public Types
-
enum class ExternalStorageFormat : uint8_t
Values:
-
enumerator None
is always stored in memory
-
enumerator MRPT_Serialization
Uses mrpt-serialization binary file
-
enumerator PlainTextFile
Plain text, format explained in saveToTextFile()
-
enumerator None
Public Functions
-
virtual mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const override
By default, returns CObservation::timestamp but in sensors capable of satellite (or otherwise) accurate UTC timing of readings, this contains the computer-based timestamp of reception, which may be slightly different than timestamp
See also
-
inline virtual void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot. Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.
See also
-
inline virtual void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot. Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.
See also
-
virtual void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
Note
If overried by derived classes, call base CObservation::getDescriptionAsText() first to show common information.
Note
This is the text that appears in RawLogViewer when selecting an object in the dataset
Protected Attributes
-
ExternalStorageFormat m_externally_stored = ExternalStorageFormat::None
-
std::string m_external_file