Public Member Functions | |
ICCVTutorial (boost::shared_ptr< pcl::Keypoint< pcl::PointXYZRGB, pcl::PointXYZI > > keypoint_detector, typename pcl::Feature< pcl::PointXYZRGB, FeatureType >::Ptr feature_extractor, boost::shared_ptr< pcl::PCLSurfaceBase< pcl::PointXYZRGBNormal > > surface_reconstructor, typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr source, typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr target) | |
ICCVTutorial (boost::shared_ptr< pcl::Keypoint< pcl::PointXYZRGB, pcl::PointXYZI > > keypoint_detector, typename pcl::Feature< pcl::PointXYZRGB, FeatureType >::Ptr feature_extractor, boost::shared_ptr< pcl::PCLSurfaceBase< pcl::PointXYZRGBNormal > > surface_reconstructor, typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr source, typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr target) | |
void | run () |
starts the event loop for the visualizer | |
void | run () |
starts the event loop for the visualizer | |
Protected Member Functions | |
void | detectKeypoints (typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr input, pcl::PointCloud< pcl::PointXYZI >::Ptr keypoints) const |
Detects key points in the input point cloud. | |
void | detectKeypoints (typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr input, pcl::PointCloud< pcl::PointXYZI >::Ptr keypoints) const |
Detects key points in the input point cloud. | |
void | determineFinalTransformation () |
calculate the final rigid transformation using ICP over all points | |
void | determineFinalTransformation () |
calculate the final rigid transformation using ICP over all points | |
void | determineInitialTransformation () |
calculate the initial rigid transformation from filtered corresponding keypoints | |
void | determineInitialTransformation () |
calculate the initial rigid transformation from filtered corresponding keypoints | |
void | extractDescriptors (typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr input, typename pcl::PointCloud< pcl::PointXYZI >::Ptr keypoints, typename pcl::PointCloud< FeatureType >::Ptr features) |
extract descriptors for given key points | |
void | extractDescriptors (typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr input, typename pcl::PointCloud< pcl::PointXYZI >::Ptr keypoints, typename pcl::PointCloud< FeatureType >::Ptr features) |
extract descriptors for given key points | |
void | filterCorrespondences () |
remove non-consistent correspondences | |
void | filterCorrespondences () |
remove non-consistent correspondences | |
void | findCorrespondences (typename pcl::PointCloud< FeatureType >::Ptr source, typename pcl::PointCloud< FeatureType >::Ptr target, std::vector< int > &correspondences) const |
find corresponding features based on some metric | |
void | findCorrespondences (typename pcl::PointCloud< FeatureType >::Ptr source, typename pcl::PointCloud< FeatureType >::Ptr target, std::vector< int > &correspondences) const |
find corresponding features based on some metric | |
void | keyboard_callback (const pcl::visualization::KeyboardEvent &event, void *cookie) |
callback to handle keyboard events | |
void | keyboard_callback (const pcl::visualization::KeyboardEvent &event, void *cookie) |
callback to handle keyboard events | |
void | reconstructSurface () |
reconstructs the surface from merged point clouds | |
void | reconstructSurface () |
reconstructs the surface from merged point clouds | |
void | segmentation (typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr input, typename pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented) const |
remove plane and select largest cluster as input object | |
void | segmentation (typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr input, typename pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented) const |
remove plane and select largest cluster as input object | |
Private Attributes | |
pcl::CorrespondencesPtr | correspondences_ |
pcl::Feature< pcl::PointXYZRGB, FeatureType >::Ptr | feature_extractor_ |
Eigen::Matrix4f | initial_transformation_matrix_ |
boost::shared_ptr < pcl::Keypoint < pcl::PointXYZRGB, pcl::PointXYZI > > | keypoint_detector_ |
bool | show_correspondences |
bool | show_source2target_ |
bool | show_target2source_ |
std::vector< int > | source2target_ |
pcl::PointCloud < pcl::PointXYZRGB >::ConstPtr | source_ |
pcl::PointCloud< FeatureType >::Ptr | source_features_ |
pcl::PointCloud < pcl::PointXYZI >::Ptr | source_keypoints_ |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | source_registered_ |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | source_segmented_ |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | source_transformed_ |
pcl::PolygonMesh | surface_ |
boost::shared_ptr < pcl::PCLSurfaceBase < pcl::PointXYZRGBNormal > > | surface_reconstructor_ |
std::vector< int > | target2source_ |
pcl::PointCloud < pcl::PointXYZRGB >::ConstPtr | target_ |
pcl::PointCloud< FeatureType >::Ptr | target_features_ |
pcl::PointCloud < pcl::PointXYZI >::Ptr | target_keypoints_ |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | target_segmented_ |
Eigen::Matrix4f | transformation_matrix_ |
pcl::visualization::PCLVisualizer | visualizer_ |
Definition at line 31 of file feature_matching.cpp.
ICCVTutorial< FeatureType >::ICCVTutorial | ( | boost::shared_ptr< pcl::Keypoint< pcl::PointXYZRGB, pcl::PointXYZI > > | keypoint_detector, |
typename pcl::Feature< pcl::PointXYZRGB, FeatureType >::Ptr | feature_extractor, | ||
boost::shared_ptr< pcl::PCLSurfaceBase< pcl::PointXYZRGBNormal > > | surface_reconstructor, | ||
typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | source, | ||
typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | target | ||
) |
Definition at line 129 of file feature_matching.cpp.
ICCVTutorial< FeatureType >::ICCVTutorial | ( | boost::shared_ptr< pcl::Keypoint< pcl::PointXYZRGB, pcl::PointXYZI > > | keypoint_detector, |
typename pcl::Feature< pcl::PointXYZRGB, FeatureType >::Ptr | feature_extractor, | ||
boost::shared_ptr< pcl::PCLSurfaceBase< pcl::PointXYZRGBNormal > > | surface_reconstructor, | ||
typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | source, | ||
typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | target | ||
) |
void ICCVTutorial< FeatureType >::detectKeypoints | ( | typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | input, |
pcl::PointCloud< pcl::PointXYZI >::Ptr | keypoints | ||
) | const [protected] |
Detects key points in the input point cloud.
input | the input point cloud |
keypoints | the resulting key points. Note that they are not necessarily a subset of the input cloud |
Definition at line 234 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::detectKeypoints | ( | typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | input, |
pcl::PointCloud< pcl::PointXYZI >::Ptr | keypoints | ||
) | const [protected] |
Detects key points in the input point cloud.
input | the input point cloud |
keypoints | the resulting key points. Note that they are not necessarily a subset of the input cloud |
void ICCVTutorial< FeatureType >::determineFinalTransformation | ( | ) | [protected] |
calculate the final rigid transformation using ICP over all points
Definition at line 333 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::determineFinalTransformation | ( | ) | [protected] |
calculate the final rigid transformation using ICP over all points
void ICCVTutorial< FeatureType >::determineInitialTransformation | ( | ) | [protected] |
calculate the initial rigid transformation from filtered corresponding keypoints
void ICCVTutorial< FeatureType >::determineInitialTransformation | ( | ) | [protected] |
calculate the initial rigid transformation from filtered corresponding keypoints
Definition at line 321 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::extractDescriptors | ( | typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | input, |
typename pcl::PointCloud< pcl::PointXYZI >::Ptr | keypoints, | ||
typename pcl::PointCloud< FeatureType >::Ptr | features | ||
) | [protected] |
extract descriptors for given key points
input | point cloud to be used for descriptor extraction |
keypoints | locations where descriptors are to be extracted |
features | resulting descriptors |
Definition at line 243 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::extractDescriptors | ( | typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | input, |
typename pcl::PointCloud< pcl::PointXYZI >::Ptr | keypoints, | ||
typename pcl::PointCloud< FeatureType >::Ptr | features | ||
) | [protected] |
extract descriptors for given key points
input | point cloud to be used for descriptor extraction |
keypoints | locations where descriptors are to be extracted |
features | resulting descriptors |
void ICCVTutorial< FeatureType >::filterCorrespondences | ( | ) | [protected] |
remove non-consistent correspondences
void ICCVTutorial< FeatureType >::filterCorrespondences | ( | ) | [protected] |
remove non-consistent correspondences
Definition at line 297 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::findCorrespondences | ( | typename pcl::PointCloud< FeatureType >::Ptr | source, |
typename pcl::PointCloud< FeatureType >::Ptr | target, | ||
std::vector< int > & | correspondences | ||
) | const [protected] |
find corresponding features based on some metric
source | source feature descriptors |
target | target feature descriptors |
correspondences | indices out of the target descriptors that correspond (nearest neighbor) to the source descriptors |
void ICCVTutorial< FeatureType >::findCorrespondences | ( | typename pcl::PointCloud< FeatureType >::Ptr | source, |
typename pcl::PointCloud< FeatureType >::Ptr | target, | ||
std::vector< int > & | correspondences | ||
) | const [protected] |
find corresponding features based on some metric
source | source feature descriptors |
target | target feature descriptors |
correspondences | indices out of the target descriptors that correspond (nearest neighbor) to the source descriptors |
Definition at line 275 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::keyboard_callback | ( | const pcl::visualization::KeyboardEvent & | event, |
void * | cookie | ||
) | [protected] |
callback to handle keyboard events
event | object containing information about the event. e.g. type (press, release) etc. |
cookie | user defined data passed during registration of the callback |
Definition at line 390 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::keyboard_callback | ( | const pcl::visualization::KeyboardEvent & | event, |
void * | cookie | ||
) | [protected] |
callback to handle keyboard events
event | object containing information about the event. e.g. type (press, release) etc. |
cookie | user defined data passed during registration of the callback |
void ICCVTutorial< FeatureType >::reconstructSurface | ( | ) | [protected] |
reconstructs the surface from merged point clouds
void ICCVTutorial< FeatureType >::reconstructSurface | ( | ) | [protected] |
reconstructs the surface from merged point clouds
Definition at line 350 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::run | ( | ) |
starts the event loop for the visualizer
void ICCVTutorial< FeatureType >::run | ( | ) |
starts the event loop for the visualizer
Definition at line 384 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::segmentation | ( | typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | input, |
typename pcl::PointCloud< pcl::PointXYZRGB >::Ptr | segmented | ||
) | const [protected] |
remove plane and select largest cluster as input object
input | the input point cloud |
segmented | the resulting segmented point cloud containing only points of the largest cluster |
Definition at line 175 of file feature_matching.cpp.
void ICCVTutorial< FeatureType >::segmentation | ( | typename pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr | input, |
typename pcl::PointCloud< pcl::PointXYZRGB >::Ptr | segmented | ||
) | const [protected] |
remove plane and select largest cluster as input object
input | the input point cloud |
segmented | the resulting segmented point cloud containing only points of the largest cluster |
pcl::CorrespondencesPtr ICCVTutorial< FeatureType >::correspondences_ [private] |
Definition at line 120 of file feature_matching.cpp.
pcl::Feature< pcl::PointXYZRGB, FeatureType >::Ptr ICCVTutorial< FeatureType >::feature_extractor_ [private] |
Definition at line 107 of file feature_matching.cpp.
Eigen::Matrix4f ICCVTutorial< FeatureType >::initial_transformation_matrix_ [private] |
Definition at line 121 of file feature_matching.cpp.
boost::shared_ptr< pcl::Keypoint< pcl::PointXYZRGB, pcl::PointXYZI > > ICCVTutorial< FeatureType >::keypoint_detector_ [private] |
Definition at line 106 of file feature_matching.cpp.
bool ICCVTutorial< FeatureType >::show_correspondences [private] |
Definition at line 125 of file feature_matching.cpp.
bool ICCVTutorial< FeatureType >::show_source2target_ [private] |
Definition at line 123 of file feature_matching.cpp.
bool ICCVTutorial< FeatureType >::show_target2source_ [private] |
Definition at line 124 of file feature_matching.cpp.
std::vector< int > ICCVTutorial< FeatureType >::source2target_ [private] |
Definition at line 118 of file feature_matching.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr ICCVTutorial< FeatureType >::source_ [private] |
Definition at line 109 of file feature_matching.cpp.
pcl::PointCloud< FeatureType >::Ptr ICCVTutorial< FeatureType >::source_features_ [private] |
Definition at line 116 of file feature_matching.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr ICCVTutorial< FeatureType >::source_keypoints_ [private] |
Definition at line 104 of file feature_matching.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr ICCVTutorial< FeatureType >::source_registered_ [private] |
Definition at line 114 of file feature_matching.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr ICCVTutorial< FeatureType >::source_segmented_ [private] |
Definition at line 111 of file feature_matching.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr ICCVTutorial< FeatureType >::source_transformed_ [private] |
Definition at line 113 of file feature_matching.cpp.
pcl::PolygonMesh ICCVTutorial< FeatureType >::surface_ [private] |
Definition at line 115 of file feature_matching.cpp.
boost::shared_ptr< pcl::PCLSurfaceBase< pcl::PointXYZRGBNormal > > ICCVTutorial< FeatureType >::surface_reconstructor_ [private] |
Definition at line 108 of file feature_matching.cpp.
std::vector< int > ICCVTutorial< FeatureType >::target2source_ [private] |
Definition at line 119 of file feature_matching.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr ICCVTutorial< FeatureType >::target_ [private] |
Definition at line 110 of file feature_matching.cpp.
pcl::PointCloud< FeatureType >::Ptr ICCVTutorial< FeatureType >::target_features_ [private] |
Definition at line 117 of file feature_matching.cpp.
pcl::PointCloud< pcl::PointXYZI >::Ptr ICCVTutorial< FeatureType >::target_keypoints_ [private] |
Definition at line 105 of file feature_matching.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr ICCVTutorial< FeatureType >::target_segmented_ [private] |
Definition at line 112 of file feature_matching.cpp.
Eigen::Matrix4f ICCVTutorial< FeatureType >::transformation_matrix_ [private] |
Definition at line 122 of file feature_matching.cpp.
pcl::visualization::PCLVisualizer ICCVTutorial< FeatureType >::visualizer_ [private] |
Definition at line 103 of file feature_matching.cpp.