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_OPENGL_VIEWER_H
00042 #define PCL_APPS_IN_HAND_SCANNER_OPENGL_VIEWER_H
00043 
00044 #include <string>
00045 
00046 #include <QGLWidget>
00047 
00048 #include <pcl/pcl_exports.h>
00049 #include <pcl/common/time.h>
00050 #include <pcl/apps/in_hand_scanner/boost.h>
00051 #include <pcl/apps/in_hand_scanner/common_types.h>
00052 #include <pcl/apps/in_hand_scanner/eigen.h>
00053 
00054 namespace pcl
00055 {
00056   namespace ihs
00057   {
00058     namespace detail
00059     {
00064       class FaceVertexMesh
00065       {
00066         public:
00067 
00068           class Triangle
00069           {
00070             public:
00071 
00072               Triangle () : first (0), second (0), third (0) {}
00073               Triangle (const unsigned int first, const unsigned int second, const unsigned int third)
00074                 : first (first), second (second), third (third)
00075               {
00076               }
00077 
00078               unsigned int first;
00079               unsigned int second;
00080               unsigned int third;
00081           };
00082 
00084           FaceVertexMesh ();
00085 
00087           FaceVertexMesh (const Mesh& mesh, const Eigen::Isometry3d& T);
00088 
00089           typedef pcl::ihs::PointIHS         PointIHS;
00090           typedef pcl::ihs::CloudIHS         CloudIHS;
00091           typedef pcl::ihs::CloudIHSPtr      CloudIHSPtr;
00092           typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr;
00093 
00094           CloudIHS               vertices;
00095           std::vector <Triangle> triangles;
00096           Eigen::Isometry3d      transformation;
00097 
00098         public:
00099 
00100           EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00101       };
00102     } 
00103 
00107     class PCL_EXPORTS OpenGLViewer : public QGLWidget
00108     {
00109       Q_OBJECT
00110 
00111       public:
00112 
00113         typedef pcl::PointXYZRGBNormal              PointXYZRGBNormal;
00114         typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
00115         typedef CloudXYZRGBNormal::Ptr              CloudXYZRGBNormalPtr;
00116         typedef CloudXYZRGBNormal::ConstPtr         CloudXYZRGBNormalConstPtr;
00117 
00118         typedef pcl::ihs::Mesh         Mesh;
00119         typedef pcl::ihs::MeshPtr      MeshPtr;
00120         typedef pcl::ihs::MeshConstPtr MeshConstPtr;
00121 
00123         typedef enum MeshRepresentation
00124         {
00125           MR_POINTS, 
00126           MR_EDGES,  
00127           MR_FACES   
00128         } MeshRepresentation;
00129 
00131         typedef enum Coloring
00132         {
00133           COL_RGB,       
00134           COL_ONE_COLOR, 
00135           COL_VISCONF    
00136         } Coloring;
00137 
00139         class BoxCoefficients
00140         {
00141           public:
00142 
00143             BoxCoefficients ()
00144               : x_min (0), x_max (0),
00145                 y_min (0), y_max (0),
00146                 z_min (0), z_max (0),
00147                 transformation (Eigen::Isometry3d::Identity ())
00148             {
00149             }
00150 
00151             BoxCoefficients (const float x_min, const float x_max,
00152                              const float y_min, const float y_max,
00153                              const float z_min, const float z_max,
00154                              const Eigen::Isometry3d& T)
00155               : x_min (x_min), x_max (x_max),
00156                 y_min (y_min), y_max (y_max),
00157                 z_min (z_min), z_max (z_max),
00158                 transformation (T)
00159             {
00160             }
00161 
00162             float x_min; float x_max;
00163             float y_min; float y_max;
00164             float z_min; float z_max;
00165             Eigen::Isometry3d transformation;
00166 
00167           public:
00168 
00169             EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00170         };
00171 
00173         explicit OpenGLViewer (QWidget* parent=0);
00174 
00176         ~OpenGLViewer ();
00177 
00185         bool
00186         addMesh (const MeshConstPtr& mesh, const std::string& id, const Eigen::Isometry3d& T = Eigen::Isometry3d::Identity ());
00187 
00195         bool
00196         addMesh (const CloudXYZRGBNormalConstPtr& cloud, const std::string& id, const Eigen::Isometry3d& T = Eigen::Isometry3d::Identity ());
00197 
00202         bool
00203         removeMesh (const std::string& id);
00204 
00206         void
00207         removeAllMeshes ();
00208 
00210         void
00211         setBoxCoefficients (const BoxCoefficients& coeffs);
00212 
00214         void
00215         setDrawBox (const bool enabled);
00216 
00218         bool
00219         getDrawBox () const;
00220 
00222         void
00223         setPivot (const Eigen::Vector3d& pivot);
00224 
00228         void
00229         setPivot (const std::string& id);
00230 
00232         void
00233         stopTimer ();
00234 
00236         void
00237         setVisibilityConfidenceNormalization (const float vis_conf_norm);
00238 
00240         virtual QSize
00241         minimumSizeHint () const;
00242 
00244         virtual QSize
00245         sizeHint () const;
00246 
00248         void
00249         setScalingFactor (const double scale);
00250 
00251       public slots:
00252 
00254         void
00255         timerCallback ();
00256 
00258         void
00259         resetCamera ();
00260 
00262         void
00263         toggleMeshRepresentation ();
00264 
00266         void
00267         setMeshRepresentation (const MeshRepresentation& representation);
00268 
00270         void
00271         toggleColoring ();
00272 
00274         void
00275         setColoring (const Coloring& coloring);
00276 
00277       protected:
00278 
00280         class FPS
00281         {
00282           public:
00283 
00284             FPS () : fps_ (0.) {}
00285 
00286             inline double& value ()       {return (fps_);}
00287             inline double  value () const {return (fps_);}
00288 
00289             inline std::string
00290             str () const
00291             {
00292               std::stringstream ss;
00293               ss << std::setprecision (1) << std::fixed << fps_;
00294               return (ss.str ());
00295             }
00296 
00297           protected:
00298 
00299             ~FPS () {}
00300 
00301           private:
00302 
00303             double fps_;
00304         };
00305 
00307         template <class FPS> void
00308         calcFPS (FPS& fps) const
00309         {
00310           static pcl::StopWatch sw;
00311           static unsigned int count = 0;
00312 
00313           ++count;
00314           if (sw.getTimeSeconds () >= .2)
00315           {
00316             fps.value () = static_cast <double> (count) / sw.getTimeSeconds ();
00317             count = 0;
00318             sw.reset ();
00319           }
00320         }
00321 
00325         virtual void
00326         paintEvent (QPaintEvent* event);
00327 
00328       private:
00329 
00330         typedef Eigen::Matrix <unsigned char, 3, 1             > Color;
00331         typedef Eigen::Matrix <unsigned char, 3, Eigen::Dynamic> Colors;
00332         typedef Eigen::Matrix <unsigned char, 3, 256           > Colormap;
00333 
00334         typedef boost::unordered_map <std::string, CloudXYZRGBNormalPtr> CloudXYZRGBNormalMap;
00335 
00336         typedef pcl::ihs::PointIHS         PointIHS;
00337         typedef pcl::ihs::CloudIHS         CloudIHS;
00338         typedef pcl::ihs::CloudIHSPtr      CloudIHSPtr;
00339         typedef pcl::ihs::CloudIHSConstPtr CloudIHSConstPtr;
00340 
00341         typedef pcl::ihs::detail::FaceVertexMesh                      FaceVertexMesh;
00342         typedef boost::shared_ptr <      FaceVertexMesh>              FaceVertexMeshPtr;
00343         typedef boost::shared_ptr <const FaceVertexMesh>              FaceVertexMeshConstPtr;
00344         typedef boost::unordered_map <std::string, FaceVertexMeshPtr> FaceVertexMeshMap;
00345 
00349         bool
00350         getMeshIsAdded (const std::string& id);
00351 
00353         void
00354         calcPivot ();
00355 
00359         void
00360         drawMeshes ();
00361 
00363         void
00364         drawBox ();
00365 
00367         void
00368         initializeGL ();
00369 
00371         void
00372         setupViewport (const int w, const int h);
00373 
00375         void
00376         resizeGL (int w, int h);
00377 
00379         void
00380         mousePressEvent (QMouseEvent* event);
00381 
00383         void
00384         mouseMoveEvent (QMouseEvent* event);
00385 
00387         void
00388         wheelEvent (QWheelEvent* event);
00389 
00391         
00393 
00395         boost::mutex mutex_vis_;
00396 
00398         boost::shared_ptr <QTimer> timer_vis_;
00399 
00401         Colormap colormap_;
00402 
00404         float vis_conf_norm_;
00405 
00407         FaceVertexMeshMap drawn_meshes_;
00408 
00410         MeshRepresentation mesh_representation_;
00411 
00413         Coloring coloring_;
00414 
00416         bool draw_box_;
00417 
00419         BoxCoefficients box_coefficients_;
00420 
00422         double scaling_factor_;
00423 
00425         Eigen::Quaterniond R_cam_;
00426 
00428         Eigen::Vector3d t_cam_;
00429 
00431         Eigen::Vector3d cam_pivot_;
00432 
00434         std::string cam_pivot_id_;
00435 
00437         bool mouse_pressed_begin_;
00438 
00440         int x_prev_;
00441 
00443         int y_prev_;
00444 
00445       public:
00446 
00447         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00448     };
00449   } 
00450 } 
00451 
00452 
00453 Q_DECLARE_METATYPE (pcl::ihs::OpenGLViewer::MeshRepresentation)
00454 Q_DECLARE_METATYPE (pcl::ihs::OpenGLViewer::Coloring)
00455 
00456 #endif // PCL_APPS_IN_HAND_SCANNER_OPENGL_VIEWER_H