graph_builder.h
Go to the documentation of this file.
1/*
2 * Software License Agreement (BSD License)
3 *
4 * Point Cloud Library (PCL) - www.pointclouds.org
5 * Copyright (c) 2014-, Open Perception, Inc.
6 *
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of the copyright holder(s) nor the names of its
20 * contributors may be used to endorse or promote products derived
21 * from this software without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *
36 */
37
38#ifndef PCL_GRAPH_GRAPH_BUILDER_H
39#define PCL_GRAPH_GRAPH_BUILDER_H
40
41#include <boost/concept_check.hpp>
42
43#include <pcl/pcl_base.h>
44
45#include "point_cloud_graph.h"
47
48namespace pcl::graph
49{
50
51 /** This is an abstract base class for building a BGL-compatible point cloud
52 * graph from a point cloud.
53 *
54 * Building a graph involves creating vertices and establishing edges
55 * between them. (A particular algorithm for doing these depends on the
56 * extending class.)
57 *
58 * The two template parameters are the type of points in input cloud and
59 * the output graph type. The graph type should be a model of
60 * \ref concepts::PointCloudGraphConcept (i.e. either point_cloud_graph or
61 * \c boost::subgraph wrapped around the former). The type of input points
62 * and points bundled in graph vertices do not need to be the same.
63 *
64 * \author Sergey Alexandrov
65 * \ingroup graph */
66 template <typename PointT, typename GraphT>
67 class PCL_EXPORTS GraphBuilder : public pcl::PCLBase<PointT>
68 {
69
70 BOOST_CONCEPT_ASSERT((pcl::graph::PointCloudGraphConcept<GraphT>));
71
72 public:
74
75 /// Type of points in the input cloud.
76 typedef PointT PointInT;
77 /// Type of points in the output graph.
79
80 typedef typename boost::graph_traits<GraphT>::vertex_descriptor VertexId;
81
82 /** Build a graph based on the provided input data. */
83 virtual void compute(GraphT& graph) = 0;
84
85 /** Get a mapping between points in the input cloud and the vertices in
86 * the output graph.
87 *
88 * \warning Some points may have no corresponding vertex. This happens
89 * e.g. for NaN points, or if the user intentionally excluded some
90 * points from graph building process by providing indices vector with
91 * setIndices(). For such points the "nil" vertex id will be assigned,
92 * which is equal to std::numeric_limits<VertexId>::max (). */
93 const std::vector<VertexId>&
95 {
96 return (point_to_vertex_map_);
97 }
98
99 protected:
100 std::vector<VertexId> point_to_vertex_map_;
101 };
102
103} // namespace pcl::graph
104
105
106#endif /* PCL_GRAPH_GRAPH_BUILDER_H */
This is an abstract base class for building a BGL-compatible point cloud graph from a point cloud.
boost::graph_traits< GraphT >::vertex_descriptor VertexId
const std::vector< VertexId > & getPointToVertexMap() const
Get a mapping between points in the input cloud and the vertices in the output graph.
point_cloud_graph_traits< GraphT >::point_type PointOutT
Type of points in the output graph.
std::vector< VertexId > point_to_vertex_map_
virtual void compute(GraphT &graph)=0
Build a graph based on the provided input data.
boost::shared_ptr< GraphBuilder< PointT, GraphT > > Ptr
PointT PointInT
Type of points in the input cloud.
A PointCloudGraph is a graph that has PCL points bundled in vertices and can be viewed as a PCL point...
Graph::point_type point_type
The type of PCL points bundled in vertices.