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_APPS_IN_HAND_SCANNER_INTEGRATION_H
00042 #define PCL_APPS_IN_HAND_SCANNER_INTEGRATION_H
00043 
00044 #include <stdint.h>
00045 
00046 #include <pcl/pcl_exports.h>
00047 #include <pcl/apps/in_hand_scanner/common_types.h>
00048 
00050 
00052 
00053 namespace pcl
00054 {
00055   template <typename PointT>
00056   class KdTree;
00057 } 
00058 
00060 
00062 
00063 namespace pcl
00064 {
00065   namespace ihs
00066   {
00071     class PCL_EXPORTS Integration
00072     {
00073       public:
00074 
00075         typedef pcl::PointXYZRGBNormal              PointXYZRGBNormal;
00076         typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
00077         typedef CloudXYZRGBNormal::Ptr              CloudXYZRGBNormalPtr;
00078         typedef CloudXYZRGBNormal::ConstPtr         CloudXYZRGBNormalConstPtr;
00079 
00080         typedef pcl::ihs::Mesh            Mesh;
00081         typedef pcl::ihs::MeshPtr         MeshPtr;
00082         typedef pcl::ihs::MeshConstPtr    MeshConstPtr;
00083         typedef Mesh::VertexIndex         VertexIndex;
00084         typedef Mesh::VertexIndices       VertexIndices;
00085 
00087         Integration ();
00088 
00094         bool
00095         reconstructMesh (const CloudXYZRGBNormalConstPtr& cloud_data,
00096                          MeshPtr&                         mesh_model) const;
00097 
00104         bool
00105         merge (const CloudXYZRGBNormalConstPtr& cloud_data,
00106                MeshPtr&                         mesh_model,
00107                const Eigen::Matrix4f&           T) const;
00108 
00113         void
00114         age (const MeshPtr& mesh, const bool cleanup=true) const;
00115 
00120         void
00121         removeUnfitVertices (const MeshPtr& mesh, const bool cleanup=true) const;
00122 
00127         void  setMaxSquaredDistance (const float squared_distance);
00128         float getMaxSquaredDistance () const;
00135         void  setMaxAngle (const float angle);
00136         float getMaxAngle () const;
00143         void         setMaxAge (const unsigned int age);
00144         unsigned int getMaxAge () const;
00151         void         setMinDirections (const unsigned int directions);
00152         unsigned int getMinDirections () const;
00155       private:
00156 
00157         typedef pcl::PointXYZ              PointXYZ;
00158         typedef pcl::PointCloud <PointXYZ> CloudXYZ;
00159         typedef CloudXYZ::Ptr              CloudXYZPtr;
00160         typedef CloudXYZ::ConstPtr         CloudXYZConstPtr;
00161 
00162         typedef pcl::ihs::PointIHS         PointIHS;
00163         typedef pcl::ihs::CloudIHS         CloudIHS;
00164         typedef pcl::ihs::CloudIHSPtr      CloudIHSPtr;
00165         typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr;
00166 
00167         typedef pcl::KdTree <PointXYZ>           KdTree;
00168         typedef boost::shared_ptr <KdTree>       KdTreePtr;
00169         typedef boost::shared_ptr <const KdTree> KdTreeConstPtr;
00170 
00171         uint8_t
00172         trimRGB (const float val) const;
00173 
00175         void
00176         addToMesh (const PointIHS& pt_0,
00177                    const PointIHS& pt_1,
00178                    const PointIHS& pt_2,
00179                    const PointIHS& pt_3,
00180                    VertexIndex&    vi_0,
00181                    VertexIndex&    vi_1,
00182                    VertexIndex&    vi_2,
00183                    VertexIndex&    vi_3,
00184                    const MeshPtr&  mesh) const;
00185 
00187         void
00188         addToMesh (const PointIHS& pt_0,
00189                    const PointIHS& pt_1,
00190                    const PointIHS& pt_2,
00191                    VertexIndex&    vi_0,
00192                    VertexIndex&    vi_1,
00193                    VertexIndex&    vi_2,
00194                    const MeshPtr&  mesh) const;
00195 
00197         bool
00198         distanceThreshold (const PointIHS& pt_0,
00199                            const PointIHS& pt_1,
00200                            const PointIHS& pt_2) const;
00201 
00203         bool
00204         distanceThreshold (const PointIHS& pt_0,
00205                            const PointIHS& pt_1,
00206                            const PointIHS& pt_2,
00207                            const PointIHS& pt_3) const;
00208 
00210         
00212 
00214         KdTreePtr kd_tree_;
00215 
00217         float max_squared_distance_;
00218 
00220         float max_angle_;
00221 
00223         float min_weight_;
00224 
00226         unsigned int max_age_;
00227 
00229         unsigned int min_directions_;
00230     };
00231   } 
00232 } 
00233 
00234 #endif // PCL_APPS_IN_HAND_SCANNER_INTEGRATION_H