Point Cloud Library (PCL)  1.4.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
pcl_visualizer.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: pcl_visualizer.h 3771 2012-01-01 06:58:14Z rusu $
00037  *
00038  */
00039 #ifndef PCL_PCL_VISUALIZER_H_
00040 #define PCL_PCL_VISUALIZER_H_
00041 
00042 // PCL includes
00043 #include <pcl/point_types.h>
00044 #include <pcl/correspondence.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/PolygonMesh.h>
00047 // 
00048 #include <pcl/console/print.h>
00049 #include <pcl/visualization/common/common.h>
00050 #include <pcl/visualization/common/shapes.h>
00051 #include <pcl/visualization/window.h>
00052 #include <boost/algorithm/string/split.hpp>
00053 #include <boost/algorithm/string/classification.hpp>
00054 // VTK includes
00055 #include <vtkAxes.h>
00056 #include <vtkFloatArray.h>
00057 #include <vtkAppendPolyData.h>
00058 #include <vtkPointData.h>
00059 #include <vtkPolyData.h>
00060 #include <vtkUnstructuredGrid.h>
00061 #include <vtkTubeFilter.h>
00062 #include <vtkPolyDataMapper.h>
00063 #include <vtkDataSetMapper.h>
00064 #include <vtkCellArray.h>
00065 #include <vtkCommand.h>
00066 #include <vtkPLYReader.h>
00067 #include <vtkTransformFilter.h>
00068 #include <vtkPolyLine.h>
00069 #include <vtkVectorText.h>
00070 #include <vtkFollower.h>
00071 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00072 #include <pcl/visualization/interactor.h>
00073 #else
00074 #include <vtkRenderWindowInteractor.h>
00075 #endif
00076 
00077 namespace pcl
00078 {
00079   namespace visualization
00080   {
00085     class PCL_EXPORTS PCLVisualizer
00086     {
00087       public:
00088         typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2> GeometryHandler;
00089         typedef GeometryHandler::Ptr GeometryHandlerPtr;
00090         typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr;
00091 
00092         typedef PointCloudColorHandler<sensor_msgs::PointCloud2> ColorHandler;
00093         typedef ColorHandler::Ptr ColorHandlerPtr;
00094         typedef ColorHandler::ConstPtr ColorHandlerConstPtr;
00095 
00100         PCLVisualizer (const std::string &name = "", const bool create_interactor = true);
00108         PCLVisualizer (int &argc, char **argv, const std::string &name = "", 
00109             PCLVisualizerInteractorStyle* style = PCLVisualizerInteractorStyle::New (), const bool create_interactor = true);
00110 
00112         virtual ~PCLVisualizer ();
00113 
00118         boost::signals2::connection 
00119         registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> cb);
00120 
00126         inline boost::signals2::connection 
00127         registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*), void* cookie = NULL)
00128         {
00129           return (registerKeyboardCallback (boost::bind (callback, _1, cookie)));
00130         }
00131         
00138         template<typename T> inline boost::signals2::connection 
00139         registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*), T& instance, void* cookie = NULL)
00140         {
00141           return (registerKeyboardCallback (boost::bind (callback,  boost::ref (instance), _1, cookie)));
00142         }
00143         
00148         boost::signals2::connection 
00149         registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> cb);
00150         
00156         inline boost::signals2::connection 
00157         registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*), void* cookie = NULL)
00158         {
00159           return (registerMouseCallback (boost::bind (callback, _1, cookie)));
00160         }
00161         
00168         template<typename T> inline boost::signals2::connection 
00169         registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*), T& instance, void* cookie = NULL)
00170         {
00171           return (registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00172         }
00173 
00178         boost::signals2::connection 
00179         registerPointPickingCallback (boost::function<void (const pcl::visualization::PointPickingEvent&)> cb);
00180         
00186         inline boost::signals2::connection 
00187         registerPointPickingCallback (void (*callback) (const pcl::visualization::PointPickingEvent&, void*), void* cookie = NULL)
00188         {
00189           return (registerPointPickingCallback (boost::bind (callback, _1, cookie)));
00190         }
00191         
00198         template<typename T> inline boost::signals2::connection 
00199         registerPointPickingCallback (void (T::*callback) (const pcl::visualization::PointPickingEvent&, void*), T& instance, void* cookie = NULL)
00200         {
00201           return (registerPointPickingCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00202         }
00203         
00205         void 
00206         spin ();
00207         
00213         void 
00214         spinOnce (int time = 1, bool force_redraw = false);
00215 
00220         void 
00221         addCoordinateSystem (double scale = 1.0, int viewport = 0);
00222         
00230         void 
00231         addCoordinateSystem (double scale, float x, float y, float z, int viewport = 0);
00232 
00264         void 
00265         addCoordinateSystem (double scale, const Eigen::Matrix4f& t, int viewport = 0);
00266 
00270         bool 
00271         removeCoordinateSystem (int viewport = 0);
00272 
00277         bool 
00278         removePointCloud (const std::string &id = "cloud", int viewport = 0);
00279 
00284         inline bool 
00285         removePolygonMesh (const std::string &id = "polygon", int viewport = 0)
00286         {
00287           // Polygon Meshes are represented internally as point clouds with special cell array structures since 1.4
00288           return (removePointCloud (id, viewport));
00289         }
00290 
00295         bool 
00296         removeShape (const std::string &id = "cloud", int viewport = 0);
00297 
00302         bool 
00303         removeText3D (const std::string &id = "cloud", int viewport = 0);
00304 
00308         bool
00309         removeAllPointClouds (int viewport = 0);
00310 
00314         bool
00315         removeAllShapes (int viewport = 0);
00316 
00323         void 
00324         setBackgroundColor (const double &r, const double &g, const double &b, int viewport = 0);
00325 
00333         bool 
00334         addText (const std::string &text, 
00335                  int xpos, int ypos, 
00336                  const std::string &id = "", int viewport = 0);
00337 
00348         bool 
00349         addText (const std::string &text, int xpos, int ypos, double r, double g, double b, 
00350                  const std::string &id = "", int viewport = 0);
00351 
00363         bool 
00364         addText (const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b, 
00365                  const std::string &id = "", int viewport = 0);
00366 
00367         
00378         template <typename PointT> bool
00379         addText3D (const std::string &text, 
00380                    const PointT &position, 
00381                    double textScale = 1.0, 
00382                    double r = 1.0, double g = 1.0, double b = 1.0,
00383                    const std::string &id = "", int viewport = 0);
00384 
00392         template <typename PointNT> bool 
00393         addPointCloudNormals (const typename pcl::PointCloud<PointNT>::ConstPtr &cloud,
00394                               int level = 100, double scale = 0.02,
00395                               const std::string &id = "cloud", int viewport = 0);
00396 
00405         template <typename PointT, typename PointNT> bool 
00406         addPointCloudNormals (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00407                               const typename pcl::PointCloud<PointNT>::ConstPtr &normals,
00408                               int level = 100, double scale = 0.02,
00409                               const std::string &id = "cloud", int viewport = 0);
00410 
00420         bool 
00421         addPointCloudPrincipalCurvatures (
00422             const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 
00423             const pcl::PointCloud<pcl::Normal>::ConstPtr &normals,
00424             const pcl::PointCloud<pcl::PrincipalCurvatures>::ConstPtr &pcs,
00425             int level = 100, double scale = 1.0,
00426             const std::string &id = "cloud", int viewport = 0);
00427    
00433         template <typename PointT> bool 
00434         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00435                        const std::string &id = "cloud", int viewport = 0);
00436 
00442         template <typename PointT> bool 
00443         updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00444                           const std::string &id = "cloud");
00445 
00452         template <typename PointT> bool 
00453         updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00454                           const PointCloudGeometryHandler<PointT> &geometry_handler,
00455                           const std::string &id = "cloud");
00456 
00463         template <typename PointT> bool 
00464         updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00465                           const PointCloudColorHandler<PointT> &color_handler,
00466                           const std::string &id = "cloud");
00467 
00468 //        bool 
00469 //        updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 
00470 //                          const PointCloudColorHandlerRGBField<pcl::PointXYZRGB> &color_handler,
00471 //                          const std::string &id = "cloud");
00472 
00479         template <typename PointT> bool 
00480         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00481                        const PointCloudGeometryHandler<PointT> &geometry_handler,
00482                        const std::string &id = "cloud", int viewport = 0);
00483 
00496         template <typename PointT> bool 
00497         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00498                        const GeometryHandlerConstPtr &geometry_handler,
00499                        const std::string &id = "cloud", int viewport = 0);
00500 
00507         template <typename PointT> bool 
00508         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00509                        const PointCloudColorHandler<PointT> &color_handler,
00510                        const std::string &id = "cloud", int viewport = 0);
00511 
00524         template <typename PointT> bool 
00525         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00526                        const ColorHandlerConstPtr &color_handler,
00527                        const std::string &id = "cloud", int viewport = 0);
00528 
00542         template <typename PointT> bool 
00543         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00544                        const GeometryHandlerConstPtr &geometry_handler,
00545                        const ColorHandlerConstPtr &color_handler,
00546                        const std::string &id = "cloud", int viewport = 0);
00547 
00555         template <typename PointT> bool 
00556         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00557                        const PointCloudColorHandler<PointT> &color_handler,
00558                        const PointCloudGeometryHandler<PointT> &geometry_handler,
00559                        const std::string &id = "cloud", int viewport = 0);
00560 
00566         inline bool 
00567         addPointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 
00568                        const std::string &id = "cloud", int viewport = 0)
00569         {
00570           return (addPointCloud<pcl::PointXYZ> (cloud, id, viewport));
00571         }
00572 
00573 
00579         inline bool 
00580         addPointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 
00581                        const std::string &id = "cloud", int viewport = 0)
00582         {
00583           pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud);
00584           return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler, id, viewport));
00585         }
00586 
00592         inline bool 
00593         updatePointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 
00594                           const std::string &id = "cloud")
00595         {
00596           return (updatePointCloud<pcl::PointXYZ> (cloud, id));
00597         }
00598 
00604         inline bool 
00605         updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 
00606                           const std::string &id = "cloud")
00607         {
00608           pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud);
00609           return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler, id));
00610         }
00611 
00617         bool
00618         addPolygonMesh (const pcl::PolygonMesh &polymesh, 
00619                         const std::string &id = "polygon", 
00620                         int viewport = 0);
00621 
00628         template <typename PointT> bool
00629         addPolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00630                         const std::vector<pcl::Vertices> &vertices,
00631                         const std::string &id = "polygon", 
00632                         int viewport = 0);
00633 
00640         template <typename PointT> bool
00641         updatePolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00642                            const std::vector<pcl::Vertices> &vertices,
00643                            const std::string &id = "polygon");
00644 
00650         bool
00651         addPolylineFromPolygonMesh (const pcl::PolygonMesh &polymesh, 
00652                                     const std::string &id = "polyline",
00653                                     int viewport = 0);
00654 
00662         template <typename PointT> bool
00663         addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
00664                             const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
00665                             const std::vector<int> & correspondences,
00666                             const std::string &id = "correspondences",
00667                             int viewport = 0);
00668 
00676         template <typename PointT> bool
00677         addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
00678                             const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
00679                             const pcl::Correspondences &correspondences,
00680                             const std::string &id = "correspondences",
00681                             int viewport = 0);
00682         
00687         inline void
00688         removeCorrespondences (const std::string &id = "correspondences", int viewport = 0)
00689         {
00690           removeShape (id, viewport);
00691         }
00692          
00696         inline int 
00697         getColorHandlerIndex (const std::string &id)
00698         {
00699           CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id);
00700           if (am_it == cloud_actor_map_->end ())
00701             return (-1);
00702 
00703           return (am_it->second.color_handler_index_);
00704         }
00705         
00709         inline int 
00710         getGeometryHandlerIndex (const std::string &id)
00711         {
00712           CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id);
00713           if (am_it != cloud_actor_map_->end ())
00714             return (-1);
00715 
00716           return (am_it->second.geometry_handler_index_);
00717         }
00718 
00723         bool 
00724         updateColorHandlerIndex (const std::string &id, int index);
00725 
00734         bool 
00735         setPointCloudRenderingProperties (int property, double val1, double val2, double val3, 
00736                                           const std::string &id = "cloud", int viewport = 0);
00737 
00744         bool 
00745         setPointCloudRenderingProperties (int property, double value, 
00746                                           const std::string &id = "cloud", int viewport = 0);
00747 
00753         bool 
00754         getPointCloudRenderingProperties (int property, double &value, 
00755                                           const std::string &id = "cloud");
00756         
00763         bool 
00764         setShapeRenderingProperties (int property, double value, 
00765                                      const std::string &id, int viewport = 0);
00766 
00775          bool
00776          setShapeRenderingProperties (int property, double val1, double val2, double val3,
00777                                       const std::string &id, int viewport = 0);
00778 
00779 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00780 
00781         bool 
00782         wasStopped () const { if (interactor_ != NULL) return (interactor_->stopped); else return true; }
00783 
00785         void 
00786         resetStoppedFlag () { if (interactor_ != NULL) interactor_->stopped = false; }
00787 #else
00788 
00789         bool 
00790         wasStopped () const { if (interactor_ != NULL) return (stopped_); else return (true); }
00791 
00793         void 
00794         resetStoppedFlag () { if (interactor_ != NULL) stopped_ = false; }
00795 #endif
00796 
00803         void 
00804         createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport);
00805 
00815         template <typename PointT> bool
00816         addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00817                     double r, double g, double b, 
00818                     const std::string &id = "polygon", int viewport = 0);
00819 
00826         template <typename PointT> bool
00827         addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
00828                     const std::string &id = "polygon", 
00829                     int viewport = 0);
00830 
00837         template <typename P1, typename P2> bool 
00838         addLine (const P1 &pt1, const P2 &pt2, const std::string &id = "line", 
00839                  int viewport = 0);
00840 
00850         template <typename P1, typename P2> bool 
00851         addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b, 
00852                  const std::string &id = "line", int viewport = 0);
00853 
00863         template <typename P1, typename P2> bool 
00864         addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, 
00865                   const std::string &id = "arrow", int viewport = 0);
00866 
00873         template <typename PointT> bool 
00874         addSphere (const PointT &center, double radius, const std::string &id = "sphere", 
00875                    int viewport = 0);
00876 
00886         template <typename PointT> bool 
00887         addSphere (const PointT &center, double radius, double r, double g, double b, 
00888                    const std::string &id = "sphere", int viewport = 0);
00889 
00895         bool
00896         addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata, 
00897                               const std::string & id = "PolyData", 
00898                               int viewport = 0);
00899 
00906         bool
00907         addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata, 
00908                               vtkSmartPointer<vtkTransform> transform,
00909                               const std::string &id = "PolyData", 
00910                               int viewport = 0);
00911 
00917         bool
00918         addModelFromPLYFile (const std::string &filename, 
00919                              const std::string &id = "PLYModel", 
00920                              int viewport = 0);
00921 
00928         bool
00929         addModelFromPLYFile (const std::string &filename, 
00930                              vtkSmartPointer<vtkTransform> transform,
00931                              const std::string &id = "PLYModel", 
00932                              int viewport = 0);
00933 
00960         bool 
00961         addCylinder (const pcl::ModelCoefficients &coefficients, 
00962                      const std::string &id = "cylinder", 
00963                      int viewport = 0);
00964 
00987         bool 
00988         addSphere (const pcl::ModelCoefficients &coefficients, 
00989                    const std::string &id = "sphere", 
00990                    int viewport = 0);
00991 
01015         bool 
01016         addLine (const pcl::ModelCoefficients &coefficients, 
01017                  const std::string &id = "line", 
01018                  int viewport = 0);
01019 
01040         bool 
01041         addPlane (const pcl::ModelCoefficients &coefficients, 
01042                   const std::string &id = "plane", 
01043                   int viewport = 0);
01044 
01064         bool 
01065         addCircle (const pcl::ModelCoefficients &coefficients, 
01066                    const std::string &id = "circle", 
01067                    int viewport = 0);
01068 
01074         bool 
01075         addCone (const pcl::ModelCoefficients &coefficients, 
01076                  const std::string &id = "cone", 
01077                  int viewport = 0);
01078 
01084         bool 
01085         addCube (const pcl::ModelCoefficients &coefficients, 
01086                  const std::string &id = "cube", 
01087                  int viewport = 0);
01088 
01090         void
01091         setRepresentationToSurfaceForAllActors ();
01092 
01100         void
01101         renderView (int xres, int yres, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
01102 
01120         void
01121         renderViewTesselatedSphere (
01122             int xres, int yres,
01123             std::vector<pcl::PointCloud<pcl::PointXYZ>,Eigen::aligned_allocator< pcl::PointCloud<pcl::PointXYZ> > > & cloud,
01124             std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies, int tesselation_level,
01125             float view_angle = 45, float radius_sphere = 1, bool use_vertices = true);
01126 
01128         Camera camera_;
01129 
01131         void 
01132         initCameraParameters ();
01133 
01138         bool 
01139         getCameraParameters (int argc, char **argv);
01140 
01142         bool 
01143         cameraParamsSet () const;
01144 
01146         void 
01147         updateCamera ();
01148 
01150         void 
01151         resetCamera ();
01152 
01156         void
01157         resetCameraViewpoint (const std::string &id = "cloud");
01158 
01167         void
01168         setCameraPosition (double posX,double posY, double posZ,
01169                            double viewX, double viewY, double viewZ);
01170 
01172         void
01173         getCameras (std::vector<Camera>& cameras);
01174         
01176         Eigen::Affine3f
01177         getViewerPose ();
01178 
01182         void
01183         saveScreenshot (const std::string &file);
01184 
01186         vtkSmartPointer<vtkRenderWindow> 
01187         getRenderWindow () 
01188         {
01189           return (win_);
01190         }
01191 
01193         void 
01194         createInteractor ();
01195 
01196       protected:
01198 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01199         vtkSmartPointer<PCLVisualizerInteractor> interactor_;
01200 #else
01201         vtkSmartPointer<vtkRenderWindowInteractor> interactor_;
01202 #endif
01203       private:
01204         struct ExitMainLoopTimerCallback : public vtkCommand
01205         {
01206           static ExitMainLoopTimerCallback* New()
01207           {
01208             return new ExitMainLoopTimerCallback;
01209           }
01210           virtual void Execute(vtkObject* vtkNotUsed(caller), unsigned long event_id, void* call_data)
01211           {
01212             if (event_id != vtkCommand::TimerEvent)
01213               return;
01214             int timer_id = *(int*)call_data;
01215             //PCL_WARN ("[pcl::visualization::PCLVisualizer::ExitMainLoopTimerCallback] Timer %d called.\n", timer_id);
01216             if (timer_id != right_timer_id)
01217               return;
01218             // Stop vtk loop and send notification to app to wake it up
01219 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01220             pcl_visualizer->interactor_->stopLoop ();
01221 #else
01222             pcl_visualizer->interactor_->TerminateApp ();
01223 #endif
01224           }
01225           int right_timer_id;
01226           PCLVisualizer* pcl_visualizer;
01227         };
01228         struct ExitCallback : public vtkCommand
01229         {
01230           static ExitCallback* New ()
01231           {
01232             return new ExitCallback;
01233           }
01234           virtual void Execute (vtkObject* caller, unsigned long event_id, void* call_data)
01235           {
01236             if (event_id != vtkCommand::ExitEvent)
01237               return;
01238 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01239             pcl_visualizer->interactor_->stopped = true;
01240             // This tends to close the window...
01241             pcl_visualizer->interactor_->stopLoop ();
01242 #else
01243             pcl_visualizer->stopped_ = true;
01244             // This tends to close the window...
01245             pcl_visualizer->interactor_->TerminateApp ();
01246 #endif
01247           }
01248           PCLVisualizer* pcl_visualizer;
01249         };
01250 
01251 #if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01252 
01253         bool stopped_;
01254 
01256         int timer_id_;
01257 #endif
01258 
01259         vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
01260         vtkSmartPointer<ExitCallback> exit_callback_;
01261 
01263         vtkSmartPointer<vtkRendererCollection> rens_;
01264 
01266         vtkSmartPointer<vtkRenderWindow> win_;
01267 
01269         vtkSmartPointer<PCLVisualizerInteractorStyle> style_;
01270 
01272         CloudActorMapPtr cloud_actor_map_;
01273 
01275         ShapeActorMapPtr shape_actor_map_;
01276 
01278         CoordinateActorMap coordinate_actor_map_;
01279 
01281         bool camera_set_;
01282         
01287         void 
01288         removeActorFromRenderer (const vtkSmartPointer<vtkLODActor> &actor, 
01289                                  int viewport = 0);
01290 
01295         void 
01296         addActorToRenderer (const vtkSmartPointer<vtkProp> &actor, 
01297                             int viewport = 0);
01298 
01303         void 
01304         removeActorFromRenderer (const vtkSmartPointer<vtkProp> &actor, 
01305                                  int viewport = 0);
01306 
01312         void 
01313         createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data, 
01314                                    vtkSmartPointer<vtkLODActor> &actor,
01315                                    bool use_scalars = true);
01316 
01323         template <typename PointT> void 
01324         convertPointCloudToVTKPolyData (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 
01325                                         vtkSmartPointer<vtkPolyData> &polydata,
01326                                         vtkSmartPointer<vtkIdTypeArray> &initcells);
01327 
01334         template <typename PointT> void 
01335         convertPointCloudToVTKPolyData (const PointCloudGeometryHandler<PointT> &geometry_handler, 
01336                                         vtkSmartPointer<vtkPolyData> &polydata,
01337                                         vtkSmartPointer<vtkIdTypeArray> &initcells);
01338 
01345         void 
01346         convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler, 
01347                                         vtkSmartPointer<vtkPolyData> &polydata,
01348                                         vtkSmartPointer<vtkIdTypeArray> &initcells);
01349 
01358         void 
01359         updateCells (vtkSmartPointer<vtkIdTypeArray> &cells, 
01360                      vtkSmartPointer<vtkIdTypeArray> &initcells,
01361                      vtkIdType nr_points);
01362 
01371         template <typename PointT> bool
01372         fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler,
01373                               const PointCloudColorHandler<PointT> &color_handler,
01374                               const std::string &id,
01375                               int viewport);
01376 
01385         template <typename PointT> bool
01386         fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler,
01387                               const ColorHandlerConstPtr &color_handler,
01388                               const std::string &id, 
01389                               int viewport);
01390 
01399         bool
01400         fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler,
01401                               const ColorHandlerConstPtr &color_handler,
01402                               const std::string &id, 
01403                               int viewport);
01404 
01413         template <typename PointT> bool
01414         fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler,
01415                               const PointCloudColorHandler<PointT> &color_handler,
01416                               const std::string &id, 
01417                               int viewport);
01418 
01422         void
01423         allocVtkPolyData (vtkSmartPointer<vtkAppendPolyData> &polydata);
01424 
01428         void
01429         allocVtkPolyData (vtkSmartPointer<vtkPolyData> &polydata);
01430 
01434         void
01435         allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata);
01436 
01442         void
01443         getTransformationMatrix (const Eigen::Vector4f &origin,
01444                                  const Eigen::Quaternion<float> &orientation,
01445                                  Eigen::Matrix4f &transformation);
01446 
01451         void
01452         convertToVtkMatrix (const Eigen::Matrix4f &m,
01453                             vtkSmartPointer<vtkMatrix4x4> &vtk_matrix);
01454 
01460         void
01461         convertToVtkMatrix (const Eigen::Vector4f &origin,
01462                             const Eigen::Quaternion<float> &orientation,
01463                             vtkSmartPointer<vtkMatrix4x4> &vtk_matrix);
01464 
01465     };
01466   }
01467 }
01468 
01469 #include <pcl/visualization/impl/pcl_visualizer.hpp>
01470 
01471 #endif
01472 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines