Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef PCL_MIN_CUT_SEGMENTATION_H_
00040 #define PCL_MIN_CUT_SEGMENTATION_H_
00041
00042 #include <pcl/segmentation/boost.h>
00043 #if (BOOST_VERSION >= 104400)
00044 #include <pcl/pcl_base.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/point_types.h>
00047 #include <pcl/search/search.h>
00048 #include <string>
00049 #include <set>
00050
00051 namespace pcl
00052 {
00058 template <typename PointT>
00059 class PCL_EXPORTS MinCutSegmentation : public pcl::PCLBase<PointT>
00060 {
00061 public:
00062
00063 typedef pcl::search::Search <PointT> KdTree;
00064 typedef typename KdTree::Ptr KdTreePtr;
00065 typedef pcl::PointCloud< PointT > PointCloud;
00066 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00067
00068 using PCLBase <PointT>::input_;
00069 using PCLBase <PointT>::indices_;
00070 using PCLBase <PointT>::initCompute;
00071 using PCLBase <PointT>::deinitCompute;
00072
00073 public:
00074
00075 typedef boost::adjacency_list_traits< boost::vecS, boost::vecS, boost::directedS > Traits;
00076
00077 typedef boost::adjacency_list< boost::vecS, boost::vecS, boost::directedS,
00078 boost::property< boost::vertex_name_t, std::string,
00079 boost::property< boost::vertex_index_t, long,
00080 boost::property< boost::vertex_color_t, boost::default_color_type,
00081 boost::property< boost::vertex_distance_t, long,
00082 boost::property< boost::vertex_predecessor_t, Traits::edge_descriptor > > > > >,
00083 boost::property< boost::edge_capacity_t, double,
00084 boost::property< boost::edge_residual_capacity_t, double,
00085 boost::property< boost::edge_reverse_t, Traits::edge_descriptor > > > > mGraph;
00086
00087 typedef boost::property_map< mGraph, boost::edge_capacity_t >::type CapacityMap;
00088
00089 typedef boost::property_map< mGraph, boost::edge_reverse_t>::type ReverseEdgeMap;
00090
00091 typedef Traits::vertex_descriptor VertexDescriptor;
00092
00093 typedef boost::graph_traits< mGraph >::edge_descriptor EdgeDescriptor;
00094
00095 typedef boost::graph_traits< mGraph >::out_edge_iterator OutEdgeIterator;
00096
00097 typedef boost::graph_traits< mGraph >::vertex_iterator VertexIterator;
00098
00099 typedef boost::property_map< mGraph, boost::edge_residual_capacity_t >::type ResidualCapacityMap;
00100
00101 typedef boost::property_map< mGraph, boost::vertex_index_t >::type IndexMap;
00102
00103 typedef boost::graph_traits< mGraph >::in_edge_iterator InEdgeIterator;
00104
00105 public:
00106
00108 MinCutSegmentation ();
00109
00111 virtual
00112 ~MinCutSegmentation ();
00113
00117 virtual void
00118 setInputCloud (const PointCloudConstPtr &cloud);
00119
00121 double
00122 getSigma () const;
00123
00127 void
00128 setSigma (double sigma);
00129
00131 double
00132 getRadius () const;
00133
00137 void
00138 setRadius (double radius);
00139
00141 double
00142 getSourceWeight () const;
00143
00147 void
00148 setSourceWeight (double weight);
00149
00153 KdTreePtr
00154 getSearchMethod () const;
00155
00160 void
00161 setSearchMethod (const KdTreePtr& tree);
00162
00164 unsigned int
00165 getNumberOfNeighbours () const;
00166
00170 void
00171 setNumberOfNeighbours (unsigned int neighbour_number);
00172
00174 std::vector<PointT, Eigen::aligned_allocator<PointT> >
00175 getForegroundPoints () const;
00176
00180 void
00181 setForegroundPoints (typename pcl::PointCloud<PointT>::Ptr foreground_points);
00182
00184 std::vector<PointT, Eigen::aligned_allocator<PointT> >
00185 getBackgroundPoints () const;
00186
00190 void
00191 setBackgroundPoints (typename pcl::PointCloud<PointT>::Ptr background_points);
00192
00198 void
00199 extract (std::vector <pcl::PointIndices>& clusters);
00200
00202 double
00203 getMaxFlow () const;
00204
00206 typename boost::shared_ptr<typename pcl::MinCutSegmentation<PointT>::mGraph>
00207 getGraph () const;
00208
00210 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00211 getColoredCloud ();
00212
00213 protected:
00214
00216 bool
00217 buildGraph ();
00218
00225 void
00226 calculateUnaryPotential (int point, double& source_weight, double& sink_weight) const;
00227
00233 bool
00234 addEdge (int source, int target, double weight);
00235
00241 double
00242 calculateBinaryPotential (int source, int target) const;
00243
00245 bool
00246 recalculateUnaryPotentials ();
00247
00249 bool
00250 recalculateBinaryPotentials ();
00251
00255 void
00256 assembleLabels (ResidualCapacityMap& residual_capacity);
00257
00258 protected:
00259
00261 double inverse_sigma_;
00262
00264 bool binary_potentials_are_valid_;
00265
00267 double epsilon_;
00268
00270 double radius_;
00271
00273 bool unary_potentials_are_valid_;
00274
00276 double source_weight_;
00277
00279 KdTreePtr search_;
00280
00282 unsigned int number_of_neighbours_;
00283
00285 bool graph_is_valid_;
00286
00288 std::vector<PointT, Eigen::aligned_allocator<PointT> > foreground_points_;
00289
00291 std::vector<PointT, Eigen::aligned_allocator<PointT> > background_points_;
00292
00294 std::vector <pcl::PointIndices> clusters_;
00295
00297 boost::shared_ptr<mGraph> graph_;
00298
00300 boost::shared_ptr<CapacityMap> capacity_;
00301
00303 boost::shared_ptr<ReverseEdgeMap> reverse_edges_;
00304
00306 std::vector< VertexDescriptor > vertices_;
00307
00309 std::vector< std::set<int> > edge_marker_;
00310
00312 VertexDescriptor source_;
00313
00315 VertexDescriptor sink_;
00316
00318 double max_flow_;
00319
00320 public:
00321 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00322 };
00323 }
00324
00325 #ifdef PCL_NO_PRECOMPILE
00326 #include <pcl/segmentation/impl/min_cut_segmentation.hpp>
00327 #endif
00328
00329 #endif
00330 #endif