cluster_graph_structure.h
Go to the documentation of this file.
00001 
00063 #ifndef __CLUSTER_GRAPH_STRUCTURE_H__
00064 #define __CLUSTER_GRAPH_STRUCTURE_H__
00065 
00066 #include <utility>
00067 
00068 #include <boost/graph/adjacency_list.hpp>
00069 #include <boost/graph/graph_traits.hpp>
00070 
00071 #include "cob_3d_segmentation/cluster_handler.h"
00072 #include "cob_3d_segmentation/edge_handler.h"
00073 
00074 namespace cob_3d_segmentation
00075 {
00076   template <typename ClusterHandlerT, typename EdgeHandlerT>
00077   class ClusterGraphStructure
00078   {
00079   public:
00080     typedef typename ClusterHandlerT::Ptr ClusterHandlerPtr;
00081     typedef typename ClusterHandlerT::ClusterType ClusterType;
00082     typedef typename ClusterHandlerT::ClusterPtr ClusterPtr;
00083     typedef typename EdgeHandlerT::Ptr EdgeHandlerPtr;
00084     typedef typename EdgeHandlerT::EdgeType EdgeType;
00085     typedef typename EdgeHandlerT::EdgePtr EdgePtr;
00086 
00087     typedef boost::shared_ptr<ClusterGraphStructure<ClusterHandlerT, EdgeHandlerT> > Ptr;
00088 
00089   public:
00090     ClusterGraphStructure()
00091       : c_hdl_(new ClusterHandlerT)
00092       , e_hdl_(new EdgeHandlerT)
00093       , g_()
00094       , vid_()
00095     { }
00096 
00097     ClusterGraphStructure(ClusterHandlerPtr c_hdl, EdgeHandlerPtr e_hdl)
00098       : c_hdl_(c_hdl)
00099       , e_hdl_(e_hdl)
00100       , g_()
00101       , vid_()
00102     { }
00103 
00104     ~ClusterGraphStructure()
00105     { }
00106 
00107     inline ClusterHandlerPtr clusters() { return c_hdl_; }
00108     inline EdgeHandlerPtr edges() { return e_hdl_; }
00109 
00110     inline void clear() { c_hdl_->clear(); e_hdl_->clear(); vid_.clear(); g_.clear(); }
00111 
00112     EdgePtr connect(const int cid1, const int cid2)
00113     {
00114       if (cid1 == cid2) { std::cout << "[ClusterGraphStructure::connect]: connect identic IDs" << std::endl; return e_hdl_->end(); }
00115       if (vid_.find(cid1) == vid_.end()) { vid_[cid1] = boost::add_vertex(GraphVertex(c_hdl_->getCluster(cid1)), g_); }
00116       if (vid_.find(cid2) == vid_.end()) { vid_[cid2] = boost::add_vertex(GraphVertex(c_hdl_->getCluster(cid2)), g_); }
00117       std::pair<EdgeID,bool> res = boost::add_edge(vid_[cid1], vid_[cid2], g_);
00118       if (res.second) g_[res.first].e_it = e_hdl_->createEdge();
00119       return g_[res.first].e_it;
00120     }
00121 
00122     inline bool areConnected(const int cid1, const int cid2)
00123     { return (boost::edge(vid_.find(cid1)->second, vid_.find(cid2)->second, g_)).second; }
00124 
00125     inline EdgePtr getConnection(const int cid1, const int cid2)
00126     { return g_[boost::edge(vid_.find(cid1)->second, vid_.find(cid2)->second, g_).first].e_it; }
00127 
00128     void merge(const int cid_source, const int cid_target);
00129     void merge(const int cid_source, const int cid_target, std::vector<EdgePtr>& updated_edges);
00130     void getAdjacentClusters(int cid, std::vector<ClusterPtr>& adjacent_clusters);
00131     void getConnectedClusters(int cid_start, std::vector<ClusterPtr>& connected_clusters, boost::function<bool (EdgePtr)> f);
00132 
00133 
00134   private:
00135     struct GraphVertex
00136     {
00137       GraphVertex() { };
00138       GraphVertex(ClusterPtr it) : c_it(it) { };
00139 
00140       ClusterPtr c_it;
00141     };
00142 
00143     struct GraphEdge
00144     {
00145       GraphEdge() {};
00146       GraphEdge(EdgePtr it) : e_it(it) { };
00147 
00148       EdgePtr e_it;
00149     };
00150 
00151     // adjacencs_list< OutEdgeList, VertexList, TransitionType[, VertexProperties, EdgeProperties, GraphProperties, EdgeList] >
00152     typedef boost::adjacency_list<boost::setS, boost::listS, boost::undirectedS, GraphVertex, GraphEdge> GraphT;
00153     typedef typename boost::graph_traits<GraphT>::vertex_descriptor VertexID;
00154     typedef typename boost::graph_traits<GraphT>::edge_descriptor EdgeID;
00155 
00156     void merge(const VertexID src, const VertexID trg, std::vector<EdgePtr>& updated_edges);
00157 
00158     ClusterHandlerPtr c_hdl_;
00159     EdgeHandlerPtr e_hdl_;
00160     GraphT g_;
00161     std::map<int, VertexID> vid_;
00162   };
00163 }
00164 
00165 #endif


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:03