Go to the documentation of this file.
89 template <
class POINTMAP>
256 virtual void load()
const override;
261 virtual void unload()
override;
314 template <
class POINTMAP>
316 POINTMAP& dest_pointcloud,
320 detail::project3DPointsFromDepthImageInto<POINTMAP>(
321 *
this, dest_pointcloud, projectParams, filterParams);
332 p.takeIntoAccountSensorPoseOnRobot =
false;
333 p.PROJ3D_USE_LUT = PROJ3D_USE_LUT;
530 using Ptr = std::shared_ptr<TPixelLabelInfoBase>;
543 throw std::runtime_error(
544 "Error: label index has no defined name");
558 if (it->second ==
name)
return it->first;
565 virtual void setSize(
const int NROWS,
const int NCOLS) = 0;
571 const int row,
const int col,
uint8_t label_idx) = 0;
573 const int row,
const int col,
uint8_t& labels) = 0;
579 const int row,
const int col,
uint8_t label_idx) = 0;
583 const int row,
const int col,
uint8_t label_idx) = 0;
588 const int row,
const int col,
uint8_t label_idx)
const = 0;
617 virtual void Print(std::ostream&)
const = 0;
620 template <
unsigned int BYTES_REQUIRED_>
623 using Ptr = std::shared_ptr<TPixelLabelInfo>;
643 Eigen::Matrix<bitmask_t, Eigen::Dynamic, Eigen::Dynamic>;
646 void setSize(
const int NROWS,
const int NCOLS)
override
648 pixelLabels = TPixelLabelMatrix::Zero(NROWS, NCOLS);
660 const int row,
const int col,
uint8_t label_idx)
override
669 const int row,
const int col,
uint8_t label_idx)
const override
672 (
static_cast<bitmask_t>(1) << label_idx)) != 0;
683 void Print(std::ostream& out)
const override
688 out <<
"Number of rows: " << nR << std::endl;
689 out <<
"Number of cols: " << nC << std::endl;
690 out <<
"Matrix of labels: " << std::endl;
700 out <<
"Label indices and names: " << std::endl;
704 out << it->first <<
" " << it->second << std::endl;
770 const unsigned int& r2,
const unsigned int& c1,
const unsigned int& c2);
803 mrpt::obs::CObservation3DRangeScan, float>
812 static const int HAS_RGB = 0;
814 static const int HAS_RGBf = 0;
816 static const int HAS_RGBu8 = 0;
820 : m_obj(*const_cast<
mrpt::obs::CObservation3DRangeScan*>(&
obj))
833 template <
typename T>
852 "mrpt::obs::CObservation3DRangeScan requires needs to be dense");
863 #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.
virtual void setSize(const int NROWS, const int NCOLS)=0
Resizes the matrix pixelLabels to the given size, setting all bitfields to zero (that is,...
std::string sensorLabel
The sensor label that will have the newly created observation.
void resize(const size_t N)
Set number of points (to uninitialized values)
void getLabels(const int row, const int col, uint8_t &labels) override
virtual void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory.
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...
const Scalar * const_iterator
bool hasPoints3D
true means the field points3D contains valid data.
#define MRPT_ENUM_TYPE_END()
std::string points3D_getExternalStorageFile() const
static TPixelLabelInfoBase * readAndBuildFromStream(mrpt::serialization::CArchive &in)
static TCached3DProjTables & get_3dproj_lut()
3D point cloud projection look-up-table
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
PointCloudAdapter(const mrpt::obs::CObservation3DRangeScan &obj)
Constructor (accept a const ref for convenience)
T3DPointsTo2DScanParams()
void Print(std::ostream &out) const override
mrpt::img::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
float coords_t
The type of each point XYZ coordinates.
CObservation3DRangeScan()
Default constructor.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction.
virtual ~TPixelLabelInfoBase()
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...
void internal_writeToStream(mrpt::serialization::CArchive &out) const override
mrpt::img::TCamera prev_camParams
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
std::string rangeImage_getExternalStorageFileAbsolutePath() const
void internal_readFromStream(mrpt::serialization::CArchive &in) override
Virtual interface to all pixel-label information structs.
GLsizei GLsizei GLuint * obj
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.
bool checkLabel(const int row, const int col, uint8_t label_idx) const override
Checks whether pixel(row,col) has been clasified into category label_idx, which may be in the range 0...
double angle_sup
(Default=5 degrees) [Only if use_origin_sensor_pose=false] The upper & lower half-FOV angle (in radia...
void setSize(const int NROWS, const int NCOLS) override
Resizes the matrix pixelLabels to the given size, setting all bitfields to zero (that is,...
const uint8_t BITFIELD_BYTES
Minimum number of bytes required to hold MAX_NUM_DIFFERENT_LABELS bits.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void setLabel(const int row, const int col, uint8_t label_idx) override
Mark the pixel(row,col) as classified in the category label_idx, which may be in the range 0 to MAX_N...
bool hasPixelLabels() const
Returns true if the field CObservation3DRangeScan::pixelLabels contains a non-NULL smart pointer.
std::shared_ptr< TPixelLabelInfoBase > Ptr
Used in CObservation3DRangeScan::pixelLabels.
#define THROW_EXCEPTION(msg)
bool rangeImage_isExternallyStored() const
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
std::vector< float > points3D_y
Used in CObservation3DRangeScan::convertTo2DScan()
void project3DPointsFromDepthImage(const bool PROJ3D_USE_LUT=true)
This method is equivalent to project3DPointsFromDepthImageInto() storing the projected 3D points (wit...
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 ...
mrpt::math::CVectorFloat 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.
Virtual base class for "archives": classes abstracting I/O streams.
mrpt::img::TCamera cameraParams
Projection parameters of the depth camera.
virtual void Print(std::ostream &) const =0
GLuint const GLchar * name
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
std::map< uint32_t, std::string > TMapLabelID2Name
int checkLabelNameExistence(const std::string &name) const
Check the existence of a label by returning its associated index.
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 ...
GLdouble GLdouble GLdouble r
size_t getScanSize() const
Get the size of the scan pointcloud.
bool PROJ3D_USE_LUT
(Default:true) [Only used when range_is_depth=true] Whether to use a Look-up-table (LUT) to speed up ...
virtual ~CObservation3DRangeScan()
Destructor.
void setLabelName(unsigned int label_idx, const std::string &name)
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
friend std::ostream & operator<<(std::ostream &out, const TPixelLabelInfoBase &obj)
std stream interface
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
This class is a "CSerializable" wrapper for "CMatrixFloat".
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
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).
TPixelLabelMatrix pixelLabels
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.
TPixelLabelInfoBase(unsigned int BITFIELD_BYTES_)
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.
T3DPointsProjectionParams()
bool USE_SSE2
(Default:true) If possible, use SSE2 optimized code.
void unsetAll(const int row, const int col, uint8_t label_idx) override
Removes all categories for pixel(row,col)
double z_min
(Default:-inf, +inf) [Only if use_origin_sensor_pose=true] Only obstacle points with Z coordinates wi...
std::vector< uint16_t > points3D_idxs_y
virtual void unsetLabel(const int row, const int col, uint8_t label_idx)=0
For the pixel(row,col), removes its classification into the category label_idx, which may be in the r...
Structure to hold the parameters of a pinhole camera 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 project3DPointsFromDepthImageInto(mrpt::obs::CObservation3DRangeScan &src_obs, POINTMAP &dest_pointcloud, const mrpt::obs::T3DPointsProjectionParams &projectParams, const mrpt::obs::TRangeImageFilterParams &filterParams)
Look-up-table struct for project3DPointsFromDepthImageInto()
void unsetLabel(const int row, const int col, uint8_t label_idx) override
For the pixel(row,col), removes its classification into the category label_idx, which may be in the r...
virtual void internal_writeToStream(mrpt::serialization::CArchive &out) const =0
@ CH_IR
Infrarred (IR) channel.
typename mrpt::uint_select_by_bytecount< BYTES_REQUIRED >::type bitmask_t
Automatically-determined integer type of the proper size such that all labels fit as one bit (max: 64...
std::string rangeImage_getExternalStorageFile() const
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>
const mrpt::poses::CPose3D * robotPoseInTheWorld
(Default: nullptr) Read takeIntoAccountSensorPoseOnRobot
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters)
bool MAKE_DENSE
(Default:true) set to false if you want to preserve the organization of the point cloud
Eigen::Matrix< bitmask_t, Eigen::Dynamic, Eigen::Dynamic > TPixelLabelMatrix
Each pixel may be assigned between 0 and MAX_NUM_LABELS-1 'labels' by setting to 1 the corresponding ...
bool doDepthAndIntensityCamerasCoincide() const
Return true if relativePoseIntensityWRTDepth equals the pure rotation (0,0,0,-90deg,...
GLenum GLenum GLvoid * row
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
GLsizei const GLfloat * value
A helper base class for those PointCloudAdapter<> which do not handle RGB data; it declares needed in...
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.
const std::string & getLabelName(unsigned int label_idx) const
virtual void setLabel(const int row, const int col, uint8_t label_idx)=0
Mark the pixel(row,col) as classified in the category label_idx, which may be in the range 0 to MAX_N...
Declares a class that represents any robot's observation.
void project3DPointsFromDepthImageInto(POINTMAP &dest_pointcloud, const T3DPointsProjectionParams &projectParams, const TRangeImageFilterParams &filterParams=TRangeImageFilterParams())
Project the RGB+D images into a 3D point cloud (with color if the target map supports it) and optiona...
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
GLsizei const GLchar ** string
virtual bool checkLabel(const int row, const int col, uint8_t label_idx) const =0
Checks whether pixel(row,col) has been clasified into category label_idx, which may be in the range 0...
mrpt::math::CVectorFloat Kys
size_t size() const
Get number of points.
virtual void getLabels(const int row, const int col, uint8_t &labels)=0
virtual void unload() override
Unload all images, for the case they being delayed-load images stored in external files (othewise,...
virtual void internal_readFromStream(mrpt::serialization::CArchive &in)=0
bool use_origin_sensor_pose
(Default:false) If false, the conversion will be such that the 2D observation pose on the robot coinc...
Usage: uint_select_by_bytecount<N>type var; allows defining var as a unsigned integer with,...
double oversampling_ratio
(Default=1.2=120%) How many more laser scans rays to create (read docs for CObservation3DRangeScan::c...
bool takeIntoAccountSensorPoseOnRobot
(Default: false) If false, local (sensor-centric) coordinates of points are generated.
mrpt::obs::CObservation3DRangeScan & m_obj
void swap(CObservation3DRangeScan &o)
Very efficient method to swap the contents of two observations.
static bool EXTERNALS_AS_TEXT()
void rangeImage_forceResetExternalStorage()
Forces marking this observation as non-externally stored - it doesn't anything else apart from reseti...
virtual void unsetAll(const int row, const int col, uint8_t label_idx)=0
Removes all categories for pixel(row,col)
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
unsigned __int32 uint32_t
bool m_rangeImage_external_stored
If set to true, m_rangeImage_external_file is valid.
TMapLabelID2Name pixelLabelNames
The 'semantic' or human-friendly name of the i'th bit in pixelLabels(r,c) can be found in pixelLabelN...
void writeToStream(mrpt::serialization::CArchive &out) const
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |