point_cloud_library / 1.12.1 / classpcl_1_1registration_1_1_l_u_m.html /

Globally Consistent Scan Matching based on an algorithm by Lu and Milios. More...

#include <pcl/registration/lum.h>

Classes

struct EdgeProperties
struct VertexProperties

Public Types

using Ptr = shared_ptr< LUM< PointT > >
using ConstPtr = shared_ptr< const LUM< PointT > >
using PointCloud = pcl::PointCloud< PointT >
using PointCloudPtr = typename PointCloud::Ptr
using PointCloudConstPtr = typename PointCloud::ConstPtr
using SLAMGraph = boost::adjacency_list< boost::eigen_vecS, boost::eigen_vecS, boost::bidirectionalS, VertexProperties, EdgeProperties, boost::no_property, boost::eigen_listS >
using SLAMGraphPtr = shared_ptr< SLAMGraph >
using Vertex = typename SLAMGraph::vertex_descriptor
using Edge = typename SLAMGraph::edge_descriptor

Public Member Functions

LUM ()
Empty constructor. More...
void setLoopGraph (const SLAMGraphPtr &slam_graph)
Set the internal SLAM graph structure. More...
SLAMGraphPtr getLoopGraph () const
Get the internal SLAM graph structure. More...
SLAMGraph::vertices_size_type getNumVertices () const
Get the number of vertices in the SLAM graph. More...
void setMaxIterations (int max_iterations)
Set the maximum number of iterations for the compute() method. More...
int getMaxIterations () const
Get the maximum number of iterations for the compute() method. More...
void setConvergenceThreshold (float convergence_threshold)
Set the convergence threshold for the compute() method. More...
float getConvergenceThreshold () const
Get the convergence threshold for the compute() method. More...
Vertex addPointCloud (const PointCloudPtr &cloud, const Eigen::Vector6f &pose=Eigen::Vector6f::Zero())
Add a new point cloud to the SLAM graph. More...
void setPointCloud (const Vertex &vertex, const PointCloudPtr &cloud)
Change a point cloud on one of the SLAM graph's vertices. More...
PointCloudPtr getPointCloud (const Vertex &vertex) const
Return a point cloud from one of the SLAM graph's vertices. More...
void setPose (const Vertex &vertex, const Eigen::Vector6f &pose)
Change a pose estimate on one of the SLAM graph's vertices. More...
Eigen::Vector6f getPose (const Vertex &vertex) const
Return a pose estimate from one of the SLAM graph's vertices. More...
Eigen::Affine3f getTransformation (const Vertex &vertex) const
Return a pose estimate from one of the SLAM graph's vertices as an affine transformation matrix. More...
void setCorrespondences (const Vertex &source_vertex, const Vertex &target_vertex, const pcl::CorrespondencesPtr &corrs)
Add/change a set of correspondences for one of the SLAM graph's edges. More...
pcl::CorrespondencesPtr getCorrespondences (const Vertex &source_vertex, const Vertex &target_vertex) const
Return a set of correspondences from one of the SLAM graph's edges. More...
void compute ()
Perform LUM's globally consistent scan matching. More...
PointCloudPtr getTransformedCloud (const Vertex &vertex) const
Return a point cloud from one of the SLAM graph's vertices compounded onto its current pose estimate. More...
PointCloudPtr getConcatenatedCloud () const
Return a concatenated point cloud of all the SLAM graph's point clouds compounded onto their current pose estimates. More...

Protected Member Functions

void computeEdge (const Edge &e)
Linearized computation of C^-1 and C^-1*D (results stored in slam_graph_). More...
Eigen::Matrix6f incidenceCorrection (const Eigen::Vector6f &pose)
Returns a pose corrected 6DoF incidence matrix. More...

Detailed Description

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

Globally Consistent Scan Matching based on an algorithm by Lu and Milios.

A GraphSLAM algorithm where registration data is managed in a graph:

  • Vertices represent poses and hold the point cloud data and relative transformations.
  • Edges represent pose constraints and hold the correspondence data between two point clouds.

Computation uses the first point cloud in the SLAM graph as a reference pose and attempts to align all other point clouds to it simultaneously. For more information:

  • F. Lu, E. Milios, Globally Consistent Range Scan Alignment for Environment Mapping, Autonomous Robots 4, April 1997
  • Dorit Borrmann, Jan Elseberg, Kai Lingemann, Andreas Nüchter, and Joachim Hertzberg, The Efficient Extension of Globally Consistent Scan Matching to 6 DoF, In Proceedings of the 4th International Symposium on 3D Data Processing, Visualization and Transmission (3DPVT '08), June 2008

Usage example:

// Add point clouds as vertices to the SLAM graph
lum. addPointCloud (cloud_0);
lum. addPointCloud (cloud_1);
lum. addPointCloud (cloud_2);
// Use your favorite pairwise correspondence estimation algorithm(s)
corrs_0_to_1 = someAlgo (cloud_0, cloud_1);
corrs_1_to_2 = someAlgo (cloud_1, cloud_2);
corrs_2_to_0 = someAlgo (lum. getPointCloud (2), lum. getPointCloud (0));
// Add the correspondence results as edges to the SLAM graph
lum. setCorrespondences (0, 1, corrs_0_to_1);
lum. setCorrespondences (1, 2, corrs_1_to_2);
lum. setCorrespondences (2, 0, corrs_2_to_0);
// Change the computation parameters
lum. setMaxIterations (5);
// Perform the actual LUM computation
lum. compute ();
// Return the concatenated point cloud result
cloud_out = lum. getConcatenatedCloud ();
// Return the separate point cloud transformations
for( int i = 0; i < lum. getNumVertices (); i++)
{
transforms_out[i] = lum. getTransformation (i);
}
Author
Frits Florentinus, Jochen Sprickerhof

Definition at line 108 of file lum.h.

Member Typedef Documentation

ConstPtr

template<typename PointT >
using pcl::registration::LUM< PointT >::ConstPtr = shared_ptr<const LUM<PointT> >

Definition at line 111 of file lum.h.

Edge

template<typename PointT >
using pcl::registration::LUM< PointT >::Edge = typename SLAMGraph::edge_descriptor

Definition at line 138 of file lum.h.

PointCloud

template<typename PointT >
using pcl::registration::LUM< PointT >::PointCloud = pcl::PointCloud<PointT>

Definition at line 113 of file lum.h.

PointCloudConstPtr

template<typename PointT >
using pcl::registration::LUM< PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr

Definition at line 115 of file lum.h.

PointCloudPtr

template<typename PointT >
using pcl::registration::LUM< PointT >::PointCloudPtr = typename PointCloud::Ptr

Definition at line 114 of file lum.h.

Ptr

template<typename PointT >
using pcl::registration::LUM< PointT >::Ptr = shared_ptr<LUM<PointT> >

Definition at line 110 of file lum.h.

SLAMGraph

template<typename PointT >
using pcl::registration::LUM< PointT >::SLAMGraph = boost::adjacency_list<boost::eigen_vecS, boost::eigen_vecS, boost::bidirectionalS, VertexProperties, EdgeProperties, boost::no_property, boost::eigen_listS>

Definition at line 135 of file lum.h.

SLAMGraphPtr

template<typename PointT >
using pcl::registration::LUM< PointT >::SLAMGraphPtr = shared_ptr<SLAMGraph>

Definition at line 136 of file lum.h.

Vertex

template<typename PointT >
using pcl::registration::LUM< PointT >::Vertex = typename SLAMGraph::vertex_descriptor

Definition at line 137 of file lum.h.

Constructor & Destructor Documentation

LUM()

template<typename PointT >
pcl::registration::LUM< PointT >::LUM ( )
inline

Empty constructor.

Definition at line 142 of file lum.h.

Member Function Documentation

addPointCloud()

template<typename PointT >
LUM< PointT >::Vertex pcl::registration::LUM< PointT >::addPointCloud ( const PointCloudPtr & cloud,
const Eigen::Vector6f & pose = Eigen::Vector6f::Zero()
)

Add a new point cloud to the SLAM graph.

This method will add a new vertex to the SLAM graph and attach a point cloud to that vertex. Optionally you can specify a pose estimate for this point cloud. A vertex' pose is always relative to the first vertex in the SLAM graph, i.e. the first point cloud that was added. Because this first vertex is the reference, you can not set a pose estimate for this vertex. Providing pose estimates to the vertices in the SLAM graph will reduce overall computation time of LUM.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] cloud The new point cloud.
[in] pose (optional) The pose estimate relative to the reference pose (first point cloud that was added).
Returns
The vertex descriptor of the newly created vertex.

Definition at line 101 of file lum.hpp.

compute()

template<typename PointT >
void pcl::registration::LUM< PointT >::compute

Perform LUM's globally consistent scan matching.

Computation uses the first point cloud in the SLAM graph as a reference pose and attempts to align all other point clouds to it simultaneously.
Things to keep in mind:

  • Only those parts of the graph connected to the reference pose will properly align to it.
  • All sets of correspondences should span the same space and need to be sufficient to determine a rigid transformation.
  • The algorithm draws it strength from loops in the graph because it will distribute errors evenly amongst those loops.

Computation ends when either of the following conditions hold:

Computation will change the pose estimates for the vertices of the SLAM graph, not the point clouds attached to them. The results can be retrieved with getPose(), getTransformation(), getTransformedCloud() or getConcatenatedCloud().

Definition at line 221 of file lum.hpp.

References pcl::B.

computeEdge()

template<typename PointT >
void pcl::registration::LUM< PointT >::computeEdge ( const Edge & e )
protected

Linearized computation of C^-1 and C^-1*D (results stored in slam_graph_).

Definition at line 308 of file lum.hpp.

References pcl::getTransformation().

getConcatenatedCloud()

template<typename PointT >
LUM< PointT >::PointCloudPtr pcl::registration::LUM< PointT >::getConcatenatedCloud

Return a concatenated point cloud of all the SLAM graph's point clouds compounded onto their current pose estimates.

Returns
The concatenated transformed point clouds of the entire SLAM graph.

Definition at line 294 of file lum.hpp.

References pcl::getTransformation(), and pcl::transformPointCloud().

getConvergenceThreshold()

template<typename PointT >
float pcl::registration::LUM< PointT >::getConvergenceThreshold
inline

Get the convergence threshold for the compute() method.

When the compute() method computes the new poses relative to the old poses, it will determine the length of the difference vector. When the average length of all difference vectors becomes less than the convergence_threshold the convergence is assumed to be met.

Returns
The current convergence threshold (default = 0.0).

Definition at line 94 of file lum.hpp.

getCorrespondences()

template<typename PointT >
pcl::CorrespondencesPtr pcl::registration::LUM< PointT >::getCorrespondences ( const Vertex & source_vertex,
const Vertex & target_vertex
) const
inline

Return a set of correspondences from one of the SLAM graph's edges.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] source_vertex The vertex descriptor of the correspondences' source point cloud.
[in] target_vertex The vertex descriptor of the correspondences' target point cloud.
Returns
The current set of correspondences of that edge.

Definition at line 200 of file lum.hpp.

getLoopGraph()

template<typename PointT >
LUM< PointT >::SLAMGraphPtr pcl::registration::LUM< PointT >::getLoopGraph
inline

Get the internal SLAM graph structure.

All data used and produced by LUM is stored in this boost::adjacency_list. It is recommended to use the LUM class itself to build the graph. This method could otherwise be useful for managing several SLAM graphs in one instance of LUM.

Returns
The current SLAM graph.

Definition at line 59 of file lum.hpp.

getMaxIterations()

template<typename PointT >
int pcl::registration::LUM< PointT >::getMaxIterations
inline

Get the maximum number of iterations for the compute() method.

The compute() method finishes when max_iterations are met or when the convergence criteria is met.

Returns
The current maximum number of iterations (default = 5).

Definition at line 80 of file lum.hpp.

getNumVertices()

template<typename PointT >
LUM< PointT >::SLAMGraph::vertices_size_type pcl::registration::LUM< PointT >::getNumVertices

Get the number of vertices in the SLAM graph.

Returns
The current number of vertices in the SLAM graph.

Definition at line 66 of file lum.hpp.

getPointCloud()

template<typename PointT >
LUM< PointT >::PointCloudPtr pcl::registration::LUM< PointT >::getPointCloud ( const Vertex & vertex ) const
inline

Return a point cloud from one of the SLAM graph's vertices.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] vertex The vertex descriptor of which to return the point cloud.
Returns
The current point cloud for that vertex.

Definition at line 130 of file lum.hpp.

getPose()

template<typename PointT >
Eigen::Vector6f pcl::registration::LUM< PointT >::getPose ( const Vertex & vertex ) const
inline

Return a pose estimate from one of the SLAM graph's vertices.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] vertex The vertex descriptor of which to return the pose estimate.
Returns
The current pose estimate of that vertex.

Definition at line 159 of file lum.hpp.

getTransformation()

template<typename PointT >
Eigen::Affine3f pcl::registration::LUM< PointT >::getTransformation ( const Vertex & vertex ) const
inline

Return a pose estimate from one of the SLAM graph's vertices as an affine transformation matrix.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] vertex The vertex descriptor of which to return the transformation matrix.
Returns
The current transformation matrix of that vertex.

Definition at line 171 of file lum.hpp.

References pcl::getTransformation().

getTransformedCloud()

template<typename PointT >
LUM< PointT >::PointCloudPtr pcl::registration::LUM< PointT >::getTransformedCloud ( const Vertex & vertex ) const

Return a point cloud from one of the SLAM graph's vertices compounded onto its current pose estimate.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] vertex The vertex descriptor of which to return the transformed point cloud.
Returns
The transformed point cloud of that vertex.

Definition at line 285 of file lum.hpp.

References pcl::getTransformation(), and pcl::transformPointCloud().

incidenceCorrection()

template<typename PointT >
Eigen::Matrix6f pcl::registration::LUM< PointT >::incidenceCorrection ( const Eigen::Vector6f & pose )
inlineprotected

Returns a pose corrected 6DoF incidence matrix.

Definition at line 445 of file lum.hpp.

setConvergenceThreshold()

template<typename PointT >
void pcl::registration::LUM< PointT >::setConvergenceThreshold ( float convergence_threshold )

Set the convergence threshold for the compute() method.

When the compute() method computes the new poses relative to the old poses, it will determine the length of the difference vector. When the average length of all difference vectors becomes less than the convergence_threshold the convergence is assumed to be met.

Parameters
[in] convergence_threshold The new convergence threshold (default = 0.0).

Definition at line 87 of file lum.hpp.

setCorrespondences()

template<typename PointT >
void pcl::registration::LUM< PointT >::setCorrespondences ( const Vertex & source_vertex,
const Vertex & target_vertex,
const pcl::CorrespondencesPtr & corrs
)

Add/change a set of correspondences for one of the SLAM graph's edges.

The edges in the SLAM graph are directional and point from source vertex to target vertex. The query indices of the correspondences, index the points at the source vertex' point cloud. The matching indices of the correspondences, index the points at the target vertex' point cloud. If no edge was present at the specified location, this method will add a new edge to the SLAM graph and attach the correspondences to that edge. If the edge was already present, this method will overwrite the correspondence information of that edge and will not alter the SLAM graph structure.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] source_vertex The vertex descriptor of the correspondences' source point cloud.
[in] target_vertex The vertex descriptor of the correspondences' target point cloud.
[in] corrs The new set of correspondences for that edge.

Definition at line 179 of file lum.hpp.

setLoopGraph()

template<typename PointT >
void pcl::registration::LUM< PointT >::setLoopGraph ( const SLAMGraphPtr & slam_graph )
inline

Set the internal SLAM graph structure.

All data used and produced by LUM is stored in this boost::adjacency_list. It is recommended to use the LUM class itself to build the graph. This method could otherwise be useful for managing several SLAM graphs in one instance of LUM.

Parameters
[in] slam_graph The new SLAM graph.

Definition at line 52 of file lum.hpp.

setMaxIterations()

template<typename PointT >
void pcl::registration::LUM< PointT >::setMaxIterations ( int max_iterations )

Set the maximum number of iterations for the compute() method.

The compute() method finishes when max_iterations are met or when the convergence criteria is met.

Parameters
[in] max_iterations The new maximum number of iterations (default = 5).

Definition at line 73 of file lum.hpp.

setPointCloud()

template<typename PointT >
void pcl::registration::LUM< PointT >::setPointCloud ( const Vertex & vertex,
const PointCloudPtr & cloud
)
inline

Change a point cloud on one of the SLAM graph's vertices.

This method will change the point cloud attached to an existing vertex and will not alter the SLAM graph structure. Note that the correspondences attached to this vertex will not change and may need to be updated manually.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] vertex The vertex descriptor of which to change the point cloud.
[in] cloud The new point cloud for that vertex.

Definition at line 118 of file lum.hpp.

setPose()

template<typename PointT >
void pcl::registration::LUM< PointT >::setPose ( const Vertex & vertex,
const Eigen::Vector6f & pose
)
inline

Change a pose estimate on one of the SLAM graph's vertices.

A vertex' pose is always relative to the first vertex in the SLAM graph, i.e. the first point cloud that was added. Because this first vertex is the reference, you can not set a pose estimate for this vertex. Providing pose estimates to the vertices in the SLAM graph will reduce overall computation time of LUM.

Note
Vertex descriptors are typecastable to int.
Parameters
[in] vertex The vertex descriptor of which to set the pose estimate.
[in] pose The new pose estimate for that vertex.

Definition at line 142 of file lum.hpp.


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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1registration_1_1_l_u_m.html