Classes | Public Member Functions | Public Attributes | Protected Member Functions | Static Protected Member Functions | Private Member Functions | Private Attributes
pcl::LineRGBD< PointXYZT, PointRGBT > Class Template Reference

High-level class for template matching using the LINEMOD approach based on RGB and Depth data. More...

#include <line_rgbd.h>

List of all members.

Classes

struct  Detection
 A LineRGBD detection. More...

Public Member Functions

bool addTemplate (const SparseQuantizedMultiModTemplate &sqmmt, pcl::PointCloud< pcl::PointXYZRGBA > &cloud, size_t object_id=0)
void computeTransformedTemplatePoints (const size_t detection_id, pcl::PointCloud< pcl::PointXYZRGBA > &cloud)
 Computes and returns the point cloud of the specified detection. This is the template point cloud transformed to the detection coordinates. The detection ID refers to the last call of the method detect (...).
int createAndAddTemplate (pcl::PointCloud< pcl::PointXYZRGBA > &cloud, const size_t object_id, const MaskMap &mask_xyz, const MaskMap &mask_rgb, const RegionXY &region)
 Creates a template from the specified data and adds it to the matching queue.
void detect (std::vector< typename pcl::LineRGBD< PointXYZT, PointRGBT >::Detection > &detections)
 Applies the detection process and fills the supplied vector with the detection instances.
void detectSemiScaleInvariant (std::vector< typename pcl::LineRGBD< PointXYZT, PointRGBT >::Detection > &detections, float min_scale=0.6944444f, float max_scale=1.44f, float scale_multiplier=1.2f)
 Applies the detection process in a semi-scale-invariant manner. This is done by acutally scaling the template to different sizes.
std::vector< size_t > findObjectPointIndices (const size_t detection_id)
 Finds the indices of the points in the input cloud which correspond to the specified detection. The detection ID refers to the last call of the method detect (...).
 LineRGBD ()
 Constructor.
bool loadTemplates (const std::string &file_name, size_t object_id=0)
 Loads templates from a LMT (LineMod Template) file. Overrides old templates.
void setDetectionThreshold (float threshold)
 Sets the threshold for the detection responses. Responses are between 0 and 1, where 1 is a best.
void setGradientMagnitudeThreshold (const float threshold)
 Sets the threshold on the magnitude of color gradients. Color gradients with a magnitude below this threshold are not considered in the detection process.
void setInputCloud (const typename pcl::PointCloud< PointXYZT >::ConstPtr &cloud)
 Sets the input cloud with xyz point coordinates. The cloud has to be organized.
void setInputColors (const typename pcl::PointCloud< PointRGBT >::ConstPtr &cloud)
 Sets the input cloud with rgb values. The cloud has to be organized.
void setIntersectionVolumeThreshold (const float threshold=1.0f)
 Sets the threshold for the decision whether two detections of the same template are merged or not. If ratio between the intersection of the bounding boxes of two detections and the original bounding boxes is larger than the specified threshold then they are merged. If detection A overlaps with detection B and B with C than A, B, and C are merged. Threshold has to be between 0 and 1.
virtual ~LineRGBD ()
 Destructor.

Public Attributes

std::vector< pcl::BoundingBoxXYZbounding_boxes_
 Bounding boxes corresonding to the templates.
pcl::PointCloud< PointRGBT >
::ConstPtr 
cloud_rgb_
 RGB point cloud.
pcl::PointCloud< PointXYZT >
::ConstPtr 
cloud_xyz_
 XYZ point cloud.
pcl::ColorGradientModality
< PointRGBT > 
color_gradient_mod_
 Color gradient modality.
std::vector< typename
pcl::LineRGBD< PointXYZT,
PointRGBT >::Detection
detections_
 Detections from last call of method detect (...).
pcl::LINEMOD linemod_
 LINEMOD instance.
std::vector< size_t > object_ids_
 Object IDs corresponding to the templates.
pcl::SurfaceNormalModality
< PointXYZT > 
surface_normal_mod_
 Surface normal modality.
pcl::PointCloud
< pcl::PointXYZRGBA >
::CloudVectorType 
template_point_clouds_
 Point clouds corresponding to the templates.

Protected Member Functions

std::vector< size_t > alignTemplatePoints (const size_t detection_id)
 Aligns the template points with the points found at the detection position of the specified detection. The detection ID refers to the last call of the method detect (...).
void applyProjectiveDepthICPOnDetections ()
 Applies projective ICP on detections to find their correct position in depth.
void refineDetectionsAlongDepth ()
 Refines the found detections along the depth.
void removeOverlappingDetections ()
 Checks for overlapping detections, removes them and keeps only the strongest one.

Static Protected Member Functions

static float computeBoundingBoxIntersectionVolume (const BoundingBoxXYZ &box1, const BoundingBoxXYZ &box2)
 Computes the volume of the intersection between two bounding boxes.

Private Member Functions

bool readLTMHeader (int fd, pcl::io::TARHeader &header)
 Read another LTM header chunk.

Private Attributes

float intersection_volume_threshold_
 Intersection volume threshold.

Detailed Description

template<typename PointXYZT, typename PointRGBT = PointXYZT>
class pcl::LineRGBD< PointXYZT, PointRGBT >

High-level class for template matching using the LINEMOD approach based on RGB and Depth data.

Author:
Stefan Holzer

Definition at line 73 of file line_rgbd.h.


Constructor & Destructor Documentation

template<typename PointXYZT, typename PointRGBT = PointXYZT>
pcl::LineRGBD< PointXYZT, PointRGBT >::LineRGBD ( ) [inline]

Constructor.

Definition at line 98 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
virtual pcl::LineRGBD< PointXYZT, PointRGBT >::~LineRGBD ( ) [inline, virtual]

Destructor.

Definition at line 113 of file line_rgbd.h.


Member Function Documentation

template<typename PointXYZT , typename PointRGBT >
bool pcl::LineRGBD< PointXYZT, PointRGBT >::addTemplate ( const SparseQuantizedMultiModTemplate sqmmt,
pcl::PointCloud< pcl::PointXYZRGBA > &  cloud,
size_t  object_id = 0 
)

Definition at line 329 of file line_rgbd.hpp.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
std::vector<size_t> pcl::LineRGBD< PointXYZT, PointRGBT >::alignTemplatePoints ( const size_t  detection_id) [inline, protected]

Aligns the template points with the points found at the detection position of the specified detection. The detection ID refers to the last call of the method detect (...).

Parameters:
[in]detection_idThe ID of the detection (according to the last call of the method detect (...)).

Definition at line 252 of file line_rgbd.h.

template<typename PointXYZT , typename PointRGBT >
void pcl::LineRGBD< PointXYZT, PointRGBT >::applyProjectiveDepthICPOnDetections ( ) [protected]

Applies projective ICP on detections to find their correct position in depth.

Definition at line 736 of file line_rgbd.hpp.

template<typename PointXYZT , typename PointRGBT >
float pcl::LineRGBD< PointXYZT, PointRGBT >::computeBoundingBoxIntersectionVolume ( const BoundingBoxXYZ box1,
const BoundingBoxXYZ box2 
) [static, protected]

Computes the volume of the intersection between two bounding boxes.

Parameters:
[in]Firstbounding box.
[in]Secondbounding box.

Definition at line 951 of file line_rgbd.hpp.

template<typename PointXYZT , typename PointRGBT >
void pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints ( const size_t  detection_id,
pcl::PointCloud< pcl::PointXYZRGBA > &  cloud 
)

Computes and returns the point cloud of the specified detection. This is the template point cloud transformed to the detection coordinates. The detection ID refers to the last call of the method detect (...).

Parameters:
[in]detection_idThe ID of the detection (according to the last call of the method detect (...)).
[out]cloudThe storage for the transformed points.

Definition at line 611 of file line_rgbd.hpp.

template<typename PointXYZT , typename PointRGBT >
int pcl::LineRGBD< PointXYZT, PointRGBT >::createAndAddTemplate ( pcl::PointCloud< pcl::PointXYZRGBA > &  cloud,
const size_t  object_id,
const MaskMap mask_xyz,
const MaskMap mask_rgb,
const RegionXY region 
)

Creates a template from the specified data and adds it to the matching queue.

Parameters:
[in]mask_xyzthe mask that determine which parts of the xyz-modality are used for creating the template.
[in]mask_rgbthe mask that determine which parts of the rgb-modality are used for creating the template.
[in]regionthe region which will be associated with the template (can be larger than the actual modality-maps).

Definition at line 233 of file line_rgbd.hpp.

template<typename PointXYZT , typename PointRGBT >
void pcl::LineRGBD< PointXYZT, PointRGBT >::detect ( std::vector< typename pcl::LineRGBD< PointXYZT, PointRGBT >::Detection > &  detections)

Applies the detection process and fills the supplied vector with the detection instances.

Parameters:
[out]detectionsThe storage for the detection instances.

Definition at line 412 of file line_rgbd.hpp.

template<typename PointXYZT , typename PointRGBT >
void pcl::LineRGBD< PointXYZT, PointRGBT >::detectSemiScaleInvariant ( std::vector< typename pcl::LineRGBD< PointXYZT, PointRGBT >::Detection > &  detections,
float  min_scale = 0.6944444f,
float  max_scale = 1.44f,
float  scale_multiplier = 1.2f 
)

Applies the detection process in a semi-scale-invariant manner. This is done by acutally scaling the template to different sizes.

Definition at line 510 of file line_rgbd.hpp.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
std::vector<size_t> pcl::LineRGBD< PointXYZT, PointRGBT >::findObjectPointIndices ( const size_t  detection_id) [inline]

Finds the indices of the points in the input cloud which correspond to the specified detection. The detection ID refers to the last call of the method detect (...).

Parameters:
[in]detection_idThe ID of the detection (according to the last call of the method detect (...)).

Definition at line 233 of file line_rgbd.h.

template<typename PointXYZT , typename PointRGBT >
bool pcl::LineRGBD< PointXYZT, PointRGBT >::loadTemplates ( const std::string file_name,
size_t  object_id = 0 
)

Loads templates from a LMT (LineMod Template) file. Overrides old templates.

LineMod Template files are TAR files that store pairs of PCD datasets together with their LINEMOD signatures in SparseQuantizedMultiModTemplate format.

Parameters:
[in]file_nameThe name of the file that stores the templates.
Returns:
true, if the operation was succesful, false otherwise.

Definition at line 87 of file line_rgbd.hpp.

template<typename PointXYZT , typename PointRGBT >
bool pcl::LineRGBD< PointXYZT, PointRGBT >::readLTMHeader ( int  fd,
pcl::io::TARHeader header 
) [private]

Read another LTM header chunk.

Definition at line 62 of file line_rgbd.hpp.

template<typename PointXYZT , typename PointRGBT >
void pcl::LineRGBD< PointXYZT, PointRGBT >::refineDetectionsAlongDepth ( ) [protected]

Refines the found detections along the depth.

Definition at line 658 of file line_rgbd.hpp.

template<typename PointXYZT , typename PointRGBT >
void pcl::LineRGBD< PointXYZT, PointRGBT >::removeOverlappingDetections ( ) [protected]

Checks for overlapping detections, removes them and keeps only the strongest one.

Definition at line 817 of file line_rgbd.hpp.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
void pcl::LineRGBD< PointXYZT, PointRGBT >::setDetectionThreshold ( float  threshold) [inline]

Sets the threshold for the detection responses. Responses are between 0 and 1, where 1 is a best.

Parameters:
[in]thresholdThe threshold used to decide where a template is detected.

Definition at line 137 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
void pcl::LineRGBD< PointXYZT, PointRGBT >::setGradientMagnitudeThreshold ( const float  threshold) [inline]

Sets the threshold on the magnitude of color gradients. Color gradients with a magnitude below this threshold are not considered in the detection process.

Parameters:
[in]thresholdThe threshold on the magnitude of color gradients.

Definition at line 147 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
void pcl::LineRGBD< PointXYZT, PointRGBT >::setInputCloud ( const typename pcl::PointCloud< PointXYZT >::ConstPtr &  cloud) [inline]

Sets the input cloud with xyz point coordinates. The cloud has to be organized.

Parameters:
[in]cloudThe input cloud with xyz point coordinates.

Definition at line 169 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
void pcl::LineRGBD< PointXYZT, PointRGBT >::setInputColors ( const typename pcl::PointCloud< PointRGBT >::ConstPtr &  cloud) [inline]

Sets the input cloud with rgb values. The cloud has to be organized.

Parameters:
[in]cloudThe input cloud with rgb values.

Definition at line 181 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
void pcl::LineRGBD< PointXYZT, PointRGBT >::setIntersectionVolumeThreshold ( const float  threshold = 1.0f) [inline]

Sets the threshold for the decision whether two detections of the same template are merged or not. If ratio between the intersection of the bounding boxes of two detections and the original bounding boxes is larger than the specified threshold then they are merged. If detection A overlaps with detection B and B with C than A, B, and C are merged. Threshold has to be between 0 and 1.

Parameters:
[in]thresholdThe threshold on the ratio between the intersection bounding box and the original bounding box.

Definition at line 160 of file line_rgbd.h.


Member Data Documentation

template<typename PointXYZT, typename PointRGBT = PointXYZT>
std::vector<pcl::BoundingBoxXYZ> pcl::LineRGBD< PointXYZT, PointRGBT >::bounding_boxes_

Bounding boxes corresonding to the templates.

Definition at line 305 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
pcl::PointCloud<PointRGBT>::ConstPtr pcl::LineRGBD< PointXYZT, PointRGBT >::cloud_rgb_

RGB point cloud.

Definition at line 300 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
pcl::PointCloud<PointXYZT>::ConstPtr pcl::LineRGBD< PointXYZT, PointRGBT >::cloud_xyz_

XYZ point cloud.

Definition at line 298 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
pcl::ColorGradientModality<PointRGBT> pcl::LineRGBD< PointXYZT, PointRGBT >::color_gradient_mod_

Color gradient modality.

Definition at line 293 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
std::vector<typename pcl::LineRGBD<PointXYZT, PointRGBT>::Detection> pcl::LineRGBD< PointXYZT, PointRGBT >::detections_

Detections from last call of method detect (...).

Definition at line 310 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
float pcl::LineRGBD< PointXYZT, PointRGBT >::intersection_volume_threshold_ [private]

Intersection volume threshold.

Definition at line 288 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
pcl::LINEMOD pcl::LineRGBD< PointXYZT, PointRGBT >::linemod_

LINEMOD instance.

Definition at line 291 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
std::vector<size_t> pcl::LineRGBD< PointXYZT, PointRGBT >::object_ids_

Object IDs corresponding to the templates.

Definition at line 307 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
pcl::SurfaceNormalModality<PointXYZT> pcl::LineRGBD< PointXYZT, PointRGBT >::surface_normal_mod_

Surface normal modality.

Definition at line 295 of file line_rgbd.h.

template<typename PointXYZT, typename PointRGBT = PointXYZT>
pcl::PointCloud<pcl::PointXYZRGBA>::CloudVectorType pcl::LineRGBD< PointXYZT, PointRGBT >::template_point_clouds_

Point clouds corresponding to the templates.

Definition at line 303 of file line_rgbd.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:42:13