Classes | Public Types | Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes
pcl::registration::ELCH< PointT > Class Template Reference

ELCH (Explicit Loop Closing Heuristic) class More...

#include <elch.h>

Inheritance diagram for pcl::registration::ELCH< PointT >:
Inheritance graph
[legend]

List of all members.

Classes

struct  Vertex

Public Types

typedef boost::shared_ptr
< const ELCH< PointT > > 
ConstPtr
typedef boost::adjacency_list
< boost::listS, boost::vecS,
boost::undirectedS, Vertex,
boost::no_property > 
LoopGraph
 graph structure to hold the SLAM graph
typedef boost::shared_ptr
< LoopGraph
LoopGraphPtr
typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr
typedef boost::shared_ptr
< ELCH< PointT > > 
Ptr
typedef pcl::Registration
< PointT, PointT
Registration
typedef Registration::ConstPtr RegistrationConstPtr
typedef Registration::Ptr RegistrationPtr

Public Member Functions

void addPointCloud (PointCloudPtr cloud)
 Add a new point cloud to the internal graph.
void compute ()
 Computes now poses for all point clouds by closing the loop between start and end point cloud. This will transform all given point clouds for now!
 ELCH ()
 Empty constructor.
boost::graph_traits< LoopGraph >
::vertex_descriptor 
getLoopEnd ()
 Getter for the last scan of a loop.
LoopGraphPtr getLoopGraph ()
 Getter for the internal graph.
boost::graph_traits< LoopGraph >
::vertex_descriptor 
getLoopStart ()
 Getter for the first scan of a loop.
Eigen::Matrix4f getLoopTransform ()
 Getter for the transformation between the first and the last scan.
RegistrationPtr getReg ()
 Getter for the registration algorithm.
void setLoopEnd (const typename boost::graph_traits< LoopGraph >::vertex_descriptor &loop_end)
 Setter for the last scan of a loop.
void setLoopGraph (LoopGraphPtr loop_graph)
 Setter for a new internal graph.
void setLoopStart (const typename boost::graph_traits< LoopGraph >::vertex_descriptor &loop_start)
 Setter for the first scan of a loop.
void setLoopTransform (const Eigen::Matrix4f &loop_transform)
 Setter for the transformation between the first and the last scan.
void setReg (RegistrationPtr reg)
 Setter for the registration algorithm.

Protected Member Functions

virtual bool initCompute ()
 This method should get called before starting the actual computation.

Private Types

typedef boost::adjacency_list
< boost::listS, boost::vecS,
boost::undirectedS,
boost::no_property,
boost::property
< boost::edge_weight_t, double > > 
LOAGraph
 graph structure for the internal optimization graph

Private Member Functions

void loopOptimizerAlgorithm (LOAGraph &g, double *weights)

Private Attributes

bool compute_loop_
boost::graph_traits< LoopGraph >
::vertex_descriptor 
loop_end_
 The last scan of the loop.
LoopGraphPtr loop_graph_
 The internal loop graph.
boost::graph_traits< LoopGraph >
::vertex_descriptor 
loop_start_
 The first scan of the loop.
Eigen::Matrix4f loop_transform_
 The transformation between that start and end of the loop.
RegistrationPtr reg_
 The registration object used to close the loop.
boost::graph_traits< LoopGraph >
::vertex_descriptor 
vd_
 previously added node in the loop_graph_.

Detailed Description

template<typename PointT>
class pcl::registration::ELCH< PointT >

ELCH (Explicit Loop Closing Heuristic) class

Author:
Jochen Sprickerhof

Definition at line 64 of file elch.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr< const ELCH<PointT> > pcl::registration::ELCH< PointT >::ConstPtr

Definition at line 68 of file elch.h.

template<typename PointT>
typedef boost::adjacency_list< boost::listS, boost::vecS, boost::undirectedS, boost::no_property, boost::property< boost::edge_weight_t, double > > pcl::registration::ELCH< PointT >::LOAGraph [private]

graph structure for the internal optimization graph

Definition at line 218 of file elch.h.

template<typename PointT>
typedef boost::adjacency_list< boost::listS, boost::vecS, boost::undirectedS, Vertex, boost::no_property> pcl::registration::ELCH< PointT >::LoopGraph

graph structure to hold the SLAM graph

Definition at line 85 of file elch.h.

template<typename PointT>
typedef boost::shared_ptr< LoopGraph > pcl::registration::ELCH< PointT >::LoopGraphPtr

Definition at line 87 of file elch.h.

template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::registration::ELCH< PointT >::PointCloud

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 70 of file elch.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 72 of file elch.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::registration::ELCH< PointT >::PointCloudPtr

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 71 of file elch.h.

template<typename PointT>
typedef boost::shared_ptr< ELCH<PointT> > pcl::registration::ELCH< PointT >::Ptr

Definition at line 67 of file elch.h.

template<typename PointT>
typedef pcl::Registration<PointT, PointT> pcl::registration::ELCH< PointT >::Registration

Definition at line 89 of file elch.h.

Definition at line 91 of file elch.h.

template<typename PointT>
typedef Registration::Ptr pcl::registration::ELCH< PointT >::RegistrationPtr

Definition at line 90 of file elch.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::registration::ELCH< PointT >::ELCH ( ) [inline]

Empty constructor.

Definition at line 94 of file elch.h.


Member Function Documentation

template<typename PointT>
void pcl::registration::ELCH< PointT >::addPointCloud ( PointCloudPtr  cloud) [inline]

Add a new point cloud to the internal graph.

Parameters:
[in]cloudthe new point cloud

Definition at line 108 of file elch.h.

template<typename PointT >
void pcl::registration::ELCH< PointT >::compute ( )

Computes now poses for all point clouds by closing the loop between start and end point cloud. This will transform all given point clouds for now!

Definition at line 218 of file elch.hpp.

template<typename PointT>
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::getLoopEnd ( ) [inline]

Getter for the last scan of a loop.

Definition at line 151 of file elch.h.

template<typename PointT>
LoopGraphPtr pcl::registration::ELCH< PointT >::getLoopGraph ( ) [inline]

Getter for the internal graph.

Definition at line 119 of file elch.h.

template<typename PointT>
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::getLoopStart ( ) [inline]

Getter for the first scan of a loop.

Definition at line 135 of file elch.h.

template<typename PointT>
Eigen::Matrix4f pcl::registration::ELCH< PointT >::getLoopTransform ( ) [inline]

Getter for the transformation between the first and the last scan.

Definition at line 183 of file elch.h.

template<typename PointT>
RegistrationPtr pcl::registration::ELCH< PointT >::getReg ( ) [inline]

Getter for the registration algorithm.

Definition at line 167 of file elch.h.

template<typename PointT >
bool pcl::registration::ELCH< PointT >::initCompute ( ) [protected, virtual]

This method should get called before starting the actual computation.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 158 of file elch.hpp.

template<typename PointT >
void pcl::registration::ELCH< PointT >::loopOptimizerAlgorithm ( LOAGraph g,
double *  weights 
) [private]

graph balancer algorithm computes the weights

Parameters:
[in]gthe graph
[in]findex of the first node
[in]lindex of the last node
[out]weightsarray for the weights

Definition at line 57 of file elch.hpp.

template<typename PointT>
void pcl::registration::ELCH< PointT >::setLoopEnd ( const typename boost::graph_traits< LoopGraph >::vertex_descriptor &  loop_end) [inline]

Setter for the last scan of a loop.

Parameters:
[in]loop_endthe scan that ends the loop

Definition at line 160 of file elch.h.

template<typename PointT>
void pcl::registration::ELCH< PointT >::setLoopGraph ( LoopGraphPtr  loop_graph) [inline]

Setter for a new internal graph.

Parameters:
[in]loop_graphthe new graph

Definition at line 128 of file elch.h.

template<typename PointT>
void pcl::registration::ELCH< PointT >::setLoopStart ( const typename boost::graph_traits< LoopGraph >::vertex_descriptor &  loop_start) [inline]

Setter for the first scan of a loop.

Parameters:
[in]loop_startthe scan that starts the loop

Definition at line 144 of file elch.h.

template<typename PointT>
void pcl::registration::ELCH< PointT >::setLoopTransform ( const Eigen::Matrix4f &  loop_transform) [inline]

Setter for the transformation between the first and the last scan.

Parameters:
[in]loop_transformthe transformation between the first and the last scan

Definition at line 192 of file elch.h.

template<typename PointT>
void pcl::registration::ELCH< PointT >::setReg ( RegistrationPtr  reg) [inline]

Setter for the registration algorithm.

Parameters:
[in]regthe registration algorithm used to compute the transformation between the start and the end of the loop

Definition at line 176 of file elch.h.


Member Data Documentation

template<typename PointT>
bool pcl::registration::ELCH< PointT >::compute_loop_ [private]

Definition at line 244 of file elch.h.

template<typename PointT>
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::loop_end_ [private]

The last scan of the loop.

Definition at line 237 of file elch.h.

template<typename PointT>
LoopGraphPtr pcl::registration::ELCH< PointT >::loop_graph_ [private]

The internal loop graph.

Definition at line 231 of file elch.h.

template<typename PointT>
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::loop_start_ [private]

The first scan of the loop.

Definition at line 234 of file elch.h.

template<typename PointT>
Eigen::Matrix4f pcl::registration::ELCH< PointT >::loop_transform_ [private]

The transformation between that start and end of the loop.

Definition at line 243 of file elch.h.

template<typename PointT>
RegistrationPtr pcl::registration::ELCH< PointT >::reg_ [private]

The registration object used to close the loop.

Definition at line 240 of file elch.h.

template<typename PointT>
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::vd_ [private]

previously added node in the loop_graph_.

Definition at line 247 of file elch.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:23