Public Types | Public Member Functions | Protected Member Functions | Private Attributes
pcl::registration::GraphHandler< GraphT > Class Template Reference

GraphHandler class is a wrapper for a general SLAM graph The actual graph class must fulfil the following boost::graph concepts: More...

#include <graph_handler.h>

List of all members.

Public Types

typedef boost::shared_ptr
< const GraphHandler< GraphT > > 
ConstPtr
typedef boost::graph_traits
< GraphT >::edge_descriptor 
Edge
typedef boost::shared_ptr
< const GraphT > 
GraphConstPtr
typedef boost::shared_ptr< GraphT > GraphPtr
typedef boost::shared_ptr
< GraphHandler< GraphT > > 
Ptr
typedef boost::graph_traits
< GraphT >::vertex_descriptor 
Vertex

Public Member Functions

template<class MeasurementT >
Edge addGenericConstraint (const MeasurementT &measurement)
 Add a generic constraint created according to the given measurement.
template<class EstimateT >
Vertex addGenericVertex (const EstimateT &estimate)
 Add a new generic vertex created according to the given estimate.
template<class PointT >
Vertex addPointCloud (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const Eigen::Matrix4f &pose)
 Add a new point cloud to the graph and return the new vertex.
template<class InformationT >
Edge addPoseConstraint (const Vertex &v_start, const Vertex &v_end, const Eigen::Matrix4f &relative_transformation, const InformationT &information_matrix)
 Add a new constraint between two poses.
void clear ()
 Clear the graph.
GraphConstPtr getGraph () const
 Get a pointer to the BGL graph.
GraphPtr getGraph ()
 Get a pointer to the BGL graph.
 GraphHandler ()
 Empty constructor.
void removeConstraint (const Edge &e)
 Remove a constraint from the graph.
void removeVertex (const Vertex &v)
 Remove a vertex from the graph.
 ~GraphHandler ()
 Destructor.

Protected Member Functions

bool deinit ()
 This method is called when graph_impl_ is going to be destroyed.
bool init ()
 This method is called right after the creation of graph_impl_.

Private Attributes

GraphPtr graph_impl_

Detailed Description

template<typename GraphT>
class pcl::registration::GraphHandler< GraphT >

GraphHandler class is a wrapper for a general SLAM graph The actual graph class must fulfil the following boost::graph concepts:

Other valid expressions:

If a specific graph implementation needs initialization and/or finalization, specialize the protected methods init() and deinit() for your graph type

Author:
Nicola Fioraio

Definition at line 82 of file graph_handler.h.


Member Typedef Documentation

template<typename GraphT>
typedef boost::shared_ptr<const GraphHandler<GraphT> > pcl::registration::GraphHandler< GraphT >::ConstPtr

Definition at line 86 of file graph_handler.h.

template<typename GraphT>
typedef boost::graph_traits<GraphT>::edge_descriptor pcl::registration::GraphHandler< GraphT >::Edge

Definition at line 91 of file graph_handler.h.

template<typename GraphT>
typedef boost::shared_ptr<const GraphT> pcl::registration::GraphHandler< GraphT >::GraphConstPtr

Definition at line 88 of file graph_handler.h.

template<typename GraphT>
typedef boost::shared_ptr<GraphT> pcl::registration::GraphHandler< GraphT >::GraphPtr

Definition at line 87 of file graph_handler.h.

template<typename GraphT>
typedef boost::shared_ptr<GraphHandler<GraphT> > pcl::registration::GraphHandler< GraphT >::Ptr

Definition at line 85 of file graph_handler.h.

template<typename GraphT>
typedef boost::graph_traits<GraphT>::vertex_descriptor pcl::registration::GraphHandler< GraphT >::Vertex

Definition at line 90 of file graph_handler.h.


Constructor & Destructor Documentation

template<typename GraphT>
pcl::registration::GraphHandler< GraphT >::GraphHandler ( ) [inline]

Empty constructor.

Definition at line 94 of file graph_handler.h.

template<typename GraphT>
pcl::registration::GraphHandler< GraphT >::~GraphHandler ( ) [inline]

Destructor.

Definition at line 101 of file graph_handler.h.


Member Function Documentation

template<typename GraphT>
template<class MeasurementT >
Edge pcl::registration::GraphHandler< GraphT >::addGenericConstraint ( const MeasurementT &  measurement) [inline]

Add a generic constraint created according to the given measurement.

Parameters:
measurementthe measurement
Returns:
a reference to the new edge

Definition at line 172 of file graph_handler.h.

template<typename GraphT>
template<class EstimateT >
Vertex pcl::registration::GraphHandler< GraphT >::addGenericVertex ( const EstimateT &  estimate) [inline]

Add a new generic vertex created according to the given estimate.

Parameters:
estimatethe parameters' estimate
Returns:
a reference to the new vertex

Definition at line 146 of file graph_handler.h.

template<typename GraphT>
template<class PointT >
Vertex pcl::registration::GraphHandler< GraphT >::addPointCloud ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const Eigen::Matrix4f &  pose 
) [inline]

Add a new point cloud to the graph and return the new vertex.

Parameters:
cloudthe new point cloud
posethe pose estimate
Returns:
a reference to the new vertex

Definition at line 136 of file graph_handler.h.

template<typename GraphT>
template<class InformationT >
Edge pcl::registration::GraphHandler< GraphT >::addPoseConstraint ( const Vertex v_start,
const Vertex v_end,
const Eigen::Matrix4f &  relative_transformation,
const InformationT &  information_matrix 
) [inline]

Add a new constraint between two poses.

Parameters:
v_startthe first pose
v_endthe second pose
relative_transformationthe transformation from v_start to v_end
information_matrixthe uncertainty
Returns:
a reference to the new edge

Definition at line 159 of file graph_handler.h.

template<typename GraphT>
void pcl::registration::GraphHandler< GraphT >::clear ( ) [inline]

Clear the graph.

Definition at line 108 of file graph_handler.h.

template<typename GraphT>
bool pcl::registration::GraphHandler< GraphT >::deinit ( ) [inline, protected]

This method is called when graph_impl_ is going to be destroyed.

Definition at line 205 of file graph_handler.h.

template<typename GraphT>
GraphConstPtr pcl::registration::GraphHandler< GraphT >::getGraph ( ) const [inline]

Get a pointer to the BGL graph.

Definition at line 118 of file graph_handler.h.

template<typename GraphT>
GraphPtr pcl::registration::GraphHandler< GraphT >::getGraph ( ) [inline]

Get a pointer to the BGL graph.

Definition at line 125 of file graph_handler.h.

template<typename GraphT>
bool pcl::registration::GraphHandler< GraphT >::init ( ) [inline, protected]

This method is called right after the creation of graph_impl_.

Definition at line 198 of file graph_handler.h.

template<typename GraphT>
void pcl::registration::GraphHandler< GraphT >::removeConstraint ( const Edge e) [inline]

Remove a constraint from the graph.

Parameters:
ethe edge

Definition at line 190 of file graph_handler.h.

template<typename GraphT>
void pcl::registration::GraphHandler< GraphT >::removeVertex ( const Vertex v) [inline]

Remove a vertex from the graph.

Parameters:
vthe vertex

Definition at line 181 of file graph_handler.h.


Member Data Documentation

template<typename GraphT>
GraphPtr pcl::registration::GraphHandler< GraphT >::graph_impl_ [private]

Definition at line 211 of file graph_handler.h.


The documentation for this class was generated from the following file:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:46:33