Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT > Class Template Reference

Class implementing a 3D correspondence grouping algorithm that can deal with multiple instances of a model template found into a given scene. Each correspondence casts a vote for a reference point in a 3D Hough Space. The remaining 3 DOF are taken into account by associating each correspondence with a local Reference Frame. The suggested PointModelRfT is pcl::ReferenceFrame. More...

#include <hough_3d.h>

Inheritance diagram for pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud
< PointModelRfT > 
ModelRfCloud
typedef ModelRfCloud::ConstPtr ModelRfCloudConstPtr
typedef ModelRfCloud::Ptr ModelRfCloudPtr
typedef pcl::PointCloud
< PointModelT > 
PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr
typedef
pcl::CorrespondenceGrouping
< PointModelT, PointSceneT >
::SceneCloudConstPtr 
SceneCloudConstPtr
typedef pcl::PointCloud
< PointSceneRfT > 
SceneRfCloud
typedef SceneRfCloud::ConstPtr SceneRfCloudConstPtr
typedef SceneRfCloud::Ptr SceneRfCloudPtr

Public Member Functions

double getHoughBinSize () const
 Gets the size of each bin into the Hough space.
double getHoughThreshold () const
 Gets the minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud.
ModelRfCloudConstPtr getInputRf () const
 Getter for the input dataset's reference frames. Each point in the reference frame cloud should be the reference frame of the correspondent point in the input dataset.
float getLocalRfNormalsSearchRadius () const
 If the Local reference frame has not been set for either the model cloud or the scene cloud, this algorithm makes the computation itself but needs a suitable search radius to compute the normals in order to subsequently compute the RF (if not set a default 15 nearest neighbors search is performed).
float getLocalRfSearchRadius () const
 If the Local reference frame has not been set for either the model cloud or the scene cloud, this algorithm makes the computation itself but needs a suitable search radius to do so.
SceneRfCloudConstPtr getSceneRf () const
 Getter for the scene dataset's reference frames. Each point in the reference frame cloud should be the reference frame of the correspondent point in the scene dataset.
bool getUseDistanceWeight () const
 Gets whether the vote casting procedure uses the correspondence's distance as a score.
bool getUseInterpolation () const
 Gets whether the vote casting procedure interpolates the score between neighboring bins of the Hough space or not.
 Hough3DGrouping ()
 Constructor.
bool recognize (std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &transformations)
 The main function, recognizes instances of the model into the scene set by the user.
bool recognize (std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &transformations, std::vector< pcl::Correspondences > &clustered_corrs)
 The main function, recognizes instances of the model into the scene set by the user.
void setHoughBinSize (double bin_size)
 Sets the size of each bin into the Hough space.
void setHoughThreshold (double threshold)
 Sets the minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud.
void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset.
void setInputRf (const ModelRfCloudConstPtr &input_rf)
 Provide a pointer to the input dataset's reference frames. Each point in the reference frame cloud should be the reference frame of the correspondent point in the input dataset.
void setLocalRfNormalsSearchRadius (float local_rf_normals_search_radius)
 If the Local reference frame has not been set for either the model cloud or the scene cloud, this algorithm makes the computation itself but needs a suitable search radius to compute the normals in order to subsequently compute the RF (if not set a default 15 nearest neighbors search is performed).
void setLocalRfSearchRadius (float local_rf_search_radius)
 If the Local reference frame has not been set for either the model cloud or the scene cloud, this algorithm makes the computation itself but needs a suitable search radius to do so.
void setModelSceneCorrespondences (const CorrespondencesConstPtr &corrs)
 Provide a pointer to the precomputed correspondences between points in the input dataset and points in the scene dataset. The correspondences are going to be clustered into different model instances by the algorithm.
void setSceneCloud (const SceneCloudConstPtr &scene)
 Provide a pointer to the scene dataset (i.e. the cloud in which the algorithm has to search for instances of the input model)
void setSceneRf (const SceneRfCloudConstPtr &scene_rf)
 Provide a pointer to the scene dataset's reference frames. Each point in the reference frame cloud should be the reference frame of the correspondent point in the scene dataset.
void setUseDistanceWeight (bool use_distance_weight)
 Sets whether the vote casting procedure uses the correspondence's distance as a score.
void setUseInterpolation (bool use_interpolation)
 Sets whether the vote casting procedure interpolates the score between neighboring bins of the Hough space or not.
bool train ()
 Call this function after setting the input, the input_rf and the hough_bin_size parameters to perform an off line training of the algorithm. This might be useful if one wants to perform once and for all a pre-computation of votes that only concern the models, increasing the on-line efficiency of the grouping algorithm. The algorithm is automatically trained on the first invocation of the recognize method or the cluster method if this training function has not been manually invoked.

Protected Member Functions

void clusterCorrespondences (std::vector< Correspondences > &model_instances)
 Cluster the input correspondences in order to distinguish between different instances of the model into the scene.
template<typename PointType , typename PointRfType >
void computeRf (const boost::shared_ptr< const pcl::PointCloud< PointType > > &input, pcl::PointCloud< PointRfType > &rf)
 Computes the reference frame for an input cloud.
bool houghVoting ()
 Finds the transformation matrix between the input and the scene cloud for a set of correspondences using a RANSAC algorithm.

Protected Attributes

std::vector< Eigen::Matrix4f,
Eigen::aligned_allocator
< Eigen::Matrix4f > > 
found_transformations_
 Transformations found by clusterCorrespondences method.
double hough_bin_size_
 The size of each bin of the hough space.
boost::shared_ptr
< pcl::recognition::HoughSpace3D
hough_space_
 The Hough space.
bool hough_space_initialized_
 Whether the Hough space already contains the correct votes for the current input parameters and so the cluster and recognize calls don't need to recompute each value. Reset on the change of any parameter except the hough_threshold.
double hough_threshold_
 The minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud.
ModelRfCloudConstPtr input_rf_
 The input Rf cloud.
float local_rf_normals_search_radius_
 Normals search radius for the potential Rf calculation.
float local_rf_search_radius_
 Search radius for the potential Rf calculation.
std::vector< Eigen::Vector3f > model_votes_
 The result of the training. The vector between each model point and the centroid of the model adjusted by its local reference frame.
bool needs_training_
 If the training of the Hough space is needed; set on change of either the input cloud or the input_rf.
SceneRfCloudConstPtr scene_rf_
 The scene Rf cloud.
bool use_distance_weight_
 Use the weighted correspondence distance when casting votes.
bool use_interpolation_
 Use the interpolation between neighboring Hough bins when casting votes.

Detailed Description

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
class pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >

Class implementing a 3D correspondence grouping algorithm that can deal with multiple instances of a model template found into a given scene. Each correspondence casts a vote for a reference point in a 3D Hough Space. The remaining 3 DOF are taken into account by associating each correspondence with a local Reference Frame. The suggested PointModelRfT is pcl::ReferenceFrame.

Note:
If you use this code in any academic work, please cite the original paper:
  • F. Tombari, L. Di Stefano: Object recognition in 3D scenes with occlusions and clutter by Hough voting. 2010, Fourth Pacific-Rim Symposium on Image and Video Technology
Author:
Federico Tombari (original), Tommaso Cavallari (PCL port)

Definition at line 144 of file hough_3d.h.


Member Typedef Documentation

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef pcl::PointCloud<PointModelRfT> pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::ModelRfCloud

Definition at line 147 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef ModelRfCloud::ConstPtr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::ModelRfCloudConstPtr

Definition at line 149 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef ModelRfCloud::Ptr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::ModelRfCloudPtr

Definition at line 148 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef pcl::PointCloud<PointModelT> pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::PointCloud

Reimplemented from pcl::PCLBase< PointModelT >.

Definition at line 155 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef PointCloud::ConstPtr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::PointCloudConstPtr

Reimplemented from pcl::PCLBase< PointModelT >.

Definition at line 157 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef PointCloud::Ptr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::PointCloudPtr

Reimplemented from pcl::PCLBase< PointModelT >.

Definition at line 156 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef pcl::CorrespondenceGrouping<PointModelT, PointSceneT>::SceneCloudConstPtr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::SceneCloudConstPtr

Reimplemented from pcl::CorrespondenceGrouping< PointModelT, PointSceneT >.

Definition at line 159 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef pcl::PointCloud<PointSceneRfT> pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::SceneRfCloud

Definition at line 151 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef SceneRfCloud::ConstPtr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::SceneRfCloudConstPtr

Definition at line 153 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
typedef SceneRfCloud::Ptr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::SceneRfCloudPtr

Definition at line 152 of file hough_3d.h.


Constructor & Destructor Documentation

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::Hough3DGrouping ( ) [inline]

Constructor.

Definition at line 162 of file hough_3d.h.


Member Function Documentation

template<typename PointModelT , typename PointSceneT , typename PointModelRfT , typename PointSceneRfT >
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::clusterCorrespondences ( std::vector< Correspondences > &  model_instances) [protected, virtual]

Cluster the input correspondences in order to distinguish between different instances of the model into the scene.

Parameters:
[out]model_instancesa vector containing the clustered correspondences for each model found on the scene.
Returns:
true if the clustering had been successful or false if errors have occurred.

Implements pcl::CorrespondenceGrouping< PointModelT, PointSceneT >.

Definition at line 258 of file hough_3d.hpp.

template<typename PointModelT , typename PointSceneT , typename PointModelRfT , typename PointSceneRfT >
template<typename PointType , typename PointRfType >
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::computeRf ( const boost::shared_ptr< const pcl::PointCloud< PointType > > &  input,
pcl::PointCloud< PointRfType > &  rf 
) [protected]

Computes the reference frame for an input cloud.

Parameters:
[in]inputthe input cloud.
[out]rfthe resulting reference frame.

Definition at line 54 of file hough_3d.hpp.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
double pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::getHoughBinSize ( ) const [inline]

Gets the size of each bin into the Hough space.

Returns:
the size of each Hough space's bin.

Definition at line 305 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
double pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::getHoughThreshold ( ) const [inline]

Gets the minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud.

Returns:
the threshold for the Hough space voting.

Definition at line 284 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
ModelRfCloudConstPtr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::getInputRf ( ) const [inline]

Getter for the input dataset's reference frames. Each point in the reference frame cloud should be the reference frame of the correspondent point in the input dataset.

Returns:
the pointer to the input cloud's reference frames.

Definition at line 211 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
float pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::getLocalRfNormalsSearchRadius ( ) const [inline]

If the Local reference frame has not been set for either the model cloud or the scene cloud, this algorithm makes the computation itself but needs a suitable search radius to compute the normals in order to subsequently compute the RF (if not set a default 15 nearest neighbors search is performed).

Returns:
the normals search radius for the local reference frame calculation.

Definition at line 375 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
float pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::getLocalRfSearchRadius ( ) const [inline]

If the Local reference frame has not been set for either the model cloud or the scene cloud, this algorithm makes the computation itself but needs a suitable search radius to do so.

Attention:
This parameter NEEDS to be set if the reference frames are not precomputed externally, otherwise the recognition results won't be correct.
Returns:
the search radius for the local reference frame calculation.

Definition at line 403 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
SceneRfCloudConstPtr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::getSceneRf ( ) const [inline]

Getter for the scene dataset's reference frames. Each point in the reference frame cloud should be the reference frame of the correspondent point in the scene dataset.

Returns:
the pointer to the scene cloud's reference frames.

Definition at line 248 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::getUseDistanceWeight ( ) const [inline]

Gets whether the vote casting procedure uses the correspondence's distance as a score.

Returns:
if the algorithm should use the weighted distance when calculating the Hough voting score.

Definition at line 349 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::getUseInterpolation ( ) const [inline]

Gets whether the vote casting procedure interpolates the score between neighboring bins of the Hough space or not.

Returns:
if the algorithm should interpolate the vote score between neighboring bins.

Definition at line 328 of file hough_3d.h.

template<typename PointModelT , typename PointSceneT , typename PointModelRfT , typename PointSceneRfT >
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::houghVoting ( ) [protected]

Finds the transformation matrix between the input and the scene cloud for a set of correspondences using a RANSAC algorithm.

Parameters:
[in]thescene cloud in which the PointSceneT has been converted to PointModelT.
[in]corrsa set of correspondences.
[out]transformthe transformation matrix between the input cloud and the scene cloud that aligns the found correspondences.
Returns:
true if the recognition had been successful or false if errors have occurred.The Hough space voting procedure.
true if the voting had been successful or false if errors have occurred.

Definition at line 137 of file hough_3d.hpp.

template<typename PointModelT , typename PointSceneT , typename PointModelRfT , typename PointSceneRfT >
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::recognize ( std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &  transformations)

The main function, recognizes instances of the model into the scene set by the user.

Parameters:
[out]transformationsa vector containing one transformation matrix for each instance of the model recognized into the scene.
Returns:
true if the recognition had been successful or false if errors have occurred.

Definition at line 333 of file hough_3d.hpp.

template<typename PointModelT , typename PointSceneT , typename PointModelRfT , typename PointSceneRfT >
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::recognize ( std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &  transformations,
std::vector< pcl::Correspondences > &  clustered_corrs 
)

The main function, recognizes instances of the model into the scene set by the user.

Parameters:
[out]transformationsa vector containing one transformation matrix for each instance of the model recognized into the scene.
[out]clustered_corrsa vector containing the correspondences for each instance of the model found within the input data (the same output of clusterCorrespondences).
Returns:
true if the recognition had been successful or false if errors have occurred.

Definition at line 342 of file hough_3d.hpp.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setHoughBinSize ( double  bin_size) [inline]

Sets the size of each bin into the Hough space.

Parameters:
[in]bin_sizethe size of each Hough space's bin.

Definition at line 294 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setHoughThreshold ( double  threshold) [inline]

Sets the minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud.

Parameters:
[in]thresholdthe threshold for the Hough space voting, if set between -1 and 0 the maximum vote in the entire space is automatically calculated and -threshold the maximum value is used as a threshold. This means that a value between -1 and 0 should be used only if at least one instance of the model is always present in the scene, or if this false positive can be filtered later.

Definition at line 274 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setInputCloud ( const PointCloudConstPtr cloud) [inline, virtual]

Provide a pointer to the input dataset.

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message.

Reimplemented from pcl::PCLBase< PointModelT >.

Definition at line 182 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setInputRf ( const ModelRfCloudConstPtr input_rf) [inline]

Provide a pointer to the input dataset's reference frames. Each point in the reference frame cloud should be the reference frame of the correspondent point in the input dataset.

Parameters:
[in]input_rfthe pointer to the input cloud's reference frames.

Definition at line 197 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setLocalRfNormalsSearchRadius ( float  local_rf_normals_search_radius) [inline]

If the Local reference frame has not been set for either the model cloud or the scene cloud, this algorithm makes the computation itself but needs a suitable search radius to compute the normals in order to subsequently compute the RF (if not set a default 15 nearest neighbors search is performed).

Parameters:
[in]local_rf_normals_search_radiusthe normals search radius for the local reference frame calculation.

Definition at line 361 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setLocalRfSearchRadius ( float  local_rf_search_radius) [inline]

If the Local reference frame has not been set for either the model cloud or the scene cloud, this algorithm makes the computation itself but needs a suitable search radius to do so.

Attention:
This parameter NEEDS to be set if the reference frames are not precomputed externally, otherwise the recognition results won't be correct.
Parameters:
[in]local_rf_search_radiusthe search radius for the local reference frame calculation.

Definition at line 388 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setModelSceneCorrespondences ( const CorrespondencesConstPtr corrs) [inline, virtual]

Provide a pointer to the precomputed correspondences between points in the input dataset and points in the scene dataset. The correspondences are going to be clustered into different model instances by the algorithm.

Parameters:
[in]corrsthe correspondences between the model and the scene.

Reimplemented from pcl::CorrespondenceGrouping< PointModelT, PointSceneT >.

Definition at line 260 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setSceneCloud ( const SceneCloudConstPtr scene) [inline, virtual]

Provide a pointer to the scene dataset (i.e. the cloud in which the algorithm has to search for instances of the input model)

Parameters:
[in]scenethe const boost shared pointer to a PointCloud message.

Reimplemented from pcl::CorrespondenceGrouping< PointModelT, PointSceneT >.

Definition at line 221 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setSceneRf ( const SceneRfCloudConstPtr scene_rf) [inline]

Provide a pointer to the scene dataset's reference frames. Each point in the reference frame cloud should be the reference frame of the correspondent point in the scene dataset.

Parameters:
[in]scene_rfthe pointer to the scene cloud's reference frames.

Definition at line 235 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setUseDistanceWeight ( bool  use_distance_weight) [inline]

Sets whether the vote casting procedure uses the correspondence's distance as a score.

Parameters:
[in]use_distance_weightthe algorithm should use the weighted distance when calculating the Hough voting score.

Definition at line 338 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
void pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setUseInterpolation ( bool  use_interpolation) [inline]

Sets whether the vote casting procedure interpolates the score between neighboring bins of the Hough space or not.

Parameters:
[in]use_interpolationthe algorithm should interpolate the vote score between neighboring bins.

Definition at line 316 of file hough_3d.h.

template<typename PointModelT , typename PointSceneT , typename PointModelRfT , typename PointSceneRfT >
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::train ( )

Call this function after setting the input, the input_rf and the hough_bin_size parameters to perform an off line training of the algorithm. This might be useful if one wants to perform once and for all a pre-computation of votes that only concern the models, increasing the on-line efficiency of the grouping algorithm. The algorithm is automatically trained on the first invocation of the recognize method or the cluster method if this training function has not been manually invoked.

Returns:
true if the training had been successful or false if errors have occurred.

Definition at line 84 of file hough_3d.hpp.


Member Data Documentation

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::found_transformations_ [protected]

Transformations found by clusterCorrespondences method.

Definition at line 474 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
double pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::hough_bin_size_ [protected]

The size of each bin of the hough space.

Definition at line 456 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
boost::shared_ptr<pcl::recognition::HoughSpace3D> pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::hough_space_ [protected]

The Hough space.

Definition at line 471 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::hough_space_initialized_ [protected]

Whether the Hough space already contains the correct votes for the current input parameters and so the cluster and recognize calls don't need to recompute each value. Reset on the change of any parameter except the hough_threshold.

Definition at line 479 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
double pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::hough_threshold_ [protected]

The minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud.

Definition at line 453 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
ModelRfCloudConstPtr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::input_rf_ [protected]

The input Rf cloud.

Definition at line 441 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
float pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::local_rf_normals_search_radius_ [protected]

Normals search radius for the potential Rf calculation.

Definition at line 465 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
float pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::local_rf_search_radius_ [protected]

Search radius for the potential Rf calculation.

Definition at line 468 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
std::vector<Eigen::Vector3f> pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::model_votes_ [protected]

The result of the training. The vector between each model point and the centroid of the model adjusted by its local reference frame.

Definition at line 450 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::needs_training_ [protected]

If the training of the Hough space is needed; set on change of either the input cloud or the input_rf.

Definition at line 447 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
SceneRfCloudConstPtr pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::scene_rf_ [protected]

The scene Rf cloud.

Definition at line 444 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::use_distance_weight_ [protected]

Use the weighted correspondence distance when casting votes.

Definition at line 462 of file hough_3d.h.

template<typename PointModelT, typename PointSceneT, typename PointModelRfT = pcl::ReferenceFrame, typename PointSceneRfT = pcl::ReferenceFrame>
bool pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::use_interpolation_ [protected]

Use the interpolation between neighboring Hough bins when casting votes.

Definition at line 459 of file hough_3d.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:53