88 template <
class POINTMAP>
255 void load()
const override;
313 template <
class POINTMAP>
315 POINTMAP& dest_pointcloud,
319 detail::project3DPointsFromDepthImageInto<POINTMAP>(
320 *
this, dest_pointcloud, projectParams, filterParams);
331 p.takeIntoAccountSensorPoseOnRobot =
false;
332 p.PROJ3D_USE_LUT = PROJ3D_USE_LUT;
541 throw std::runtime_error(
542 "Error: label index has no defined name");
553 std::map<uint32_t, std::string>::const_iterator it;
556 if (it->second ==
name)
return it->first;
563 virtual void setSize(
const int NROWS,
const int NCOLS) = 0;
569 const int row,
const int col,
uint8_t label_idx) = 0;
571 const int row,
const int col,
uint8_t& labels) = 0;
577 const int row,
const int col,
uint8_t label_idx) = 0;
581 const int row,
const int col,
uint8_t label_idx) = 0;
586 const int row,
const int col,
uint8_t label_idx)
const = 0;
615 virtual void Print(std::ostream&)
const = 0;
618 template <
unsigned int BYTES_REQUIRED_>
643 void setSize(
const int NROWS,
const int NCOLS)
override 657 const int row,
const int col,
uint8_t label_idx)
override 666 const int row,
const int col,
uint8_t label_idx)
const override 669 (static_cast<bitmask_t>(1) << label_idx)) != 0;
680 void Print(std::ostream& out)
const override 685 out <<
"Number of rows: " << nR << std::endl;
686 out <<
"Number of cols: " << nC << std::endl;
687 out <<
"Matrix of labels: " << std::endl;
697 out <<
"Label indices and names: " << std::endl;
698 std::map<uint32_t, std::string>::const_iterator it;
701 out << it->first <<
" " << it->second << std::endl;
767 const unsigned int& r2,
const unsigned int& c1,
const unsigned int& c2);
807 static constexpr
bool HAS_RGB =
false;
809 static constexpr
bool HAS_RGBf =
false;
811 static constexpr
bool HAS_RGBu8 =
false;
815 : m_obj(*const_cast<
mrpt::obs::CObservation3DRangeScan*>(&
obj))
829 template <
typename T>
848 "mrpt::obs::CObservation3DRangeScan requires needs to be dense");
859 #include "CObservation3DRangeScan_project3D_impl.h" virtual ~TPixelLabelInfoBase()=default
bool m_points3D_external_stored
If set to true, m_points3D_external_file is valid.
std::string m_rangeImage_external_file
rangeImage is in CImage::getImagesPathBase()+<this_file_name>
std::string rangeImage_getExternalStorageFile() const
mrpt::img::TCamera cameraParams
Projection parameters of the depth camera.
void setDimensions(const size_t &height, const size_t &width)
Does nothing as of now.
static bool EXTERNALS_AS_TEXT()
const std::string & getLabelName(unsigned int label_idx) const
void writeToStream(mrpt::serialization::CArchive &out) const
bool points3D_isExternallyStored() const
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.
TIntensityChannelID
Enum type for intensityImageChannel.
uint8_t decimation
(Default:1) If !=1, split the range image in blocks of DxD (D=decimation), and only generates one poi...
void resizePoints3DVectors(const size_t nPoints)
Use this method instead of resizing all three points3D_x, points3D_y & points3D_z to allow the usage ...
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...
const mrpt::poses::CPose3D * robotPoseInTheWorld
(Default: nullptr) Read takeIntoAccountSensorPoseOnRobot
#define THROW_EXCEPTION(msg)
MRPT_FILL_ENUM_MEMBER(mrpt::obs::CObservation3DRangeScan, CH_VISIBLE)
void setLabelName(unsigned int label_idx, const std::string &name)
TPixelLabelInfoBase(unsigned int BITFIELD_BYTES_)
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...
T3DPointsTo2DScanParams()
std::string sensorLabel
The sensor label that will have the newly created observation.
void project3DPointsFromDepthImage(const bool PROJ3D_USE_LUT=true)
This method is equivalent to project3DPointsFromDepthImageInto() storing the projected 3D points (wit...
std::vector< uint16_t > points3D_idxs_x
If hasPoints3D=true, the (x,y) pixel coordinates for each (X,Y,Z) point in points3D_x, points3D_y, points3D_z.
std::string points3D_getExternalStorageFile() const
double oversampling_ratio
(Default=1.2=120%) How many more laser scans rays to create (read docs for CObservation3DRangeScan::c...
double angle_sup
(Default=5 degrees) [Only if use_origin_sensor_pose=false] The upper & lower half-FOV angle (in radia...
mrpt::math::CMatrixF rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) ...
bool m_rangeImage_external_stored
If set to true, m_rangeImage_external_file is valid.
virtual void internal_readFromStream(mrpt::serialization::CArchive &in)=0
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
Look-up-table struct for project3DPointsFromDepthImageInto()
static TPixelLabelInfoBase * readAndBuildFromStream(mrpt::serialization::CArchive &in)
friend std::ostream & operator<<(std::ostream &out, const TPixelLabelInfoBase &obj)
std stream interface
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
std::map< uint32_t, std::string > TMapLabelID2Name
double z_min
(Default:-inf, +inf) [Only if use_origin_sensor_pose=true] Only obstacle points with Z coordinates wi...
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...
GLsizei GLsizei GLuint * obj
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...
void resize(const size_t N)
Set number of points (to uninitialized values)
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
CObservation3DRangeScan()
Default constructor.
Usage: uint_select_by_bytecount<N>type var; allows defining var as a unsigned integer with...
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
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.
std::vector< float > points3D_z
const uint8_t BITFIELD_BYTES
Minimum number of bytes required to hold MAX_NUM_DIFFERENT_LABELS bits.
void internal_writeToStream(mrpt::serialization::CArchive &out) const override
PointCloudAdapter(const mrpt::obs::CObservation3DRangeScan &obj)
Constructor (accept a const ref for convenience)
std::string rangeImage_getExternalStorageFileAbsolutePath() const
void internal_readFromStream(mrpt::serialization::CArchive &in) override
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
std::vector< float > points3D_y
An adapter to different kinds of point cloud object.
std::vector< uint16_t > points3D_idxs_y
bool rangeImage_isExternallyStored() const
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...
TMapLabelID2Name pixelLabelNames
The 'semantic' or human-friendly name of the i'th bit in pixelLabels(r,c) can be found in pixelLabelN...
float coords_t
The type of each point XYZ coordinates.
void unload() override
Unload all images, for the case they being delayed-load images stored in external files (othewise...
void swap(CObservation3DRangeScan &o)
Very efficient method to swap the contents of two observations.
void project3DPointsFromDepthImageInto(mrpt::obs::CObservation3DRangeScan &src_obs, POINTMAP &dest_pointcloud, const mrpt::obs::T3DPointsProjectionParams &projectParams, const mrpt::obs::TRangeImageFilterParams &filterParams)
mrpt::img::TCamera prev_camParams
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...
T3DPointsProjectionParams()=default
void Print(std::ostream &out) const override
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...
Used in CObservation3DRangeScan::convertTo2DScan()
int checkLabelNameExistence(const std::string &name) const
Check the existence of a label by returning its associated index.
std::string m_points3D_external_file
3D points are in CImage::getImagesPathBase()+<this_file_name>
bool hasRangeImage
true means the field rangeImage contains valid data
Structure to hold the parameters of a pinhole camera model.
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...
TIntensityChannelID intensityImageChannel
The source of the intensityImage; typically the visible channel.
#define MRPT_ENUM_TYPE_END()
void rangeImage_forceResetExternalStorage()
Forces marking this observation as non-externally stored - it doesn't anything else apart from reseti...
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.
mrpt::img::CImage confidenceImage
If hasConfidenceImage=true, an image with the "confidence" value [range 0-255] as estimated by the ca...
std::string points3D_getExternalStorageFileAbsolutePath() const
bool hasPoints3D
true means the field points3D contains valid data.
GLsizei const GLchar ** string
size_type rows() const
Number of rows in the matrix.
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
size_type cols() const
Number of columns in the matrix.
const Scalar & coeff(int r, int c) const
bool USE_SSE2
(Default:true) If possible, use SSE2 optimized code.
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
This class is a "CSerializable" wrapper for "CMatrixFloat".
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
void setSize(const int NROWS, const int NCOLS) override
Resizes the matrix pixelLabels to the given size, setting all bitfields to zero (that is...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
mrpt::aligned_std_vector< float > Kys
Virtual base class for "archives": classes abstracting I/O streams.
size_t size() const
Get number of points.
bool MAKE_ORGANIZED
(Default:false) set to true if you want an organized point cloud
GLdouble GLdouble GLdouble r
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
void getPointXYZ(const size_t idx, T &x, T &y, T &z) const
Get XYZ coordinates of i'th point.
void getLabels(const int row, const int col, uint8_t &labels) override
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Declares a class that represents any robot's observation.
TPixelLabelInfoBase::Ptr pixelLabels
All information about pixel labeling is stored in this (smart pointer to) structure; refer to TPixelL...
static TCached3DProjTables & get_3dproj_lut()
3D point cloud projection look-up-table
GLenum GLenum GLvoid * row
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
virtual void internal_writeToStream(mrpt::serialization::CArchive &out) const =0
bool hasIntensityImage
true means the field intensityImage contains valid data
void setInvalidPoint(const size_t idx)
Set XYZ coordinates of i'th point.
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...
std::vector< float > points3D_x
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera...
GLuint const GLchar * name
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 ...
bool hasPixelLabels() const
Returns true if the field CObservation3DRangeScan::pixelLabels contains a non-NULL smart pointer...
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...
virtual void Print(std::ostream &) const =0
mrpt::obs::CObservation3DRangeScan & m_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 PROJ3D_USE_LUT
(Default:true) [Only used when range_is_depth=true] Whether to use a Look-up-table (LUT) to speed up ...
bool doDepthAndIntensityCamerasCoincide() const
Return true if relativePoseIntensityWRTDepth equals the pure rotation (0,0,0,-90deg,0,-90deg) (with a small comparison epsilon)
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...
GLsizei const GLfloat * value
virtual void unsetAll(const int row, const int col, uint8_t label_idx)=0
Removes all categories for pixel(row,col)
mrpt::img::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
~CObservation3DRangeScan() override
Destructor.
GLenum GLsizei GLsizei height
size_t getScanSize() const
Get the size of the scan pointcloud.
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
unsigned __int32 uint32_t
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
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...
TPixelLabelMatrix pixelLabels
mrpt::aligned_std_vector< float > Kzs
Virtual interface to all pixel-label information structs.
void unsetAll(const int row, const int col, uint8_t label_idx) override
Removes all categories for pixel(row,col)
Grayscale or RGB visible channel of the camera sensor.
bool takeIntoAccountSensorPoseOnRobot
(Default: false) If false, local (sensor-centric) coordinates of points are generated.
void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory...
A class for storing images as grayscale or RGB bitmaps.
virtual void getLabels(const int row, const int col, uint8_t &labels)=0
bool use_origin_sensor_pose
(Default:false) If false, the conversion will be such that the 2D observation pose on the robot coinc...
float maxRange
The maximum range allowed by the device, in meters (e.g.
bool hasConfidenceImage
true means the field confidenceImage contains valid data