point_cloud_graph.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_POINT_CLOUD_GRAPH_H
39 #define PCL_GRAPH_POINT_CLOUD_GRAPH_H
40 
41 #include <boost/graph/adjacency_list.hpp>
42 #include <boost/graph/subgraph.hpp>
43 
44 #include <pcl/PointIndices.h>
45 #include <pcl/point_cloud.h>
46 #include <pcl/point_types.h>
47 
48 /** \class pcl::graph::point_cloud_graph
49  *
50  * A sibling of `boost::adjacency_list` with PCL points bundled in vertices and copy-free access to them as a PCL point
51  * cloud.
52  *
53  *
54  * # Motivation #
55  *
56  *
57  * Boost Graph Library has a concept of [bundled properties][BundledProperties], i.e. custom data types that may be
58  * stored in graph vertices and conveniently accessed with `operator[]`. In the context of PCL it makes a lot of sense
59  * to have PCL points bundled in graph vertices. The following specialization of [boost::adjacency_list][AdjacencyList]
60  * achieves that:
61  *
62  * ~~~cpp
63  * typedef
64  * boost::adjacency_list<
65  * boost::vecS // Represent edge-list with std::vector
66  * , boost::vecS // Represent vertex-list with std::vector
67  * , boost::undirectedS // Undirected graph
68  * , pcl::PointXYZ> // Bundle XYZ points in vertices
69  * Graph
70  * ~~~
71  *
72  * A graph-based algorithm can easily access points associated with graph vertices:
73  *
74  * ~~~cpp
75  * Graph graph;
76  * Graph::vertex_descriptor v1 = boost::add_vertex (graph);
77  * Graph::vertex_descriptor v2 = boost::add_vertex (graph);
78  * graph[v1] = pcl::PointXYZ (1, 2, 3);
79  * graph[v2].x = graph[v1].x;
80  * ~~~
81  *
82  * The problem though is that there is no efficient way to put the point cloud data inside the graph and retrieve it
83  * back. Suppose that in some application there is a point cloud that should first be filtered using some PCL tools
84  * (e.g. pcl::PassThrough filter), then a graph-based algorithm should be applied to it, and finally some more
85  * processing using PCL tools is required. The user will need to copy all the points of the original point cloud
86  * one-by-one to the graph, run the algorithm, and then copy it back one-by-one again.
87  *
88  *
89  * # Solution #
90  *
91  *
92  * point_cloud_graph resolves this issue by storing bundled points internally as a PCL point cloud. In fact, it stores
93  * a shared pointer to a point cloud, so input and output of points is really copy-free. One can create a new graph
94  * based on an existing point cloud:
95  *
96  * ~~~cpp
97  * // Create a point cloud with 10 points
98  * pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> (10, 1);
99  * // Create a graph based on the cloud
100  * pcl::graph::point_cloud_graph<pcl::PointXYZ> graph (cloud);
101  * // The graph will have a vertex for each point of the original cloud
102  * assert (10 == boost::num_vertices (graph));
103  * // The points may be accessed using operator[]
104  * graph[1].x = 14;
105  * // The graph shares data with the original point cloud, so modifying a bundled point
106  * // changes the corresponding point in the original cloud
107  * assert (14 == cloud->points[1].x);
108  * ~~~
109  *
110  * The internal point cloud as a whole may be accessed using `pcl::graph::point_cloud (Graph& g)`:
111  *
112  * ~~~cpp
113  * // Perform some graph-based algorithm on point cloud graph
114  * // ...
115  * // Retrieve the bundled data as a point cloud
116  * pcl::PointCloud<pcl::PointXYZ>::Ptr data = pcl::graph::point_cloud (graph);
117  * // Continue to work with the data
118  * pcl::io::savePCDFile ("output.pcd", *data);
119  * ~~~
120  *
121  * Despite the fact that the point data are stored in a PCL point cloud, all the standard BGL features associated with
122  * bundled properties are supported, including `operator[]` and `get`/`put` access.
123  *
124  * [BundledProperties]: http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/bundles.html
125  *
126  *
127  * ## Comparison with [boost::adjacency_list][AdjacencyList] ##
128  *
129  *
130  * point_cloud_graph uses the same back-bone implementation as [boost::adjacency_list][AdjacencyList] and therefore
131  * models the same concepts and may be used everywhere `boost::adjacency_list` could. In particular, the very same
132  * functions could be used to add and remove vertices, access properties, iterate over edges, etc.
133  *
134  * As `boost::adjacency_list`, point_cloud_graph allows to configure itself with a number of template parameters. They
135  * are almost the same as in `boost::adjacency_list`, though there are several differences:
136  *
137  * 1. There is a required template parameter `PointT` which allows the user to select the type of PCL points to be
138  * bundled in graph vertices;
139  *
140  * Note that the `VertexProperty` parameter is still available for the user, so it is possible to additionally
141  * attach as many [internal properties][InternalProperties] (such as `vertex_color_t`) as needed.
142  *
143  * 2. The default value for `Directed` parameter is changed to `undirectedS` since it is more relevant in the context
144  * of point cloud processing;
145  *
146  * 3. The vertex-list of the graph is constrained to be `std::vector`. The user has no control over it as there is no
147  * `VertexList` template parameter;
148  *
149  * The choice of the container for the vertex-list determines the space complexity of the graph structure, as well
150  * as the time complexity of the various graph operations, see [using boost::adjacency_list][UsingAdjacencyList] for
151  * a more detailed discussion. In the case of point_cloud_graph the vertex bundled properties (PCL points) are
152  * stored in a PCL point cloud (which has `std::vector` behind the scenes), so it is only logical to have
153  * `std::vector` as the container type for the vertex-list itself.
154  *
155  * 4. There is no `GraphProperty` template parameter.
156  *
157  * [boost::adjacency_list][AdjacencyList] provides a facility to store an arbitrary piece of data associated with
158  * the graph as a whole (graph property). While being useful in certain cases, we do not consider this as a vital
159  * feature and have sacrificed it to support [boost::subgraph][Subgraph]. For more details please refer to the
160  * section about `boost::subgraph` below.
161  *
162  * [AdjacencyList]: http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/adjacency_list.html "adjacency_list"
163  * [InternalProperties]: http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/using_adjacency_list.html#sec:adjacency-list-properties
164  * [UsingAdjacencyList]: http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/using_adjacency_list.html#sec:choosing-graph-type
165  * [Subgraph]: http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/subgraph.html "subgraph"
166  *
167  *
168  * ## Compatibility with [boost::subgraph][Subgraph] ##
169  *
170  *
171  * `boost::subgraph` provides a convenient mechanism to keep track of a graph and its induced subgraphs. Two issues
172  * have been accounted for in order to allow smooth inter-operation between point_cloud_graph and `boost::subgraph`.
173  *
174  *
175  * ### Fixed interface ###
176  *
177  *
178  * `boost::subgraph` is a template class that is *wrapped around* a graph class rather than a class that *inherits*
179  * from a graph class. Therefore if we want it to be possible to use point_cloud_graph either way (plain or wrapped by
180  * `boost::subgraph`), we have to limit ourselves to the interface exposed by `boost::subgraph`. In particular, we can
181  * not have a PCL point cloud-based constructor for point_cloud_graph because (for apparent reasons) `boost::subgraph`
182  * does not have it. However, the ability to construct a point_cloud_graph from an existing PCL point cloud is an
183  * essential feature. We noted that `boost::subgraph` has a GraphProperty-based constructor that could be re-used as a
184  * desired PCL point cloud-based constructor if we alias GraphProperty to PCL point cloud. Thus GraphProperty is used
185  * to support internal mechanics of point_cloud_graph and is no longer available to the user.
186  *
187  *
188  * ### Lack of internal storage for points ###
189  *
190  *
191  * Recall that point_cloud_graph stores the points bundled in its vertices inside a PCL point cloud. It could be
192  * conveniently retrieved using `pcl::graph::point_cloud (Graph& g)` and then used in PCL algorithms.
193  * `boost::subgraph`, however, is designed in such a way that it stores the indices of the vertices and edges of the
194  * parent (root) graph that belong to it, but not the data associated with these vertices and edges. In other words, a
195  * hierarchy of subgraphs (each of which represents a particular subset of vertices and edges of the root graph) shares
196  * common vertex/edge data, and all these data are contained inside the root graph. Consequently, there does not exist
197  * a PCL point cloud for each subgraph, but rather a single PCL point cloud for the root graph. This raises a question
198  * as of how the `pcl::graph::point_cloud (Subgraph& g)` function should be implemented.
199  *
200  * One option is to construct a new PCL point cloud and fill it with subgraph's points. This, however, would be
201  * inconsistent with the behavior of `pcl::graph::point_cloud (Graph& g)`, which simply returns a pointer (meaning it
202  * is *O(1)* operation) that could be used to read and modify the points of the graph. Luckily, working with subsets of
203  * point clouds is such a common task in the PCL world that \ref pcl::PCLBase class (which lies at the top of the
204  * hierarchy of PCL algorithms) has a means for the user to supply an input point cloud *and* a vector of indices to
205  * which the processing should be limited to. Therefore, we decided that `pcl::graph::point_cloud (Subgraph& g)` should
206  * return the PCL point cloud of its root graph (that is, the whole set of points), and there should be an auxiliary
207  * function `pcl::graph::indices (Subgraph& g)` that returns indices of the points that belong to the subgraph.
208  *
209  *
210  * - - -
211  *
212  *
213  * # Specification #
214  *
215  *
216  * As was noted, point_cloud_graph is virtually the same as [boost::adjacency_list][AdjacencyList]. Please refer to
217  * its documentation. The specifications below only highlight the differences.
218  *
219  *
220  * ## Template parameters ##
221  *
222  *
223  * Parameter | Description | Default
224  * -------------- | ------------------------------------------------------------------------------------|--------------
225  * PointT | Type of PCL points bundled in graph vertices | --
226  * OutEdgeList | Selector for the container used to represent the edge-list for each of the vertices | `vecS`
227  * Directed | Selector to choose whether the graph is directed/undirected/bidirectional | `undirectedS`
228  * VertexProperty | For specifying internal vertex property storage (apart from bundled points) | `no_property`
229  * EdgeProperty | For specifying internal edge property storage | `no_property`
230  * EdgeList | Selector for the container used to represent the edge-list for the graph | `listS`
231  *
232  *
233  * ## Model of ##
234  *
235  *
236  * [PointCloudGraph](\ref boost::concepts::PointCloudGraphConcept),
237  * [VertexAndEdgeListGraph](http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/VertexAndEdgeListGraph.html),
238  * [VertexMutablePropertyGraph](http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/MutablePropertyGraph.html),
239  * [EdgeMutablePropertyGraph](http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/MutablePropertyGraph.html),
240  * [CopyConstructible](http://www.boost.org/doc/libs/1_55_0/libs/utility/CopyConstructible.html),
241  * [Assignable](http://www.boost.org/doc/libs/1_55_0/libs/utility/Assignable.html)
242  *
243  * Probably it could also support [Serializable][Serialization], however this option has not been explored.
244  *
245  * [Serialization]: http://www.boost.org/doc/libs/1_55_0/libs/serialization/doc/index.html
246  *
247  *
248  * ## Associated types ##
249  *
250  *
251  * point_cloud_graph_traits structure provides a means to access the type of points bundled in the point_cloud_graph
252  * and, for convenience, the types of PCL point cloud and shared pointer to PCL point cloud of those points.
253  *
254  *
255  * ## Non-member functions ##
256  *
257  *
258  * ~~~cpp
259  * typename pcl::PointCloud<PointT>::Ptr
260  * pcl::graph::point_cloud (point_cloud_graph<PointT>& g);
261  * ~~~
262  *
263  * Return a shared pointer to the PCL point cloud stored internally. There are both `const` and `non-const` versions.
264  *
265  * ~~~cpp
266  * typename pcl::PointCloud<PointT>::Ptr
267  * pcl::graph::point_cloud (boost::subgraph<point_cloud_graph<PointT>>& g);
268  * ~~~
269  *
270  * Return a shared pointer to the PCL point cloud stored in the *root* graph. There are both `const` and `non-const`
271  * versions.
272  *
273  * ~~~cpp
274  * pcl::PointIndices::Ptr
275  * pcl::graph::indices (point_cloud_graph<PointT>& g);
276  * ~~~
277  *
278  * Return a shared pointer to a vector of indices of the points that belong to this graph. Since point_cloud_graph is
279  * a complete graph (i.e. it is not a subgraph of some other graph), the returned indices are guaranteed to be
280  * *[0..N-1]*, where *N* is the number of vertices. There are both `const`- and `non-const`- versions.
281  *
282  * ~~~cpp
283  * pcl::PointIndices::Ptr
284  * pcl::graph::indices (boost::subgraph<point_cloud_graph<PointT>>& g);
285  * ~~~
286  *
287  * Return a shared pointer to a vector of indices of the points of the root graph that belong to this subgraph. There
288  * are both `const`- and `non-const`- versions.
289  *
290  * \author Sergey Alexandrov
291  * \ingroup graph */
292 
293 namespace pcl::graph
294 {
295 
296  template <typename PointT,
297  typename OutEdgeListS = boost::vecS,
298  typename DirectedS = boost::undirectedS,
299  typename VertexProperty = boost::no_property,
300  typename EdgeProperty = boost::no_property,
301  typename EdgeListS = boost::listS>
303  public boost::detail::adj_list_gen<point_cloud_graph<PointT,
304  OutEdgeListS,
305  DirectedS,
306  VertexProperty,
307  EdgeProperty,
308  EdgeListS>,
309  boost::vecS,
310  OutEdgeListS,
311  DirectedS,
312  VertexProperty,
313  EdgeProperty,
314  typename pcl::PointCloud<PointT>::Ptr,
315  EdgeListS>::type
316  // Not even sure what `maybe_named_graph` is, but without it
317  // CopyConstructible concept is not satisfied because of missing
318  // `vertex_by_property` (and some others) member functions
319  ,
320  public boost::graph::maybe_named_graph<
321  point_cloud_graph<PointT,
322  OutEdgeListS,
323  DirectedS,
324  VertexProperty,
325  EdgeProperty,
326  EdgeListS>,
327  typename boost::adjacency_list_traits<OutEdgeListS, boost::vecS, DirectedS, EdgeListS>::
328  vertex_descriptor,
329  VertexProperty>
330  {
331 
332  private:
333  typedef point_cloud_graph self;
334  typedef typename boost::detail::adj_list_gen<self,
335  boost::vecS,
336  OutEdgeListS,
337  DirectedS,
338  VertexProperty,
339  EdgeProperty,
340  typename pcl::PointCloud<PointT>::Ptr,
341  EdgeListS>::type Base;
342 
343  // Ensure that the user did not provide his own Bundle for vertices
344  BOOST_STATIC_ASSERT(
346 
347  public:
348  typedef typename pcl::PointCloud<PointT>::Ptr graph_property_type;
349  typedef typename pcl::PointCloud<PointT>::Ptr graph_bundled;
350  typedef typename Base::vertex_property_type vertex_property_type;
352  typedef typename Base::edge_property_type edge_property_type;
353  typedef typename Base::edge_bundled edge_bundled;
354 
355  typedef typename Base::stored_vertex stored_vertex;
356  typedef typename Base::vertices_size_type vertices_size_type;
357  typedef typename Base::edges_size_type edges_size_type;
358  typedef typename Base::degree_size_type degree_size_type;
359  typedef typename Base::vertex_descriptor vertex_descriptor;
360  typedef typename Base::edge_descriptor edge_descriptor;
361  typedef OutEdgeListS out_edge_list_selector;
362  typedef boost::vecS vertex_list_selector;
363  typedef DirectedS directed_selector;
364  typedef EdgeListS edge_list_selector;
365 
366  /// Type of PCL points bundled in graph vertices
368  typedef pcl::PointCloud<PointT> point_cloud_type;
369  typedef typename point_cloud_type::Ptr point_cloud_ptr;
370  typedef typename point_cloud_type::ConstPtr point_cloud_const_ptr;
371 
372  /** Construct a graph based on existing point cloud.
373  *
374  * The graph will have the same amount of vertices as the input point
375  * cloud has. The shared pointer will be stored internally so that the
376  * graph retains access to the point data.
377  *
378  * If the cloud is not given, then a new empty cloud will be created. */
380  Base(p->size()), m_point_cloud(p)
381  {
382  }
383 
384  /** Construct a graph with a given number of vertices.
385  *
386  * This constructor will create a new point cloud to store point data.
387  * The second parameter is completely ignored and is provided only to
388  * have the same interface as `adjacency_list`. */
391  Base(num_vertices), m_point_cloud(new point_cloud_type(num_vertices, 1))
392  {
393  }
394 
395  /** Copy constructor.
396  *
397  * Acts just like the standard copy constructor of `adjacency_list`,
398  * i.e. copies vertex and edge set along with associated properties.
399  * Note that a **deep copy** of the underlying point cloud is made.
400  *
401  * This constructor reuses assignment operator. An alternative approach
402  * would be to use the copy constructor of the base class and then copy
403  * over the underlying point cloud, however the problem is that the
404  * base constructor uses `boost::add_vertex` function, which will
405  * attempt to push points to the point cloud, although it will not be
406  * initialized yet at that point in time (hence segfault). */
408  {
409  *this = x;
410  }
411 
412  /** Assignment operator.
413  *
414  * Acts just like the standard assignment operator of `adjacency_list`,
415  * i.e. copies vertex and edge set along with associated properties. Note
416  * that a **deep copy** of the underlying point cloud is made. */
419  {
420  if (&x != this)
421  {
422  /* The motivation behind this `reset` invocation is as follows. The
423  * `operator=` function of the base class (`vec_adj_list_impl`) will
424  * use the standard `add_vertex` to append each vertex of the source
425  * graph one after another. Apparently, this is not the fastest way
426  * to copy the underlying point cloud. Resetting the point cloud
427  * pointer effectively makes `added_vertex` a no-op, so the time is
428  * not wasted copying points one by one. Rather in the next line we
429  * make a complete copy with one call. */
430  m_point_cloud.reset();
431  Base::operator=(x);
433  }
434  return (*this);
435  }
436 
437  /** Remove all of the edges and vertices from the graph.
438  *
439  * Note that it wipes the underlying point cloud as well. */
440  void
442  {
443  this->clearing_graph();
444  m_point_cloud->clear();
445  Base::clear();
446  }
447 
448  /* A note on the implementation of vertex addition/removal.
449  *
450  * In BGL vertices are added and removed to a graph via non-member
451  * functions `add_vertex` and `remove_vertex`. The implementation that is
452  * provided for `vec_adj_list_impl` (from which this class actually
453  * derives) does everything that is needed, except to adding/removing
454  * points from internal point cloud (for obvious reasons). In order to
455  * augment the behavior we could have specialized these functions for
456  * `point_cloud_graph` class, however that would involve copy-pasting of
457  * quite some code. Luckily, these functions have some sort of hooks
458  * which are member functions of graph object and got called in the end,
459  * namely `added_vertex` and `removing_vertex`. (In fact, they are
460  * designated to support some `named_graph` extension, but who cares.)
461  * Therefore these two hooks are implemented in `point_cloud_graph` to
462  * perform the desired point cloud maintenance. */
463 
464  void
466  {
467  if (m_point_cloud)
468  {
469  m_point_cloud->push_back(point_type());
470  }
471  }
472 
473  void
475  {
476  if (m_point_cloud)
477  {
478  m_point_cloud->erase(m_point_cloud->begin() + vertex);
479  }
480  }
481 
482  /* This second version of `removing_vertex` is to account for the
483  * change introduced in Boost 1.55, which added a second parameter to
484  * this function. The type of the second parameter is unimportant and
485  * likely is not present in earlier versions of Boost, hence generic
486  * templated version. */
487 
488  template <typename T>
489  void
491  {
492  removing_vertex(vertex);
493  }
494 
495  /** \name Access to bundled vertex/edge properties.
496  *
497  * The `operators[]`'s in this group may be used to access the data
498  * bundled in vertices and edges of the graph. Implementation was
499  * directly copied from `adjacency_list`.
500  *
501  * Note that there is no operator access to the GraphProperty as there
502  * is no such thing in point_cloud_graph (see the corresponding
503  * section in the class description for more information). */
504 
505  ///@{
506 
509  {
510  return (boost::get(boost::vertex_bundle, *this)[v]);
511  }
512 
513  const vertex_bundled&
515  {
516  return (boost::get(boost::vertex_bundle, *this)[v]);
517  }
518 
519  edge_bundled&
521  {
522  return (boost::get(boost::edge_bundle, *this)[e]);
523  }
524 
525  const edge_bundled&
527  {
528  return (boost::get(boost::edge_bundle, *this)[e]);
529  }
530 
531  ///@}
532 
533  /// Storage for the internal cloud data.
534  // This is public for the same reasons as everything in `boost::graph`
535  // is public.
537  };
538 
539  /** Traits struct to access the types associated with point_cloud_graph. */
540  template <typename Graph>
542  {
543  /// The type of PCL points bundled in vertices.
544  typedef typename Graph::point_type point_type;
545  /// The type of PCL point cloud the graph can be viewed as.
546  typedef typename Graph::point_cloud_type point_cloud_type;
547  /// The type of a shared pointer to PCL point cloud the graph can be
548  /// viewed as.
549  typedef typename Graph::point_cloud_ptr point_cloud_ptr;
550  /// The type of a shared pointer to const PCL point cloud the graph can be
551  /// viewed as.
552  typedef typename Graph::point_cloud_const_ptr point_cloud_const_ptr;
553  };
554 
555  /** Specialization for point_cloud_graphs wrapped in `boost::subgraph`. */
556  template <typename Graph>
557  struct point_cloud_graph_traits<boost::subgraph<Graph>> : point_cloud_graph_traits<Graph>
558  {
559  };
560 
561  /** This class is to expose the point cloud stored in the point_cloud_graph
562  * as a vertex bundle property map.
563  *
564  * The code is based on `boost::vector_property_map`. It might be the case
565  * that some of the member functions are not needed. */
566  template <typename Graph>
568  public boost::put_get_helper<
569  typename std::iterator_traits<
570  typename point_cloud_graph_traits<Graph>::point_cloud_type::iterator>::reference,
571  point_cloud_property_map<Graph>>
572  {
573 
574  public:
575  typedef typename boost::property_traits<boost::identity_property_map>::key_type key_type;
579  typedef typename std::iterator_traits<iterator>::reference reference;
581  typedef boost::lvalue_property_map_tag category;
582 
583  point_cloud_property_map(const Graph* g, boost::vertex_bundle_t) :
584  data(g->m_point_cloud), index(boost::identity_property_map())
585  {
586  }
587 
588  iterator
590  {
591  return (data->begin());
592  }
593 
594  iterator
596  {
597  return (data->end());
598  }
599 
602  {
603  return (data->begin());
604  }
605 
607  storage_end() const
608  {
609  return (data->end());
610  }
611 
612  boost::identity_property_map&
614  {
615  return (index);
616  }
617 
618  const boost::identity_property_map&
620  {
621  return (index);
622  }
623 
624  reference
625  operator[](const key_type& v) const
626  {
627  return ((*data)[get(index, v)]);
628  }
629 
630  private:
632  boost::identity_property_map index;
633  };
634 
635 } // namespace pcl::graph
636 
637 #define PCG_PARAMS typename P, typename OEL, typename D, typename VP, typename EP, typename EL
638 #define PCG pcl::graph::point_cloud_graph<P, OEL, D, VP, EP, EL>
639 
640 namespace boost
641 {
642 
643  /* In `point_cloud_graph` we use a special kind of property map to access the
644  * vertex bundle. This specialization of the `property_map` traits struct
645  * makes sure that everyone (especially `get` function defined in
646  * 'boost/graph/detail/adjacency_list.hpp' which does the job of creating
647  * these maps) is aware of this fact. */
648 
649  template <PCG_PARAMS>
650  struct property_map<PCG, vertex_bundle_t>
651  {
653  typedef type const_type;
654  };
655 
656  /* The following two functions (source, target) are required by the
657  * EdgeListGraph concept. Implementation is the same as in `adjacency_list`. */
658 
659  template <typename Directed, typename Vertex, PCG_PARAMS>
660  inline Vertex
661  source(const detail::edge_base<Directed, Vertex>& e, const PCG&)
662  {
663  return e.m_source;
664  }
665 
666  template <typename Directed, typename Vertex, PCG_PARAMS>
667  inline Vertex
668  target(const detail::edge_base<Directed, Vertex>& e, const PCG&)
669  {
670  return e.m_target;
671  }
672 
673  template <PCG_PARAMS>
674  struct graph_mutability_traits<PCG>
675  {
676  typedef mutable_property_graph_tag category;
677  };
678 
679 } // namespace boost
680 
681 namespace pcl::graph
682 {
683 
684  /** Retrieve the point cloud stored in a point cloud graph.
685  *
686  * \author Sergey Alexandrov
687  * \ingroup graph */
688  template <PCG_PARAMS>
689  inline typename pcl::PointCloud<P>::Ptr
691  {
692  return (g.m_point_cloud);
693  }
694 
695  /** Retrieve the point cloud stored in a point cloud graph (const version).
696  *
697  * \author Sergey Alexandrov
698  * \ingroup graph */
699  template <PCG_PARAMS>
700  inline typename pcl::PointCloud<P>::ConstPtr
701  point_cloud(const PCG& g)
702  {
703  return (g.m_point_cloud);
704  }
705 
706  /** Retrieve the indices of the points of the point cloud stored in a point
707  * cloud graph that actually belong to the graph.
708  *
709  * Since point_cloud_graph always contain all the points that it stores,
710  * this function always returns a vector with indices from \c 0 to \c N-1,
711  * where \c N is the number of vertices (points) in the graph.
712  *
713  * \author Sergey Alexandrov
714  * \ingroup graph */
715  template <PCG_PARAMS>
716  inline pcl::PointIndices::Ptr
717  indices(const PCG& g)
718  {
719  pcl::PointIndices::Ptr indices(new pcl::PointIndices);
720  indices->indices.resize(g.m_point_cloud->size());
721  for (size_t i = 0; i < g.m_point_cloud->size(); ++i)
722  {
723  indices->indices[i] = i;
724  }
725  return (indices);
726  }
727 
728  /** Retrieve the point cloud stored in a point cloud (sub)graph.
729  *
730  * The behavior of this function will be different for root and child
731  * subgraphs. A root subgraph will return the point cloud stored in it,
732  * whereas a child subgraph will return the point cloud stored in its
733  * parent graph.
734  *
735  * \author Sergey Alexandrov
736  * \ingroup graph */
737  template <PCG_PARAMS>
738  inline typename pcl::PointCloud<P>::Ptr
739  point_cloud(boost::subgraph<PCG>& g)
740  {
741  return (g.root().m_graph.m_point_cloud);
742  }
743 
744  /** Retrieve the point cloud stored in a point cloud (sub)graph (const
745  * version).
746  *
747  * \author Sergey Alexandrov
748  * \ingroup graph */
749  template <PCG_PARAMS>
750  inline typename pcl::PointCloud<P>::ConstPtr
751  point_cloud(const boost::subgraph<PCG>& g)
752  {
753  return (g.root().m_graph.m_point_cloud);
754  }
755 
756  /** Retrieve the indices of the points of the point cloud stored in a point
757  * cloud (sub)graph that actually belong to the (sub)graph.
758  *
759  * A child subgraph contains only a subset of the vertices of the parent
760  * graph. This function provides a vector of indices of the vertices of the
761  * parent graph that belong to this subgraph as well. These vertex indices
762  * are valid point indices for the point cloud stored in the parent graph.
763  *
764  * \author Sergey Alexandrov
765  * \ingroup graph */
766  template <PCG_PARAMS>
767  inline pcl::PointIndices::Ptr
768  indices(const boost::subgraph<PCG>& g)
769  {
770  if (g.is_root())
771  {
772  return indices(g.m_graph);
773  }
774  pcl::PointIndices::Ptr indices(new pcl::PointIndices);
775  indices->indices.resize(boost::num_vertices(g));
776  for (size_t i = 0; i < boost::num_vertices(g); ++i)
777  {
778  indices->indices[i] = g.m_global_vertex[i];
779  }
780  return (indices);
781  }
782 
783 } // namespace pcl::graph
784 #endif /* PCL_GRAPH_POINT_CLOUD_GRAPH_H */
boost::property_map< PCG, vertex_bundle_t >::const_type
type const_type
Definition: point_cloud_graph.h:653
pcl::graph::point_cloud_property_map::get_index_map
boost::identity_property_map & get_index_map()
Definition: point_cloud_graph.h:613
pcl::graph::point_cloud_property_map::operator[]
reference operator[](const key_type &v) const
Definition: point_cloud_graph.h:625
pcl::graph::point_cloud_graph::vertex_descriptor
Base::vertex_descriptor vertex_descriptor
Definition: point_cloud_graph.h:359
pcl::graph::point_cloud_graph::operator[]
const vertex_bundled & operator[](vertex_descriptor v) const
Definition: point_cloud_graph.h:514
boost::property_map< PCG, vertex_bundle_t >::type
pcl::graph::point_cloud_property_map< PCG > type
Definition: point_cloud_graph.h:652
PCG
#define PCG
Definition: point_cloud_graph.h:638
pcl::graph::point_cloud_graph::out_edge_list_selector
OutEdgeListS out_edge_list_selector
Definition: point_cloud_graph.h:361
pcl::graph::point_cloud_graph::edge_bundled
Base::edge_bundled edge_bundled
Definition: point_cloud_graph.h:353
pcl::graph::point_cloud_graph::vertices_size_type
Base::vertices_size_type vertices_size_type
Definition: point_cloud_graph.h:356
pcl::graph::point_cloud_property_map::const_iterator
point_cloud_graph_traits< Graph >::point_cloud_type::const_iterator const_iterator
Definition: point_cloud_graph.h:578
pcl::graph::point_cloud_graph::operator=
point_cloud_graph & operator=(const point_cloud_graph &x)
Assignment operator.
Definition: point_cloud_graph.h:418
boost::target
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:668
pcl::graph::point_cloud_graph::graph_property_type
pcl::PointCloud< PointT >::Ptr graph_property_type
Definition: point_cloud_graph.h:348
pcl::graph::point_cloud_property_map::storage_begin
const_iterator storage_begin() const
Definition: point_cloud_graph.h:601
boost
Definition: ApplicationOptions.h:37
pcl::graph::point_cloud_graph::m_point_cloud
point_cloud_ptr m_point_cloud
Storage for the internal cloud data.
Definition: point_cloud_graph.h:536
pcl::graph::point_cloud_graph::operator[]
edge_bundled & operator[](edge_descriptor e)
Definition: point_cloud_graph.h:520
pcl::graph::point_cloud_graph::removing_vertex
void removing_vertex(vertex_descriptor vertex)
Definition: point_cloud_graph.h:474
pcl::graph::point_cloud_graph_traits::point_cloud_type
Graph::point_cloud_type point_cloud_type
The type of PCL point cloud the graph can be viewed as.
Definition: point_cloud_graph.h:546
pcl::graph::point_cloud_graph::graph_bundled
pcl::PointCloud< PointT >::Ptr graph_bundled
Definition: point_cloud_graph.h:349
pcl::graph::point_cloud_graph::edge_property_type
Base::edge_property_type edge_property_type
Definition: point_cloud_graph.h:352
pcl::graph::point_cloud_property_map::storage_end
iterator storage_end()
Definition: point_cloud_graph.h:595
armarx::navigation::util::geometry::point_type
boost::geometry::model::d2::point_xy< float > point_type
Definition: geometry.h:35
pcl::graph::point_cloud_graph::point_cloud_const_ptr
point_cloud_type::ConstPtr point_cloud_const_ptr
Definition: point_cloud_graph.h:370
pcl::graph
Definition: common.h:45
pcl::graph::point_cloud_graph::point_cloud_graph
point_cloud_graph(const point_cloud_ptr &p=point_cloud_ptr(new point_cloud_type))
Construct a graph based on existing point cloud.
Definition: point_cloud_graph.h:379
boost::graph_mutability_traits< PCG >::category
mutable_property_graph_tag category
Definition: point_cloud_graph.h:676
pcl::graph::point_cloud_graph::vertex_bundled
PointT vertex_bundled
Definition: point_cloud_graph.h:351
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:855
pcl::graph::indices
pcl::PointIndices::Ptr indices(const PCG &g)
Retrieve the indices of the points of the point cloud stored in a point cloud graph that actually bel...
Definition: point_cloud_graph.h:717
pcl::graph::point_cloud_graph_traits::point_cloud_ptr
Graph::point_cloud_ptr point_cloud_ptr
The type of a shared pointer to PCL point cloud the graph can be viewed as.
Definition: point_cloud_graph.h:549
pcl::graph::point_cloud_graph::added_vertex
void added_vertex(vertex_descriptor)
Definition: point_cloud_graph.h:465
pcl::graph::point_cloud_graph::degree_size_type
Base::degree_size_type degree_size_type
Definition: point_cloud_graph.h:358
pcl::graph::point_cloud_graph::point_type
PointT point_type
Type of PCL points bundled in graph vertices.
Definition: point_cloud_graph.h:367
pcl::graph::point_cloud_property_map::reference
std::iterator_traits< iterator >::reference reference
Definition: point_cloud_graph.h:579
pcl::graph::point_cloud_property_map::value_type
point_cloud_graph_traits< Graph >::point_type value_type
Definition: point_cloud_graph.h:580
armarx::PointT
pcl::PointXYZRGBL PointT
Definition: Common.h:30
pcl::graph::point_cloud_property_map::category
boost::lvalue_property_map_tag category
Definition: point_cloud_graph.h:581
pcl::graph::point_cloud_graph::vertex_property_type
Base::vertex_property_type vertex_property_type
Definition: point_cloud_graph.h:350
pcl::graph::point_cloud
pcl::PointCloud< P >::Ptr point_cloud(PCG &g)
Retrieve the point cloud stored in a point cloud graph.
Definition: point_cloud_graph.h:690
armarx::Graph
boost::subgraph< CloudGraph > Graph
Definition: Common.h:58
pcl::graph::point_cloud_property_map::key_type
boost::property_traits< boost::identity_property_map >::key_type key_type
Definition: point_cloud_graph.h:575
pcl::graph::point_cloud_graph::removing_vertex
void removing_vertex(vertex_descriptor vertex, T)
Definition: point_cloud_graph.h:490
boost::source
Vertex source(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:661
pcl::graph::point_cloud_graph_traits::point_type
Graph::point_type point_type
The type of PCL points bundled in vertices.
Definition: point_cloud_graph.h:544
pcl::graph::point_cloud_graph::edge_list_selector
EdgeListS edge_list_selector
Definition: point_cloud_graph.h:364
pcl::graph::point_cloud_graph::point_cloud_graph
point_cloud_graph(vertices_size_type num_vertices, const point_cloud_ptr &=point_cloud_ptr(new point_cloud_type))
Construct a graph with a given number of vertices.
Definition: point_cloud_graph.h:389
pcl::graph::point_cloud_graph_traits::point_cloud_const_ptr
Graph::point_cloud_const_ptr point_cloud_const_ptr
The type of a shared pointer to const PCL point cloud the graph can be viewed as.
Definition: point_cloud_graph.h:552
pcl::graph::point_cloud_graph
Definition: point_cloud_graph.h:302
pcl::graph::point_cloud_property_map::storage_begin
iterator storage_begin()
Definition: point_cloud_graph.h:589
pcl::graph::point_cloud_graph::clear
void clear()
Remove all of the edges and vertices from the graph.
Definition: point_cloud_graph.h:441
pcl::graph::point_cloud_graph::operator[]
vertex_bundled & operator[](vertex_descriptor v)
Definition: point_cloud_graph.h:508
armarx::ctrlutil::v
double v(double t, double v0, double a0, double j)
Definition: CtrlUtil.h:39
pcl::graph::point_cloud_property_map::storage_end
const_iterator storage_end() const
Definition: point_cloud_graph.h:607
pcl::graph::point_cloud_graph::point_cloud_graph
point_cloud_graph(const point_cloud_graph &x)
Copy constructor.
Definition: point_cloud_graph.h:407
pcl::graph::point_cloud_graph::operator[]
const edge_bundled & operator[](edge_descriptor e) const
Definition: point_cloud_graph.h:526
pcl::graph::point_cloud_property_map::get_index_map
const boost::identity_property_map & get_index_map() const
Definition: point_cloud_graph.h:619
pcl::graph::point_cloud_graph::edge_descriptor
Base::edge_descriptor edge_descriptor
Definition: point_cloud_graph.h:360
pcl::graph::point_cloud_graph_traits
Traits struct to access the types associated with point_cloud_graph.
Definition: point_cloud_graph.h:541
pcl::graph::point_cloud_property_map::point_cloud_property_map
point_cloud_property_map(const Graph *g, boost::vertex_bundle_t)
Definition: point_cloud_graph.h:583
pcl::graph::point_cloud_graph::vertex_list_selector
boost::vecS vertex_list_selector
Definition: point_cloud_graph.h:362
pcl::graph::point_cloud_property_map::iterator
point_cloud_graph_traits< Graph >::point_cloud_type::iterator iterator
Definition: point_cloud_graph.h:576
T
float T
Definition: UnscentedKalmanFilterTest.cpp:38
pcl::graph::point_cloud_graph::directed_selector
DirectedS directed_selector
Definition: point_cloud_graph.h:363
pcl::graph::point_cloud_graph::point_cloud_ptr
point_cloud_type::Ptr point_cloud_ptr
Definition: point_cloud_graph.h:369
pcl::graph::point_cloud_graph::point_cloud_type
pcl::PointCloud< PointT > point_cloud_type
Definition: point_cloud_graph.h:368
pcl::graph::point_cloud_graph::stored_vertex
Base::stored_vertex stored_vertex
Definition: point_cloud_graph.h:355
pcl::graph::point_cloud_property_map
This class is to expose the point cloud stored in the point_cloud_graph as a vertex bundle property m...
Definition: point_cloud_graph.h:567
pcl::graph::point_cloud_graph::edges_size_type
Base::edges_size_type edges_size_type
Definition: point_cloud_graph.h:357