point_cloud_graph< PointT, OutEdgeListS, DirectedS, VertexProperty, EdgeProperty, EdgeListS > Class Template Reference

#include <VisionX/libraries/PointCloudGraph/point_cloud_graph.h>

+ Inheritance diagram for point_cloud_graph< PointT, OutEdgeListS, DirectedS, VertexProperty, EdgeProperty, EdgeListS >:

Public Types

typedef Base::degree_size_type degree_size_type
 
typedef DirectedS directed_selector
 
typedef Base::edge_bundled edge_bundled
 
typedef Base::edge_descriptor edge_descriptor
 
typedef EdgeListS edge_list_selector
 
typedef Base::edge_property_type edge_property_type
 
typedef Base::edges_size_type edges_size_type
 
typedef pcl::PointCloud< PointT >::Ptr graph_bundled
 
typedef pcl::PointCloud< PointT >::Ptr graph_property_type
 
typedef OutEdgeListS out_edge_list_selector
 
typedef point_cloud_type::ConstPtr point_cloud_const_ptr
 
typedef point_cloud_type::Ptr point_cloud_ptr
 
typedef pcl::PointCloud< PointT > point_cloud_type
 
typedef PointT point_type
 Type of PCL points bundled in graph vertices. More...
 
typedef Base::stored_vertex stored_vertex
 
typedef PointT vertex_bundled
 
typedef Base::vertex_descriptor vertex_descriptor
 
typedef boost::vecS vertex_list_selector
 
typedef Base::vertex_property_type vertex_property_type
 
typedef Base::vertices_size_type vertices_size_type
 

Public Member Functions

void added_vertex (vertex_descriptor)
 
void clear ()
 Remove all of the edges and vertices from the graph. More...
 
point_cloud_graphoperator= (const point_cloud_graph &x)
 Assignment operator. More...
 
 point_cloud_graph (const point_cloud_graph &x)
 Copy constructor. More...
 
 point_cloud_graph (const point_cloud_ptr &p=point_cloud_ptr(new point_cloud_type))
 Construct a graph based on existing point cloud. More...
 
 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. More...
 
void removing_vertex (vertex_descriptor vertex)
 
template<typename T >
void removing_vertex (vertex_descriptor vertex, T)
 
Access to bundled vertex/edge properties.

The operators[]'s in this group may be used to access the data bundled in vertices and edges of the graph.

Implementation was directly copied from adjacency_list.

Note that there is no operator access to the GraphProperty as there is no such thing in point_cloud_graph (see the corresponding section in the class description for more information).

vertex_bundledoperator[] (vertex_descriptor v)
 
const vertex_bundledoperator[] (vertex_descriptor v) const
 
edge_bundledoperator[] (edge_descriptor e)
 
const edge_bundledoperator[] (edge_descriptor e) const
 

Public Attributes

point_cloud_ptr m_point_cloud
 Storage for the internal cloud data. More...
 

Detailed Description

template<typename PointT, typename OutEdgeListS = boost::vecS, typename DirectedS = boost::undirectedS, typename VertexProperty = boost::no_property, typename EdgeProperty = boost::no_property, typename EdgeListS = boost::listS>
class pcl::graph::point_cloud_graph< PointT, OutEdgeListS, DirectedS, VertexProperty, EdgeProperty, EdgeListS >

A sibling of boost::adjacency_list with PCL points bundled in vertices and copy-free access to them as a PCL point cloud.

Motivation

Boost Graph Library has a concept of bundled properties, i.e. custom data types that may be stored in graph vertices and conveniently accessed with operator[]. In the context of PCL it makes a lot of sense to have PCL points bundled in graph vertices. The following specialization of boost::adjacency_list achieves that:

typedef
boost::adjacency_list<
boost::vecS // Represent edge-list with std::vector
, boost::vecS // Represent vertex-list with std::vector
, boost::undirectedS // Undirected graph
, pcl::PointXYZ> // Bundle XYZ points in vertices

A graph-based algorithm can easily access points associated with graph vertices:

Graph graph;
Graph::vertex_descriptor v1 = boost::add_vertex (graph);
Graph::vertex_descriptor v2 = boost::add_vertex (graph);
graph[v1] = pcl::PointXYZ (1, 2, 3);
graph[v2].x = graph[v1].x;

The problem though is that there is no efficient way to put the point cloud data inside the graph and retrieve it back. Suppose that in some application there is a point cloud that should first be filtered using some PCL tools (e.g. pcl::PassThrough filter), then a graph-based algorithm should be applied to it, and finally some more processing using PCL tools is required. The user will need to copy all the points of the original point cloud one-by-one to the graph, run the algorithm, and then copy it back one-by-one again.

Solution

point_cloud_graph resolves this issue by storing bundled points internally as a PCL point cloud. In fact, it stores a shared pointer to a point cloud, so input and output of points is really copy-free. One can create a new graph based on an existing point cloud:

// Create a point cloud with 10 points
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> (10, 1);
// Create a graph based on the cloud
// The graph will have a vertex for each point of the original cloud
assert (10 == boost::num_vertices (graph));
// The points may be accessed using operator[]
graph[1].x = 14;
// The graph shares data with the original point cloud, so modifying a bundled point
// changes the corresponding point in the original cloud
assert (14 == cloud->points[1].x);

The internal point cloud as a whole may be accessed using pcl::graph::point_cloud (Graph& g):

// Perform some graph-based algorithm on point cloud graph
// ...
// Retrieve the bundled data as a point cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr data = pcl::graph::point_cloud (graph);
// Continue to work with the data
pcl::io::savePCDFile ("output.pcd", *data);

Despite the fact that the point data are stored in a PCL point cloud, all the standard BGL features associated with bundled properties are supported, including operator[] and get/put access.

Comparison with <a href="http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/adjacency_list.html" title="adjacency_list">boost::adjacency_list</a>

point_cloud_graph uses the same back-bone implementation as boost::adjacency_list and therefore models the same concepts and may be used everywhere boost::adjacency_list could. In particular, the very same functions could be used to add and remove vertices, access properties, iterate over edges, etc.

As boost::adjacency_list, point_cloud_graph allows to configure itself with a number of template parameters. They are almost the same as in boost::adjacency_list, though there are several differences:

  1. There is a required template parameter PointT which allows the user to select the type of PCL points to be bundled in graph vertices;

    Note that the VertexProperty parameter is still available for the user, so it is possible to additionally attach as many internal properties (such as vertex_color_t) as needed.

  2. The default value for Directed parameter is changed to undirectedS since it is more relevant in the context of point cloud processing;
  3. The vertex-list of the graph is constrained to be std::vector. The user has no control over it as there is no VertexList template parameter;

    The choice of the container for the vertex-list determines the space complexity of the graph structure, as well as the time complexity of the various graph operations, see using boost::adjacency_list for a more detailed discussion. In the case of point_cloud_graph the vertex bundled properties (PCL points) are stored in a PCL point cloud (which has std::vector behind the scenes), so it is only logical to have std::vector as the container type for the vertex-list itself.

  4. There is no GraphProperty template parameter.

    boost::adjacency_list provides a facility to store an arbitrary piece of data associated with the graph as a whole (graph property). While being useful in certain cases, we do not consider this as a vital feature and have sacrificed it to support boost::subgraph. For more details please refer to the section about boost::subgraph below.

Compatibility with <a href="http://www.boost.org/doc/libs/1_55_0/libs/graph/doc/subgraph.html" title="subgraph">boost::subgraph</a>

boost::subgraph provides a convenient mechanism to keep track of a graph and its induced subgraphs. Two issues have been accounted for in order to allow smooth inter-operation between point_cloud_graph and boost::subgraph.

Fixed interface

boost::subgraph is a template class that is wrapped around a graph class rather than a class that inherits from a graph class. Therefore if we want it to be possible to use point_cloud_graph either way (plain or wrapped by boost::subgraph), we have to limit ourselves to the interface exposed by boost::subgraph. In particular, we can not have a PCL point cloud-based constructor for point_cloud_graph because (for apparent reasons) boost::subgraph does not have it. However, the ability to construct a point_cloud_graph from an existing PCL point cloud is an essential feature. We noted that boost::subgraph has a GraphProperty-based constructor that could be re-used as a desired PCL point cloud-based constructor if we alias GraphProperty to PCL point cloud. Thus GraphProperty is used to support internal mechanics of point_cloud_graph and is no longer available to the user.

Lack of internal storage for points

Recall that point_cloud_graph stores the points bundled in its vertices inside a PCL point cloud. It could be conveniently retrieved using pcl::graph::point_cloud (Graph& g) and then used in PCL algorithms. boost::subgraph, however, is designed in such a way that it stores the indices of the vertices and edges of the parent (root) graph that belong to it, but not the data associated with these vertices and edges. In other words, a hierarchy of subgraphs (each of which represents a particular subset of vertices and edges of the root graph) shares common vertex/edge data, and all these data are contained inside the root graph. Consequently, there does not exist a PCL point cloud for each subgraph, but rather a single PCL point cloud for the root graph. This raises a question as of how the pcl::graph::point_cloud (Subgraph& g) function should be implemented.

One option is to construct a new PCL point cloud and fill it with subgraph's points. This, however, would be inconsistent with the behavior of pcl::graph::point_cloud (Graph& g), which simply returns a pointer (meaning it is O(1) operation) that could be used to read and modify the points of the graph. Luckily, working with subsets of point clouds is such a common task in the PCL world that pcl::PCLBase class (which lies at the top of the hierarchy of PCL algorithms) has a means for the user to supply an input point cloud and a vector of indices to which the processing should be limited to. Therefore, we decided that pcl::graph::point_cloud (Subgraph& g) should return the PCL point cloud of its root graph (that is, the whole set of points), and there should be an auxiliary function pcl::graph::indices (Subgraph& g) that returns indices of the points that belong to the subgraph.


Specification

As was noted, point_cloud_graph is virtually the same as boost::adjacency_list. Please refer to its documentation. The specifications below only highlight the differences.

Template parameters

Parameter Description Default
PointT Type of PCL points bundled in graph vertices
OutEdgeList Selector for the container used to represent the edge-list for each of the vertices vecS
Directed Selector to choose whether the graph is directed/undirected/bidirectional undirectedS
VertexProperty For specifying internal vertex property storage (apart from bundled points) no_property
EdgeProperty For specifying internal edge property storage no_property
EdgeList Selector for the container used to represent the edge-list for the graph listS

Model of

PointCloudGraph, VertexAndEdgeListGraph, VertexMutablePropertyGraph, EdgeMutablePropertyGraph, CopyConstructible, Assignable

Probably it could also support Serializable, however this option has not been explored.

Associated types

point_cloud_graph_traits structure provides a means to access the type of points bundled in the point_cloud_graph and, for convenience, the types of PCL point cloud and shared pointer to PCL point cloud of those points.

Non-member functions

typename pcl::PointCloud<PointT>::Ptr
pcl::graph::point_cloud (point_cloud_graph<PointT>& g);

Return a shared pointer to the PCL point cloud stored internally. There are both const and non-const versions.

typename pcl::PointCloud<PointT>::Ptr
pcl::graph::point_cloud (boost::subgraph<point_cloud_graph<PointT>>& g);

Return a shared pointer to the PCL point cloud stored in the root graph. There are both const and non-const versions.

pcl::PointIndices::Ptr
pcl::graph::indices (point_cloud_graph<PointT>& g);

Return a shared pointer to a vector of indices of the points that belong to this graph. Since point_cloud_graph is a complete graph (i.e. it is not a subgraph of some other graph), the returned indices are guaranteed to be [0..N-1], where N is the number of vertices. There are both const- and non-const- versions.

pcl::PointIndices::Ptr
pcl::graph::indices (boost::subgraph<point_cloud_graph<PointT>>& g);

Return a shared pointer to a vector of indices of the points of the root graph that belong to this subgraph. There are both const- and non-const- versions.

Author
Sergey Alexandrov

Definition at line 302 of file point_cloud_graph.h.

Member Typedef Documentation

◆ degree_size_type

typedef Base::degree_size_type degree_size_type

Definition at line 373 of file point_cloud_graph.h.

◆ directed_selector

typedef DirectedS directed_selector

Definition at line 378 of file point_cloud_graph.h.

◆ edge_bundled

typedef Base::edge_bundled edge_bundled

Definition at line 368 of file point_cloud_graph.h.

◆ edge_descriptor

typedef Base::edge_descriptor edge_descriptor

Definition at line 375 of file point_cloud_graph.h.

◆ edge_list_selector

typedef EdgeListS edge_list_selector

Definition at line 379 of file point_cloud_graph.h.

◆ edge_property_type

typedef Base::edge_property_type edge_property_type

Definition at line 367 of file point_cloud_graph.h.

◆ edges_size_type

typedef Base::edges_size_type edges_size_type

Definition at line 372 of file point_cloud_graph.h.

◆ graph_bundled

typedef pcl::PointCloud<PointT>::Ptr graph_bundled

Definition at line 364 of file point_cloud_graph.h.

◆ graph_property_type

typedef pcl::PointCloud<PointT>::Ptr graph_property_type

Definition at line 363 of file point_cloud_graph.h.

◆ out_edge_list_selector

typedef OutEdgeListS out_edge_list_selector

Definition at line 376 of file point_cloud_graph.h.

◆ point_cloud_const_ptr

typedef point_cloud_type::ConstPtr point_cloud_const_ptr

Definition at line 385 of file point_cloud_graph.h.

◆ point_cloud_ptr

typedef point_cloud_type::Ptr point_cloud_ptr

Definition at line 384 of file point_cloud_graph.h.

◆ point_cloud_type

typedef pcl::PointCloud<PointT> point_cloud_type

Definition at line 383 of file point_cloud_graph.h.

◆ point_type

typedef PointT point_type

Type of PCL points bundled in graph vertices.

Definition at line 382 of file point_cloud_graph.h.

◆ stored_vertex

typedef Base::stored_vertex stored_vertex

Definition at line 370 of file point_cloud_graph.h.

◆ vertex_bundled

typedef PointT vertex_bundled

Definition at line 366 of file point_cloud_graph.h.

◆ vertex_descriptor

typedef Base::vertex_descriptor vertex_descriptor

Definition at line 374 of file point_cloud_graph.h.

◆ vertex_list_selector

typedef boost::vecS vertex_list_selector

Definition at line 377 of file point_cloud_graph.h.

◆ vertex_property_type

typedef Base::vertex_property_type vertex_property_type

Definition at line 365 of file point_cloud_graph.h.

◆ vertices_size_type

typedef Base::vertices_size_type vertices_size_type

Definition at line 371 of file point_cloud_graph.h.

Constructor & Destructor Documentation

◆ point_cloud_graph() [1/3]

Construct a graph based on existing point cloud.

The graph will have the same amount of vertices as the input point cloud has. The shared pointer will be stored internally so that the graph retains access to the point data.

If the cloud is not given, then a new empty cloud will be created.

Definition at line 394 of file point_cloud_graph.h.

◆ point_cloud_graph() [2/3]

Construct a graph with a given number of vertices.

This constructor will create a new point cloud to store point data. The second parameter is completely ignored and is provided only to have the same interface as adjacency_list.

Definition at line 405 of file point_cloud_graph.h.

◆ point_cloud_graph() [3/3]

point_cloud_graph ( const point_cloud_graph< PointT, OutEdgeListS, DirectedS, VertexProperty, EdgeProperty, EdgeListS > &  x)
inline

Copy constructor.

Acts just like the standard copy constructor of adjacency_list, i.e. copies vertex and edge set along with associated properties. Note that a deep copy of the underlying point cloud is made.

This constructor reuses assignment operator. An alternative approach would be to use the copy constructor of the base class and then copy over the underlying point cloud, however the problem is that the base constructor uses boost::add_vertex function, which will attempt to push points to the point cloud, although it will not be initialized yet at that point in time (hence segfault).

Definition at line 424 of file point_cloud_graph.h.

Member Function Documentation

◆ added_vertex()

void added_vertex ( vertex_descriptor  )
inline

Definition at line 481 of file point_cloud_graph.h.

◆ clear()

void clear ( )
inline

Remove all of the edges and vertices from the graph.

Note that it wipes the underlying point cloud as well.

Definition at line 457 of file point_cloud_graph.h.

◆ operator=()

point_cloud_graph& operator= ( const point_cloud_graph< PointT, OutEdgeListS, DirectedS, VertexProperty, EdgeProperty, EdgeListS > &  x)
inline

Assignment operator.

Acts just like the standard assignment operator of adjacency_list, i.e. copies vertex and edge set along with associated properties. Note that a deep copy of the underlying point cloud is made.

Definition at line 435 of file point_cloud_graph.h.

◆ operator[]() [1/4]

edge_bundled& operator[] ( edge_descriptor  e)
inline

Definition at line 535 of file point_cloud_graph.h.

◆ operator[]() [2/4]

const edge_bundled& operator[] ( edge_descriptor  e) const
inline

Definition at line 541 of file point_cloud_graph.h.

◆ operator[]() [3/4]

vertex_bundled& operator[] ( vertex_descriptor  v)
inline

Definition at line 523 of file point_cloud_graph.h.

+ Here is the call graph for this function:

◆ operator[]() [4/4]

const vertex_bundled& operator[] ( vertex_descriptor  v) const
inline

Definition at line 529 of file point_cloud_graph.h.

+ Here is the call graph for this function:

◆ removing_vertex() [1/2]

void removing_vertex ( vertex_descriptor  vertex)
inline

Definition at line 490 of file point_cloud_graph.h.

+ Here is the caller graph for this function:

◆ removing_vertex() [2/2]

void removing_vertex ( vertex_descriptor  vertex,
T   
)
inline

Definition at line 505 of file point_cloud_graph.h.

+ Here is the call graph for this function:

Member Data Documentation

◆ m_point_cloud

point_cloud_ptr m_point_cloud

Storage for the internal cloud data.

Definition at line 551 of file point_cloud_graph.h.


The documentation for this class was generated from the following file:
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:737
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
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:710
armarx::Graph
boost::subgraph< CloudGraph > Graph
Definition: Common.h:54
pcl::graph::point_cloud_graph
Definition: point_cloud_graph.h:302