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 #ifndef PCL_ELCH_H_
00041 #define PCL_ELCH_H_
00042 
00043 #include <boost/graph/adjacency_list.hpp>
00044 #include <boost/graph/graph_traits.hpp>
00045 #include <boost/shared_ptr.hpp>
00046 
00047 #include <Eigen/Geometry>
00048 
00049 #include <pcl/pcl_base.h>
00050 #include <pcl/point_types.h>
00051 #include <pcl/point_cloud.h>
00052 #include <pcl/registration/registration.h>
00053 #include <pcl/registration/icp.h>
00054 
00055 namespace pcl
00056 {
00057   namespace registration
00058   {
00063     template <typename PointT>
00064     class ELCH : public PCLBase<PointT>
00065     {
00066       public:
00067         typedef boost::shared_ptr< ELCH<PointT> > Ptr;
00068         typedef boost::shared_ptr< const ELCH<PointT> > ConstPtr;
00069 
00070         typedef pcl::PointCloud<PointT> PointCloud;
00071         typedef typename PointCloud::Ptr PointCloudPtr;
00072         typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00073 
00074         struct Vertex
00075         {
00076           Vertex () : cloud () {}
00077           PointCloudPtr cloud;
00078         };
00079 
00081         typedef boost::adjacency_list<
00082           boost::listS, boost::vecS, boost::undirectedS,
00083           Vertex,
00084           boost::no_property>
00085         LoopGraph;
00086 
00087         typedef boost::shared_ptr< LoopGraph > LoopGraphPtr;
00088 
00089         typedef typename pcl::Registration<PointT, PointT> Registration;
00090         typedef typename Registration::Ptr RegistrationPtr;
00091         typedef typename Registration::ConstPtr RegistrationConstPtr;
00092 
00094         ELCH () : 
00095           loop_graph_ (new LoopGraph), 
00096           loop_start_ (0), 
00097           loop_end_ (0), 
00098           reg_ (new pcl::IterativeClosestPoint<PointT, PointT>), 
00099           loop_transform_ (),
00100           compute_loop_ (true),
00101           vd_ ()
00102         {};
00103 
00107         inline void
00108         addPointCloud (PointCloudPtr cloud)
00109         {
00110           typename boost::graph_traits<LoopGraph>::vertex_descriptor vd = add_vertex (*loop_graph_);
00111           (*loop_graph_)[vd].cloud = cloud;
00112           if (num_vertices (*loop_graph_) > 1)
00113             add_edge (vd_, vd, *loop_graph_);
00114           vd_ = vd;
00115         }
00116 
00118         inline LoopGraphPtr
00119         getLoopGraph ()
00120         {
00121           return (loop_graph_);
00122         }
00123 
00127         inline void
00128         setLoopGraph (LoopGraphPtr loop_graph)
00129         {
00130           loop_graph_ = loop_graph;
00131         }
00132 
00134         inline typename boost::graph_traits<LoopGraph>::vertex_descriptor
00135         getLoopStart ()
00136         {
00137           return (loop_start_);
00138         }
00139 
00143         inline void
00144         setLoopStart (const typename boost::graph_traits<LoopGraph>::vertex_descriptor &loop_start)
00145         {
00146           loop_start_ = loop_start;
00147         }
00148 
00150         inline typename boost::graph_traits<LoopGraph>::vertex_descriptor
00151         getLoopEnd ()
00152         {
00153           return (loop_end_);
00154         }
00155 
00159         inline void
00160         setLoopEnd (const typename boost::graph_traits<LoopGraph>::vertex_descriptor &loop_end)
00161         {
00162           loop_end_ = loop_end;
00163         }
00164 
00166         inline RegistrationPtr
00167         getReg ()
00168         {
00169           return (reg_);
00170         }
00171 
00175         inline void
00176         setReg (RegistrationPtr reg)
00177         {
00178           reg_ = reg;
00179         }
00180 
00182         inline Eigen::Matrix4f
00183         getLoopTransform ()
00184         {
00185           return (loop_transform_);
00186         }
00187 
00191         inline void
00192         setLoopTransform (const Eigen::Matrix4f &loop_transform)
00193         {
00194           loop_transform_ = loop_transform;
00195           compute_loop_ = false;
00196         }
00197 
00202         void
00203         compute ();
00204 
00205       protected:
00206         using PCLBase<PointT>::deinitCompute;
00207 
00209         virtual bool
00210         initCompute ();
00211 
00212       private:
00214         typedef boost::adjacency_list<
00215           boost::listS, boost::vecS, boost::undirectedS,
00216           boost::no_property,
00217           boost::property< boost::edge_weight_t, double > >
00218         LOAGraph;
00219 
00227         void
00228         loopOptimizerAlgorithm (LOAGraph &g, double *weights);
00229 
00231         LoopGraphPtr loop_graph_;
00232 
00234         typename boost::graph_traits<LoopGraph>::vertex_descriptor loop_start_;
00235 
00237         typename boost::graph_traits<LoopGraph>::vertex_descriptor loop_end_;
00238 
00240         RegistrationPtr reg_;
00241 
00243         Eigen::Matrix4f loop_transform_;
00244         bool compute_loop_;
00245 
00247         typename boost::graph_traits<LoopGraph>::vertex_descriptor vd_;
00248 
00249       public:
00250         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00251     };
00252   }
00253 }
00254 
00255 #include <pcl/registration/impl/elch.hpp>
00256 
00257 #endif // PCL_ELCH_H_