Classes |
struct | EdgeProperties |
struct | VertexProperties |
Public Types |
typedef boost::shared_ptr
< const LUM< PointT > > | ConstPtr |
typedef SLAMGraph::edge_descriptor | Edge |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef PointCloud::Ptr | PointCloudPtr |
typedef boost::shared_ptr< LUM
< PointT > > | Ptr |
typedef boost::adjacency_list
< boost::eigen_vecS,
boost::eigen_vecS,
boost::bidirectionalS,
VertexProperties,
EdgeProperties,
boost::no_property,
boost::eigen_listS > | SLAMGraph |
typedef boost::shared_ptr
< SLAMGraph > | SLAMGraphPtr |
typedef
SLAMGraph::vertex_descriptor | Vertex |
Public Member Functions |
Vertex | addPointCloud (const PointCloudPtr &cloud, const Eigen::Vector6f &pose=Eigen::Vector6f::Zero()) |
| Add a new point cloud to the SLAM graph.
|
void | compute () |
| Perform LUM's globally consistent scan matching.
|
PointCloudPtr | getConcatenatedCloud () const |
| Return a concatenated point cloud of all the SLAM graph's point clouds compounded onto their current pose estimates.
|
float | getConvergenceThreshold () const |
| Get the convergence threshold for the compute() method.
|
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.
|
SLAMGraphPtr | getLoopGraph () const |
| Get the internal SLAM graph structure.
|
int | getMaxIterations () const |
| Get the maximum number of iterations for the compute() method.
|
SLAMGraph::vertices_size_type | getNumVertices () const |
| Get the number of vertices in the SLAM graph.
|
PointCloudPtr | getPointCloud (const Vertex &vertex) const |
| Return a point cloud from one of the SLAM graph's vertices.
|
Eigen::Vector6f | getPose (const Vertex &vertex) const |
| Return a pose estimate from one of the SLAM graph's vertices.
|
Eigen::Affine3f | getTransformation (const Vertex &vertex) const |
| Return a pose estimate from one of the SLAM graph's vertices as an affine transformation matrix.
|
PointCloudPtr | getTransformedCloud (const Vertex &vertex) const |
| Return a point cloud from one of the SLAM graph's vertices compounded onto its current pose estimate.
|
| LUM () |
| Empty constructor.
|
void | setConvergenceThreshold (float convergence_threshold) |
| Set the convergence threshold for the compute() method.
|
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.
|
void | setLoopGraph (const SLAMGraphPtr &slam_graph) |
| Set the internal SLAM graph structure.
|
void | setMaxIterations (int max_iterations) |
| Set the maximum number of iterations for the compute() method.
|
void | setPointCloud (const Vertex &vertex, const PointCloudPtr &cloud) |
| Change a point cloud on one of the SLAM graph's vertices.
|
void | setPose (const Vertex &vertex, const Eigen::Vector6f &pose) |
| Change a pose estimate on one of the SLAM graph's vertices.
|
Protected Member Functions |
void | computeEdge (const Edge &e) |
| Linearized computation of C^-1 and C^-1*D (results stored in slam_graph_).
|
Eigen::Matrix6f | incidenceCorrection (const Eigen::Vector6f &pose) |
| Returns a pose corrected 6DoF incidence matrix.
|
Private Attributes |
float | convergence_threshold_ |
| The convergence threshold for the summed vector lengths of all poses.
|
int | max_iterations_ |
| The maximum number of iterations for the compute() method.
|
SLAMGraphPtr | slam_graph_ |
| The internal SLAM graph structure.
|
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:
- Author:
- Frits Florentinus, Jochen Sprickerhof
Definition at line 110 of file lum.h.
template<typename PointT >
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 95 of file lum.hpp.
template<typename PointT >
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 209 of file lum.hpp.
template<typename PointT >
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 172 of file lum.hpp.
template<typename PointT >
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 135 of file lum.hpp.