class mrpt::obs::CObservationPointCloud
An observation from any sensor that can be summarized as a pointcloud.
The cloud can comprise plain XYZ points, or can include intensity, or RGB data; in particular, the point cloud can be any of the derived classes of mrpt::maps::CPointsMap.
The pointcloud has as frame of coordinates the sensorPose
field, which may match the origin of the vehicle/robot or not.
This is a mrpt::obs::CObservation class, but it is defined in the mrpt_maps_grp library, so it can use mrpt::maps::CPointsMap.
See also:
CObservation, mrpt::maps::CPointsMap
#include <mrpt/obs/CObservationPointCloud.h> class CObservationPointCloud: public mrpt::obs::CObservation { public: // enums enum ExternalStorageFormat; // fields mrpt::maps::CPointsMap::Ptr pointcloud; mrpt::poses::CPose3D sensorPose; // construction CObservationPointCloud(); CObservationPointCloud(const CObservation3DRangeScan& o); // methods virtual void load() const; virtual void unload() const; bool isExternallyStored() const; const std::string& getExternalStorageFile() const; void setAsExternalStorage( const std::string& fileName, const ExternalStorageFormat fmt ); void overrideExternalStorageFormatFlag(const ExternalStorageFormat fmt); More efficient for converting a pointcloud(); virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const; virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose); virtual void getDescriptionAsText(std::ostream& o) const; };
Inherited Members
public: // fields mrpt::system::TTimeStamp timestamp {mrpt::system::now()}; std::string sensorLabel; // methods mrpt::system::TTimeStamp getTimeStamp() const; virtual mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const; virtual bool exportTxtSupported() const; virtual std::string exportTxtHeader() const; virtual std::string exportTxtDataRow() const; virtual void load() const; virtual void unload() const; template <class METRICMAP> bool insertObservationInto( METRICMAP& theMap, const std::optional<const mrpt::poses::CPose3D>& robotPose = std::nullopt ) const; virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const = 0; void getSensorPose(mrpt::math::TPose3D& out_sensorPose) const; mrpt::math::TPose3D sensorPose() const; virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose) = 0; void setSensorPose(const mrpt::math::TPose3D& newSensorPose); virtual void getDescriptionAsText(std::ostream& o) const; virtual std::string asString() const;
Fields
mrpt::maps::CPointsMap::Ptr pointcloud
The pointcloud.
mrpt::poses::CPose3D sensorPose
Sensor placement wrt the vehicle/robot.
i.e. A point at (0,0,0) in pointcloud is at sensorPose wrt the vehicle.
Methods
virtual void load() const
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:
virtual void unload() const
Unload all images, for the case they being delayed-load images stored in external files (othewise, has no effect).
See also:
More efficient for converting a pointcloud()
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
virtual void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const
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:
virtual void setSensorPose(const mrpt::poses::CPose3D& newSensorPose)
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
Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
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