Implements a supervoxel algorithm based on voxel structure, normals, and rgb values. More...
#include <supervoxel_clustering.h>
Classes | |
class | SupervoxelHelper |
Internal storage class for supervoxels. More... | |
class | VoxelData |
VoxelData is a structure used for storing data within a pcl::octree::OctreePointCloudAdjacencyContainer. More... | |
Public Types | |
typedef VoxelAdjacencyList::edge_descriptor | EdgeID |
typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
typedef pcl::search::KdTree < PointT > | KdTreeT |
typedef pcl::octree::OctreePointCloudAdjacencyContainer < PointT, VoxelData > | LeafContainerT |
typedef std::vector < LeafContainerT * > | LeafVectorT |
typedef pcl::PointCloud< Normal > | NormalCloudT |
typedef pcl::octree::OctreePointCloudAdjacency < PointT, LeafContainerT > | OctreeAdjacencyT |
typedef pcl::octree::OctreePointCloudSearch < PointT > | OctreeSearchT |
typedef pcl::PointCloud< PointT > | PointCloudT |
typedef boost::adjacency_list < boost::setS, boost::setS, boost::undirectedS, uint32_t, float > | VoxelAdjacencyList |
typedef VoxelAdjacencyList::vertex_descriptor | VoxelID |
Public Member Functions | |
virtual void | extract (std::map< uint32_t, typename Supervoxel< PointT >::Ptr > &supervoxel_clusters) |
This method launches the segmentation algorithm and returns the supervoxels that were obtained during the segmentation. | |
pcl::PointCloud< PointXYZRGBA > ::Ptr | getColoredCloud () const |
Returns an RGB colorized cloud showing superpixels Otherwise it returns an empty pointer. Points that belong to the same supervoxel have the same color. But this function doesn't guarantee that different segments will have different color(it's random). Points that are unlabeled will be black. | |
pcl::PointCloud < pcl::PointXYZRGBA >::Ptr | getColoredVoxelCloud () const |
Returns an RGB colorized voxelized cloud showing superpixels Otherwise it returns an empty pointer. Points that belong to the same supervoxel have the same color. But this function doesn't guarantee that different segments will have different color(it's random). Points that are unlabeled will be black. | |
pcl::PointCloud< PointXYZL >::Ptr | getLabeledCloud () const |
Returns labeled cloud Points that belong to the same supervoxel have the same label. Labels for segments start from 1, unlabled points have label 0. | |
pcl::PointCloud < pcl::PointXYZL >::Ptr | getLabeledVoxelCloud () const |
Returns labeled voxelized cloud Points that belong to the same supervoxel have the same label. Labels for segments start from 1, unlabled points have label 0. | |
float | getSeedResolution () const |
Get the resolution of the octree seed voxels. | |
void | getSupervoxelAdjacency (std::multimap< uint32_t, uint32_t > &label_adjacency) const |
Get a multimap which gives supervoxel adjacency. | |
void | getSupervoxelAdjacencyList (VoxelAdjacencyList &adjacency_list_arg) const |
Gets the adjacency list (Boost Graph library) which gives connections between supervoxels. | |
pcl::PointCloud< PointT >::Ptr | getVoxelCentroidCloud () const |
Returns a deep copy of the voxel centroid cloud. | |
float | getVoxelResolution () const |
Get the resolution of the octree voxels. | |
virtual void | refineSupervoxels (int num_itr, std::map< uint32_t, typename Supervoxel< PointT >::Ptr > &supervoxel_clusters) |
This method refines the calculated supervoxels - may only be called after extract. | |
void | setColorImportance (float val) |
Set the importance of color for supervoxels. | |
virtual void | setInputCloud (typename pcl::PointCloud< PointT >::ConstPtr cloud) |
This method sets the cloud to be supervoxelized. | |
void | setNormalImportance (float val) |
Set the importance of scalar normal product for supervoxels. | |
void | setSeedResolution (float seed_resolution) |
Set the resolution of the octree seed voxels. | |
void | setSpatialImportance (float val) |
Set the importance of spatial distance for supervoxels. | |
void | setVoxelResolution (float resolution) |
Set the resolution of the octree voxels. | |
SupervoxelClustering (float voxel_resolution, float seed_resolution, bool use_single_camera_transform=true) | |
Constructor that sets default values for member variables. | |
virtual | ~SupervoxelClustering () |
This destructor destroys the cloud, normals and search method used for finding neighbors. In other words it frees memory. | |
Static Public Member Functions | |
static pcl::PointCloud < pcl::PointNormal >::Ptr | makeSupervoxelNormalCloud (std::map< uint32_t, typename Supervoxel< PointT >::Ptr > &supervoxel_clusters) |
Static helper function which returns a pointcloud of normals for the input supervoxels. | |
Private Types | |
typedef boost::ptr_list < SupervoxelHelper > | HelperListT |
Private Member Functions | |
void | computeVoxelData () |
This sets the data of the voxels in the tree. | |
void | createSupervoxelHelpers (std::vector< PointT, Eigen::aligned_allocator< PointT > > &seed_points) |
This method creates the internal supervoxel helpers based on the provided seed points. | |
void | expandSupervoxels (int depth) |
This performs the superpixel evolution. | |
void | makeSupervoxels (std::map< uint32_t, typename Supervoxel< PointT >::Ptr > &supervoxel_clusters) |
Constructs the map of supervoxel clusters from the internal supervoxel helpers. | |
virtual bool | prepareForSegmentation () |
This method simply checks if it is possible to execute the segmentation algorithm with the current settings. If it is possible then it returns true. | |
void | reseedSupervoxels () |
Reseeds the supervoxels by finding the voxel closest to current centroid. | |
void | selectInitialSupervoxelSeeds (std::vector< PointT, Eigen::aligned_allocator< PointT > > &seed_points) |
This selects points to use as initial supervoxel centroids. | |
void | transformFunction (PointT &p) |
Transform function used to normalize voxel density versus distance from camera. | |
float | voxelDataDistance (const VoxelData &v1, const VoxelData &v2) const |
Distance function used for comparing voxelDatas. | |
Private Attributes | |
OctreeAdjacencyT::Ptr | adjacency_octree_ |
Octree Adjacency structure with leaves at voxel resolution. | |
float | color_importance_ |
Importance of color in clustering. | |
std::vector< uint32_t > | label_colors_ |
Stores the colors used for the superpixel labels. | |
float | normal_importance_ |
Importance of similarity in normals for clustering. | |
float | resolution_ |
Stores the resolution used in the octree. | |
float | seed_resolution_ |
Stores the resolution used to seed the superpixels. | |
float | spatial_importance_ |
Importance of distance from seed center in clustering. | |
HelperListT | supervoxel_helpers_ |
StopWatch | timer_ |
PointCloudT::Ptr | voxel_centroid_cloud_ |
Contains the Voxelized centroid Cloud. | |
pcl::search::KdTree< PointT >::Ptr | voxel_kdtree_ |
Contains a KDtree for the voxelized cloud. | |
Friends | |
class | SupervoxelHelper |
Implements a supervoxel algorithm based on voxel structure, normals, and rgb values.
Definition at line 119 of file supervoxel_clustering.h.
typedef VoxelAdjacencyList::edge_descriptor pcl::SupervoxelClustering< PointT >::EdgeID |
Definition at line 177 of file supervoxel_clustering.h.
typedef boost::ptr_list<SupervoxelHelper> pcl::SupervoxelClustering< PointT >::HelperListT [private] |
Definition at line 463 of file supervoxel_clustering.h.
typedef boost::shared_ptr<std::vector<int> > pcl::SupervoxelClustering< PointT >::IndicesPtr |
Definition at line 169 of file supervoxel_clustering.h.
typedef pcl::search::KdTree<PointT> pcl::SupervoxelClustering< PointT >::KdTreeT |
Definition at line 168 of file supervoxel_clustering.h.
typedef pcl::octree::OctreePointCloudAdjacencyContainer<PointT, VoxelData> pcl::SupervoxelClustering< PointT >::LeafContainerT |
Definition at line 161 of file supervoxel_clustering.h.
typedef std::vector<LeafContainerT*> pcl::SupervoxelClustering< PointT >::LeafVectorT |
Definition at line 162 of file supervoxel_clustering.h.
typedef pcl::PointCloud<Normal> pcl::SupervoxelClustering< PointT >::NormalCloudT |
Definition at line 165 of file supervoxel_clustering.h.
typedef pcl::octree::OctreePointCloudAdjacency<PointT, LeafContainerT> pcl::SupervoxelClustering< PointT >::OctreeAdjacencyT |
Definition at line 166 of file supervoxel_clustering.h.
typedef pcl::octree::OctreePointCloudSearch<PointT> pcl::SupervoxelClustering< PointT >::OctreeSearchT |
Definition at line 167 of file supervoxel_clustering.h.
typedef pcl::PointCloud<PointT> pcl::SupervoxelClustering< PointT >::PointCloudT |
Definition at line 164 of file supervoxel_clustering.h.
typedef boost::adjacency_list<boost::setS, boost::setS, boost::undirectedS, uint32_t, float> pcl::SupervoxelClustering< PointT >::VoxelAdjacencyList |
Definition at line 175 of file supervoxel_clustering.h.
typedef VoxelAdjacencyList::vertex_descriptor pcl::SupervoxelClustering< PointT >::VoxelID |
Definition at line 176 of file supervoxel_clustering.h.
pcl::SupervoxelClustering< PointT >::SupervoxelClustering | ( | float | voxel_resolution, |
float | seed_resolution, | ||
bool | use_single_camera_transform = true |
||
) |
Constructor that sets default values for member variables.
[in] | voxel_resolution | The resolution (in meters) of voxels used |
[in] | seed_resolution | The average size (in meters) of resulting supervoxels |
[in] | use_single_camera_transform | Set to true if point density in cloud falls off with distance from origin (such as with a cloud coming from one stationary camera), set false if input cloud is from multiple captures from multiple locations. |
Definition at line 47 of file supervoxel_clustering.hpp.
pcl::SupervoxelClustering< PointT >::~SupervoxelClustering | ( | ) | [virtual] |
This destructor destroys the cloud, normals and search method used for finding neighbors. In other words it frees memory.
Definition at line 76 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::computeVoxelData | ( | ) | [private] |
This sets the data of the voxels in the tree.
Definition at line 207 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::createSupervoxelHelpers | ( | std::vector< PointT, Eigen::aligned_allocator< PointT > > & | seed_points | ) | [private] |
This method creates the internal supervoxel helpers based on the provided seed points.
[in] | seed_points | The selected points |
Definition at line 308 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::expandSupervoxels | ( | int | depth | ) | [private] |
This performs the superpixel evolution.
Definition at line 258 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::extract | ( | std::map< uint32_t, typename Supervoxel< PointT >::Ptr > & | supervoxel_clusters | ) | [virtual] |
This method launches the segmentation algorithm and returns the supervoxels that were obtained during the segmentation.
[out] | supervoxel_clusters | A map of labels to pointers to supervoxel structures |
Definition at line 98 of file supervoxel_clustering.hpp.
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr pcl::SupervoxelClustering< PointT >::getColoredCloud | ( | ) | const |
Returns an RGB colorized cloud showing superpixels Otherwise it returns an empty pointer. Points that belong to the same supervoxel have the same color. But this function doesn't guarantee that different segments will have different color(it's random). Points that are unlabeled will be black.
Definition at line 514 of file supervoxel_clustering.hpp.
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr pcl::SupervoxelClustering< PointT >::getColoredVoxelCloud | ( | ) | const |
Returns an RGB colorized voxelized cloud showing superpixels Otherwise it returns an empty pointer. Points that belong to the same supervoxel have the same color. But this function doesn't guarantee that different segments will have different color(it's random). Points that are unlabeled will be black.
Definition at line 545 of file supervoxel_clustering.hpp.
pcl::PointCloud< pcl::PointXYZL >::Ptr pcl::SupervoxelClustering< PointT >::getLabeledCloud | ( | ) | const |
Returns labeled cloud Points that belong to the same supervoxel have the same label. Labels for segments start from 1, unlabled points have label 0.
Definition at line 598 of file supervoxel_clustering.hpp.
pcl::PointCloud< pcl::PointXYZL >::Ptr pcl::SupervoxelClustering< PointT >::getLabeledVoxelCloud | ( | ) | const |
Returns labeled voxelized cloud Points that belong to the same supervoxel have the same label. Labels for segments start from 1, unlabled points have label 0.
Definition at line 576 of file supervoxel_clustering.hpp.
float pcl::SupervoxelClustering< PointT >::getSeedResolution | ( | ) | const |
Get the resolution of the octree seed voxels.
Definition at line 660 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::getSupervoxelAdjacency | ( | std::multimap< uint32_t, uint32_t > & | label_adjacency | ) | const |
Get a multimap which gives supervoxel adjacency.
[out] | label_adjacency | Multi-Map which maps a supervoxel label to all adjacent supervoxel labels |
Definition at line 495 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::getSupervoxelAdjacencyList | ( | VoxelAdjacencyList & | adjacency_list_arg | ) | const |
Gets the adjacency list (Boost Graph library) which gives connections between supervoxels.
[out] | adjacency_list_arg | BGL graph where supervoxel labels are vertices, edges are touching relationships |
Definition at line 444 of file supervoxel_clustering.hpp.
pcl::PointCloud< PointT >::Ptr pcl::SupervoxelClustering< PointT >::getVoxelCentroidCloud | ( | ) | const |
Returns a deep copy of the voxel centroid cloud.
Definition at line 567 of file supervoxel_clustering.hpp.
float pcl::SupervoxelClustering< PointT >::getVoxelResolution | ( | ) | const |
Get the resolution of the octree voxels.
Definition at line 645 of file supervoxel_clustering.hpp.
pcl::PointCloud< pcl::PointNormal >::Ptr pcl::SupervoxelClustering< PointT >::makeSupervoxelNormalCloud | ( | std::map< uint32_t, typename Supervoxel< PointT >::Ptr > & | supervoxel_clusters | ) | [static] |
Static helper function which returns a pointcloud of normals for the input supervoxels.
[in] | supervoxel_clusters | Supervoxel cluster map coming from this class |
Definition at line 628 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::makeSupervoxels | ( | std::map< uint32_t, typename Supervoxel< PointT >::Ptr > & | supervoxel_clusters | ) | [private] |
Constructs the map of supervoxel clusters from the internal supervoxel helpers.
Definition at line 290 of file supervoxel_clustering.hpp.
bool pcl::SupervoxelClustering< PointT >::prepareForSegmentation | ( | ) | [private, virtual] |
This method simply checks if it is possible to execute the segmentation algorithm with the current settings. If it is possible then it returns true.
Definition at line 182 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::refineSupervoxels | ( | int | num_itr, |
std::map< uint32_t, typename Supervoxel< PointT >::Ptr > & | supervoxel_clusters | ||
) | [virtual] |
This method refines the calculated supervoxels - may only be called after extract.
[in] | num_itr | The number of iterations of refinement to be done (2 or 3 is usually sufficient) |
[out] | supervoxel_clusters | The resulting refined supervoxels |
Definition at line 150 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::reseedSupervoxels | ( | ) | [private] |
Reseeds the supervoxels by finding the voxel closest to current centroid.
Definition at line 388 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::selectInitialSupervoxelSeeds | ( | std::vector< PointT, Eigen::aligned_allocator< PointT > > & | seed_points | ) | [private] |
This selects points to use as initial supervoxel centroids.
[out] | seed_points | The selected points |
Definition at line 330 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::setColorImportance | ( | float | val | ) |
Set the importance of color for supervoxels.
Definition at line 675 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::setInputCloud | ( | typename pcl::PointCloud< PointT >::ConstPtr | cloud | ) | [virtual] |
This method sets the cloud to be supervoxelized.
[in] | cloud | The cloud to be supervoxelize |
Definition at line 83 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::setNormalImportance | ( | float | val | ) |
Set the importance of scalar normal product for supervoxels.
Definition at line 689 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::setSeedResolution | ( | float | seed_resolution | ) |
Set the resolution of the octree seed voxels.
Definition at line 667 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::setSpatialImportance | ( | float | val | ) |
Set the importance of spatial distance for supervoxels.
Definition at line 682 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::setVoxelResolution | ( | float | resolution | ) |
Set the resolution of the octree voxels.
Definition at line 652 of file supervoxel_clustering.hpp.
void pcl::SupervoxelClustering< PointT >::transformFunction | ( | PointT & | p | ) | [private] |
Transform function used to normalize voxel density versus distance from camera.
Definition at line 416 of file supervoxel_clustering.hpp.
float pcl::SupervoxelClustering< PointT >::voxelDataDistance | ( | const VoxelData & | v1, |
const VoxelData & | v2 | ||
) | const [private] |
Distance function used for comparing voxelDatas.
Definition at line 425 of file supervoxel_clustering.hpp.
friend class SupervoxelHelper [friend] |
Definition at line 122 of file supervoxel_clustering.h.
OctreeAdjacencyT::Ptr pcl::SupervoxelClustering< PointT >::adjacency_octree_ [private] |
Octree Adjacency structure with leaves at voxel resolution.
Definition at line 353 of file supervoxel_clustering.h.
float pcl::SupervoxelClustering< PointT >::color_importance_ [private] |
Importance of color in clustering.
Definition at line 359 of file supervoxel_clustering.h.
std::vector<uint32_t> pcl::SupervoxelClustering< PointT >::label_colors_ [private] |
Stores the colors used for the superpixel labels.
Definition at line 366 of file supervoxel_clustering.h.
float pcl::SupervoxelClustering< PointT >::normal_importance_ [private] |
Importance of similarity in normals for clustering.
Definition at line 363 of file supervoxel_clustering.h.
float pcl::SupervoxelClustering< PointT >::resolution_ [private] |
Stores the resolution used in the octree.
Definition at line 336 of file supervoxel_clustering.h.
float pcl::SupervoxelClustering< PointT >::seed_resolution_ [private] |
Stores the resolution used to seed the superpixels.
Definition at line 339 of file supervoxel_clustering.h.
float pcl::SupervoxelClustering< PointT >::spatial_importance_ [private] |
Importance of distance from seed center in clustering.
Definition at line 361 of file supervoxel_clustering.h.
HelperListT pcl::SupervoxelClustering< PointT >::supervoxel_helpers_ [private] |
Definition at line 464 of file supervoxel_clustering.h.
StopWatch pcl::SupervoxelClustering< PointT >::timer_ [private] |
Definition at line 467 of file supervoxel_clustering.h.
PointCloudT::Ptr pcl::SupervoxelClustering< PointT >::voxel_centroid_cloud_ [private] |
Contains the Voxelized centroid Cloud.
Definition at line 356 of file supervoxel_clustering.h.
pcl::search::KdTree<PointT>::Ptr pcl::SupervoxelClustering< PointT >::voxel_kdtree_ [private] |
Contains a KDtree for the voxelized cloud.
Definition at line 350 of file supervoxel_clustering.h.