Go to the documentation of this file.
35 template <
class POINTMAP>
199 void load()
const override;
256 template <
class POINTMAP>
258 POINTMAP& dest_pointcloud,
263 detail::unprojectInto<POINTMAP>(
264 *
this, dest_pointcloud, projectParams, filterParams);
355 std::string& out_path)
const;
365 const std::string& fileName,
const std::string& use_this_base_dir);
417 const std::optional<mrpt::img::TColormap> color = std::nullopt,
418 const std::optional<float> normMinRange = std::nullopt,
419 const std::optional<float> normMaxRange = std::nullopt,
420 const std::optional<std::string> additionalLayerName =
430 const std::optional<mrpt::img::TColormap> color = std::nullopt);
441 const std::string& rangeImageLayer)
const;
446 std::string& out_path,
const std::string& rangeImageLayer)
const;
448 const std::string& rangeImageLayer)
const
457 const std::string& fileName,
const std::string& use_this_base_dir);
534 0, 0, 0, -90.0_deg, 0.0_deg, -90.0_deg};
578 const unsigned int& r2,
const unsigned int& c1,
const unsigned int& c2);
630 static constexpr
bool HAS_RGB =
false;
632 static constexpr
bool HAS_RGBf =
false;
634 static constexpr
bool HAS_RGBu8 =
false;
638 : m_obj(*const_cast<
mrpt::obs::CObservation3DRangeScan*>(&obj))
652 template <
typename T>
682 #include "CObservation3DRangeScan_project3D_impl.h"
MRPT_FILL_ENUM_MEMBER(mrpt::obs::CObservation3DRangeScan, CH_VISIBLE)
TIntensityChannelID
Enum type for intensityImageChannel.
An adapter to different kinds of point cloud object.
void points3D_overrideExternalStoredFlag(bool isExternal)
Users normally won't need to use this.
void resize(const size_t N)
Set number of points (to uninitialized values)
void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory.
mrpt::aligned_std_vector< float > Kxs
x,y,z: +X pointing forward (depth), +z up These doesn't account for the sensor pose.
void setInvalidPoint(const size_t idx)
Set XYZ coordinates of i'th point.
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
bool hasPoints3D
true means the field points3D contains valid data.
#define MRPT_ENUM_TYPE_END()
std::string points3D_getExternalStorageFile() const
Used in CObservation3DRangeScan::unprojectInto()
PointCloudAdapter(const mrpt::obs::CObservation3DRangeScan &obj)
Constructor (accept a const ref for convenience)
void rangeImage_getExternalStorageFileAbsolutePath(std::string &out_path, const std::string &rangeImageLayer) const
rangeImageLayer: Empty for the main rangeImage matrix, otherwise, a key of rangeImageOtherLayers
std::shared_ptr< TPixelLabelInfoBase > Ptr
Used in CObservation3DRangeScan::pixelLabels.
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
mrpt::img::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
float coords_t
The type of each point XYZ coordinates.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
void undistort()
Removes the distortion in both, depth and intensity images.
mrpt::aligned_std_vector< float > Kys_rot
static double recoverCameraCalibrationParameters(const CObservation3DRangeScan &in_obs, mrpt::img::TCamera &out_camParams, const double camera_offset=0.01)
A Levenberg-Marquart-based optimizer to recover the calibration parameters of a 3D camera given a ran...
void getPointXYZ(const size_t idx, T &x, T &y, T &z) const
Get XYZ coordinates of i'th point.
void convertTo2DScan(mrpt::obs::CObservation2DRangeScan &out_scan2d, const T3DPointsTo2DScanParams &scanParams, const TRangeImageFilterParams &filterParams=TRangeImageFilterParams())
Convert this 3D observation into an "equivalent 2D fake laser scan", with a configurable vertical FOV...
std::string points3D_getExternalStorageFileAbsolutePath() const
bool m_points3D_external_stored
If set to true, m_points3D_external_file is valid.
std::vector< float > points3D_z
~CObservation3DRangeScan() override
mrpt::aligned_std_vector< float > Kys
std::map< std::string, mrpt::math::CMatrix_u16 > rangeImageOtherLayers
Additional layer range/depth images.
void points3D_convertToExternalStorage(const std::string &fileName, const std::string &use_this_base_dir)
Users won't normally want to call this, it's only used from internal MRPT programs.
std::string rangeImage_getExternalStorageFile(const std::string &rangeImageLayer) const
static mrpt::img::CImage rangeImageAsImage(const mrpt::math::CMatrix_u16 &ranges, float val_min, float val_max, float rangeUnits, const std::optional< mrpt::img::TColormap > color=std::nullopt)
Static method to convert a range matrix into an image.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool hasPixelLabels() const
Returns true if the field CObservation3DRangeScan::pixelLabels contains a non-NULL smart pointer.
bool rangeImage_isExternallyStored() const
void unprojectInto(POINTMAP &dest_pointcloud, const T3DPointsProjectionParams &projectParams=T3DPointsProjectionParams(), const TRangeImageFilterParams &filterParams=TRangeImageFilterParams())
Unprojects the RGB+D image pair into a 3D point cloud (with color if the target map supports it) and ...
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
std::vector< float > points3D_y
Used in CObservation3DRangeScan::convertTo2DScan()
void rangeImage_setSize(const int HEIGHT, const int WIDTH)
Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the ...
This namespace contains representation of robot actions and observations.
mrpt::aligned_std_vector< float > Kzs
void resizePoints3DVectors(const size_t nPoints)
Use this method instead of resizing all three points3D_x, points3D_y & points3D_z to allow the usage ...
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
mrpt::img::TCamera cameraParams
Projection parameters of the depth camera.
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
TPixelLabelInfoBase::Ptr pixelLabels
All information about pixel labeling is stored in this (smart pointer to) structure; refer to TPixelL...
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
size_t getScanSize() const
Get the size of the scan pointcloud.
mrpt::aligned_std_vector< float > Kxs_rot
x,y,z: in the rotated frame of coordinates of the sensorPose.
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
CObservation3DRangeScan()=default
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
TIntensityChannelID intensityImageChannel
The source of the intensityImage; typically the visible channel.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
bool hasIntensityImage
true means the field intensityImage contains valid data
std::string m_rangeImage_external_file
rangeImage is in CImage::getImagesPathBase()+<this_file_name>
std::vector< float > points3D_x
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera.
bool hasRangeImage
true means the field rangeImage contains valid data
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
std::vector< uint16_t > points3D_idxs_y
Parameters for the Brown-Conrady camera lens distortion model.
mrpt::img::CImage confidenceImage
If hasConfidenceImage=true, an image with the "confidence" value [range 0-255] as estimated by the ca...
std::vector< uint16_t > points3D_idxs_x
If hasPoints3D=true, the (x,y) pixel coordinates for each (X,Y,Z) point in points3D_x,...
A class for storing images as grayscale or RGB bitmaps.
void unprojectInto(mrpt::obs::CObservation3DRangeScan &src_obs, POINTMAP &dest_pointcloud, const mrpt::obs::T3DPointsProjectionParams &projectParams, const mrpt::obs::TRangeImageFilterParams &filterParams)
const unproject_LUT_t & get_unproj_lut() const
Gets (or generates upon first request) the 3D point cloud projection look-up-table for the current de...
@ CH_IR
Infrarred (IR) channel.
mrpt::math::CMatrix_u16 rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters).
float maxRange
The maximum range allowed by the device, in meters (e.g.
bool hasConfidenceImage
true means the field confidenceImage contains valid data
std::string m_points3D_external_file
3D points are in CImage::getImagesPathBase()+<this_file_name>
mrpt::aligned_std_vector< float > Kzs_rot
bool doDepthAndIntensityCamerasCoincide() const
Return true if relativePoseIntensityWRTDepth equals the pure rotation (0,0,0,-90deg,...
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
@ CH_VISIBLE
Grayscale or RGB visible channel of the camera sensor.
void getZoneAsObs(CObservation3DRangeScan &obs, const unsigned int &r1, const unsigned int &r2, const unsigned int &c1, const unsigned int &c2)
Extract a ROI of the 3D observation as a new one.
void rangeImage_convertToExternalStorage(const std::string &fileName, const std::string &use_this_base_dir)
Users won't normally want to call this, it's only used from internal MRPT programs.
Declares a class that represents any robot's observation.
void setPointXYZ(const size_t idx, const coords_t x, const coords_t y, const coords_t z)
Set XYZ coordinates of i'th point.
bool points3D_isExternallyStored() const
size_t size() const
Get number of points.
void unload() override
Unload all images, for the case they being delayed-load images stored in external files (othewise,...
std::string rangeImage_getExternalStorageFileAbsolutePath(const std::string &rangeImageLayer) const
void setDimensions(size_t height, size_t width)
Does nothing as of now.
float rangeUnits
The conversion factor from integer units in rangeImage and actual distances in meters.
mrpt::obs::CObservation3DRangeScan & m_obj
void swap(CObservation3DRangeScan &o)
Very efficient method to swap the contents of two observations.
The namespace for 3D scene representation and rendering.
static bool EXTERNALS_AS_TEXT()
void rangeImage_forceResetExternalStorage()
Forces marking this observation as non-externally stored - it doesn't anything else apart from reseti...
Used in CObservation3DRangeScan::unprojectInto()
Look-up-table struct for unprojectInto()
mrpt::img::CImage rangeImage_getAsImage(const std::optional< mrpt::img::TColormap > color=std::nullopt, const std::optional< float > normMinRange=std::nullopt, const std::optional< float > normMaxRange=std::nullopt, const std::optional< std::string > additionalLayerName=std::nullopt) const
Builds a visualization from the rangeImage.
bool m_rangeImage_external_stored
If set to true, m_rangeImage_external_file is valid.
Page generated by Doxygen 1.8.17 for MRPT 2.0.4 at Fri Jul 17 08:43:33 UTC 2020 | |