Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #ifndef PCL_REGISTRATION_LUM_H_
00042 #define PCL_REGISTRATION_LUM_H_
00043
00044 #include <pcl/pcl_base.h>
00045 #include <pcl/registration/eigen.h>
00046 #include <pcl/registration/boost.h>
00047 #include <pcl/common/transforms.h>
00048 #include <pcl/correspondence.h>
00049 #include <pcl/registration/boost_graph.h>
00050
00051 namespace Eigen
00052 {
00053 typedef Eigen::Matrix<float, 6, 1> Vector6f;
00054 typedef Eigen::Matrix<float, 6, 6> Matrix6f;
00055 }
00056
00057 namespace pcl
00058 {
00059 namespace registration
00060 {
00109 template<typename PointT>
00110 class LUM
00111 {
00112 public:
00113 typedef boost::shared_ptr<LUM<PointT> > Ptr;
00114 typedef boost::shared_ptr<const LUM<PointT> > ConstPtr;
00115
00116 typedef pcl::PointCloud<PointT> PointCloud;
00117 typedef typename PointCloud::Ptr PointCloudPtr;
00118 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00119
00120 struct VertexProperties
00121 {
00122 PointCloudPtr cloud_;
00123 Eigen::Vector6f pose_;
00124 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00125 };
00126 struct EdgeProperties
00127 {
00128 pcl::CorrespondencesPtr corrs_;
00129 Eigen::Matrix6f cinv_;
00130 Eigen::Vector6f cinvd_;
00131 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00132 };
00133
00134 typedef boost::adjacency_list<boost::eigen_vecS, boost::eigen_vecS, boost::bidirectionalS, VertexProperties, EdgeProperties, boost::no_property, boost::eigen_listS> SLAMGraph;
00135 typedef boost::shared_ptr<SLAMGraph> SLAMGraphPtr;
00136 typedef typename SLAMGraph::vertex_descriptor Vertex;
00137 typedef typename SLAMGraph::edge_descriptor Edge;
00138
00141 LUM ()
00142 : slam_graph_ (new SLAMGraph)
00143 , max_iterations_ (5)
00144 , convergence_threshold_ (0.0)
00145 {
00146 }
00147
00154 inline void
00155 setLoopGraph (const SLAMGraphPtr &slam_graph);
00156
00163 inline SLAMGraphPtr
00164 getLoopGraph () const;
00165
00169 typename SLAMGraph::vertices_size_type
00170 getNumVertices () const;
00171
00176 void
00177 setMaxIterations (int max_iterations);
00178
00183 inline int
00184 getMaxIterations () const;
00185
00191 void
00192 setConvergenceThreshold (float convergence_threshold);
00193
00199 inline float
00200 getConvergenceThreshold () const;
00201
00213 Vertex
00214 addPointCloud (const PointCloudPtr &cloud, const Eigen::Vector6f &pose = Eigen::Vector6f::Zero ());
00215
00223 inline void
00224 setPointCloud (const Vertex &vertex, const PointCloudPtr &cloud);
00225
00231 inline PointCloudPtr
00232 getPointCloud (const Vertex &vertex) const;
00233
00242 inline void
00243 setPose (const Vertex &vertex, const Eigen::Vector6f &pose);
00244
00250 inline Eigen::Vector6f
00251 getPose (const Vertex &vertex) const;
00252
00258 inline Eigen::Affine3f
00259 getTransformation (const Vertex &vertex) const;
00260
00272 void
00273 setCorrespondences (const Vertex &source_vertex,
00274 const Vertex &target_vertex,
00275 const pcl::CorrespondencesPtr &corrs);
00276
00283 inline pcl::CorrespondencesPtr
00284 getCorrespondences (const Vertex &source_vertex, const Vertex &target_vertex) const;
00285
00303 void
00304 compute ();
00305
00311 PointCloudPtr
00312 getTransformedCloud (const Vertex &vertex) const;
00313
00317 PointCloudPtr
00318 getConcatenatedCloud () const;
00319
00320 protected:
00322 void
00323 computeEdge (const Edge &e);
00324
00326 inline Eigen::Matrix6f
00327 incidenceCorrection (const Eigen::Vector6f &pose);
00328
00329 private:
00331 SLAMGraphPtr slam_graph_;
00332
00334 int max_iterations_;
00335
00337 float convergence_threshold_;
00338 };
00339 }
00340 }
00341
00342 #ifdef PCL_NO_PRECOMPILE
00343 #include <pcl/registration/impl/lum.hpp>
00344 #endif
00345
00346 #endif // PCL_REGISTRATION_LUM_H_
00347