ELCH (Explicit Loop Closing Heuristic) class More...
#include <elch.h>
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< PointT > | PointCloud |
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_. |
ELCH (Explicit Loop Closing Heuristic) class
typedef boost::shared_ptr< const ELCH<PointT> > pcl::registration::ELCH< PointT >::ConstPtr |
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] |
typedef boost::adjacency_list< boost::listS, boost::vecS, boost::undirectedS, Vertex, boost::no_property> pcl::registration::ELCH< PointT >::LoopGraph |
typedef boost::shared_ptr< LoopGraph > pcl::registration::ELCH< PointT >::LoopGraphPtr |
typedef pcl::PointCloud<PointT> pcl::registration::ELCH< PointT >::PointCloud |
Reimplemented from pcl::PCLBase< PointT >.
typedef PointCloud::ConstPtr pcl::registration::ELCH< PointT >::PointCloudConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
typedef PointCloud::Ptr pcl::registration::ELCH< PointT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointT >.
typedef boost::shared_ptr< ELCH<PointT> > pcl::registration::ELCH< PointT >::Ptr |
typedef pcl::Registration<PointT, PointT> pcl::registration::ELCH< PointT >::Registration |
typedef Registration::ConstPtr pcl::registration::ELCH< PointT >::RegistrationConstPtr |
typedef Registration::Ptr pcl::registration::ELCH< PointT >::RegistrationPtr |
pcl::registration::ELCH< PointT >::ELCH | ( | ) | [inline] |
void pcl::registration::ELCH< PointT >::addPointCloud | ( | PointCloudPtr | cloud | ) | [inline] |
void pcl::registration::ELCH< PointT >::compute | ( | ) |
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::getLoopEnd | ( | ) | [inline] |
LoopGraphPtr pcl::registration::ELCH< PointT >::getLoopGraph | ( | ) | [inline] |
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::getLoopStart | ( | ) | [inline] |
Eigen::Matrix4f pcl::registration::ELCH< PointT >::getLoopTransform | ( | ) | [inline] |
RegistrationPtr pcl::registration::ELCH< PointT >::getReg | ( | ) | [inline] |
bool pcl::registration::ELCH< PointT >::initCompute | ( | ) | [protected, virtual] |
This method should get called before starting the actual computation.
Reimplemented from pcl::PCLBase< PointT >.
void pcl::registration::ELCH< PointT >::loopOptimizerAlgorithm | ( | LOAGraph & | g, |
double * | weights | ||
) | [private] |
void pcl::registration::ELCH< PointT >::setLoopEnd | ( | const typename boost::graph_traits< LoopGraph >::vertex_descriptor & | loop_end | ) | [inline] |
void pcl::registration::ELCH< PointT >::setLoopGraph | ( | LoopGraphPtr | loop_graph | ) | [inline] |
void pcl::registration::ELCH< PointT >::setLoopStart | ( | const typename boost::graph_traits< LoopGraph >::vertex_descriptor & | loop_start | ) | [inline] |
void pcl::registration::ELCH< PointT >::setLoopTransform | ( | const Eigen::Matrix4f & | loop_transform | ) | [inline] |
void pcl::registration::ELCH< PointT >::setReg | ( | RegistrationPtr | reg | ) | [inline] |
bool pcl::registration::ELCH< PointT >::compute_loop_ [private] |
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::loop_end_ [private] |
LoopGraphPtr pcl::registration::ELCH< PointT >::loop_graph_ [private] |
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::loop_start_ [private] |
Eigen::Matrix4f pcl::registration::ELCH< PointT >::loop_transform_ [private] |
RegistrationPtr pcl::registration::ELCH< PointT >::reg_ [private] |
boost::graph_traits<LoopGraph>::vertex_descriptor pcl::registration::ELCH< PointT >::vd_ [private] |