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 6220 2012-07-06 22:34:56Z 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 
00119         inline void
00120         setFullScreen (bool mode)
00121         {
00122           if (win_)
00123             win_->SetFullScreen (mode);
00124         }
00125 
00131         inline void
00132         setWindowBorders (bool mode)
00133         {
00134           if (win_)
00135             win_->SetBorders (mode);
00136         }
00137 
00142         boost::signals2::connection
00143         registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> cb);
00144 
00150         inline boost::signals2::connection
00151         registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*), void* cookie = NULL)
00152         {
00153           return (registerKeyboardCallback (boost::bind (callback, _1, cookie)));
00154         }
00155 
00162         template<typename T> inline boost::signals2::connection
00163         registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*), T& instance, void* cookie = NULL)
00164         {
00165           return (registerKeyboardCallback (boost::bind (callback,  boost::ref (instance), _1, cookie)));
00166         }
00167 
00172         boost::signals2::connection
00173         registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> cb);
00174 
00180         inline boost::signals2::connection
00181         registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*), void* cookie = NULL)
00182         {
00183           return (registerMouseCallback (boost::bind (callback, _1, cookie)));
00184         }
00185 
00192         template<typename T> inline boost::signals2::connection
00193         registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*), T& instance, void* cookie = NULL)
00194         {
00195           return (registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00196         }
00197 
00202         boost::signals2::connection
00203         registerPointPickingCallback (boost::function<void (const pcl::visualization::PointPickingEvent&)> cb);
00204 
00210         inline boost::signals2::connection
00211         registerPointPickingCallback (void (*callback) (const pcl::visualization::PointPickingEvent&, void*), void* cookie = NULL)
00212         {
00213           return (registerPointPickingCallback (boost::bind (callback, _1, cookie)));
00214         }
00215 
00222         template<typename T> inline boost::signals2::connection
00223         registerPointPickingCallback (void (T::*callback) (const pcl::visualization::PointPickingEvent&, void*), T& instance, void* cookie = NULL)
00224         {
00225           return (registerPointPickingCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00226         }
00227 
00229         void
00230         spin ();
00231 
00237         void
00238         spinOnce (int time = 1, bool force_redraw = false);
00239 
00244         void
00245         addCoordinateSystem (double scale = 1.0, int viewport = 0);
00246 
00254         void
00255         addCoordinateSystem (double scale, float x, float y, float z, int viewport = 0);
00256 
00288         void
00289         addCoordinateSystem (double scale, const Eigen::Affine3f& t, int viewport = 0);
00290 
00294         bool
00295         removeCoordinateSystem (int viewport = 0);
00296 
00303         bool
00304         removePointCloud (const std::string &id = "cloud", int viewport = 0);
00305 
00310         inline bool
00311         removePolygonMesh (const std::string &id = "polygon", int viewport = 0)
00312         {
00313           // Polygon Meshes are represented internally as point clouds with special cell array structures since 1.4
00314           return (removePointCloud (id, viewport));
00315         }
00316 
00322         bool
00323         removeShape (const std::string &id = "cloud", int viewport = 0);
00324 
00329         bool
00330         removeText3D (const std::string &id = "cloud", int viewport = 0);
00331 
00335         bool
00336         removeAllPointClouds (int viewport = 0);
00337 
00341         bool
00342         removeAllShapes (int viewport = 0);
00343 
00350         void
00351         setBackgroundColor (const double &r, const double &g, const double &b, int viewport = 0);
00352 
00360         bool
00361         addText (const std::string &text,
00362                  int xpos, int ypos,
00363                  const std::string &id = "", int viewport = 0);
00364 
00375         bool
00376         addText (const std::string &text, int xpos, int ypos, double r, double g, double b,
00377                  const std::string &id = "", int viewport = 0);
00378 
00390         bool
00391         addText (const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b,
00392                  const std::string &id = "", int viewport = 0);
00393 
00394 
00401         bool
00402         updateText (const std::string &text,
00403                     int xpos, int ypos,
00404                     const std::string &id = "");
00405 
00415         bool
00416         updateText (const std::string &text, 
00417                     int xpos, int ypos, double r, double g, double b,
00418                     const std::string &id = "");
00419 
00430         bool
00431         updateText (const std::string &text, 
00432                     int xpos, int ypos, int fontsize, double r, double g, double b,
00433                     const std::string &id = "");
00434 
00444         bool
00445         updateShapePose (const std::string &id, const Eigen::Affine3f& pose);
00446 
00457         template <typename PointT> bool
00458         addText3D (const std::string &text,
00459                    const PointT &position,
00460                    double textScale = 1.0,
00461                    double r = 1.0, double g = 1.0, double b = 1.0,
00462                    const std::string &id = "", int viewport = 0);
00463 
00471         template <typename PointNT> bool
00472         addPointCloudNormals (const typename pcl::PointCloud<PointNT>::ConstPtr &cloud,
00473                               int level = 100, double scale = 0.02,
00474                               const std::string &id = "cloud", int viewport = 0);
00475 
00484         template <typename PointT, typename PointNT> bool
00485         addPointCloudNormals (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00486                               const typename pcl::PointCloud<PointNT>::ConstPtr &normals,
00487                               int level = 100, double scale = 0.02,
00488                               const std::string &id = "cloud", int viewport = 0);
00489 
00499         bool
00500         addPointCloudPrincipalCurvatures (
00501             const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud,
00502             const pcl::PointCloud<pcl::Normal>::ConstPtr &normals,
00503             const pcl::PointCloud<pcl::PrincipalCurvatures>::ConstPtr &pcs,
00504             int level = 100, double scale = 1.0,
00505             const std::string &id = "cloud", int viewport = 0);
00506 
00512         template <typename PointT> bool
00513         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00514                        const std::string &id = "cloud", int viewport = 0);
00515 
00521         template <typename PointT> bool
00522         updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00523                           const std::string &id = "cloud");
00524 
00531         template <typename PointT> bool
00532         updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00533                           const PointCloudGeometryHandler<PointT> &geometry_handler,
00534                           const std::string &id = "cloud");
00535 
00542         template <typename PointT> bool
00543         updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00544                           const PointCloudColorHandler<PointT> &color_handler,
00545                           const std::string &id = "cloud");
00546 
00547 //        bool
00548 //        updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud,
00549 //                          const PointCloudColorHandlerRGBField<pcl::PointXYZRGB> &color_handler,
00550 //                          const std::string &id = "cloud");
00551 
00558         template <typename PointT> bool
00559         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00560                        const PointCloudGeometryHandler<PointT> &geometry_handler,
00561                        const std::string &id = "cloud", int viewport = 0);
00562 
00575         template <typename PointT> bool
00576         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00577                        const GeometryHandlerConstPtr &geometry_handler,
00578                        const std::string &id = "cloud", int viewport = 0);
00579 
00586         template <typename PointT> bool
00587         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00588                        const PointCloudColorHandler<PointT> &color_handler,
00589                        const std::string &id = "cloud", int viewport = 0);
00590 
00603         template <typename PointT> bool
00604         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00605                        const ColorHandlerConstPtr &color_handler,
00606                        const std::string &id = "cloud", int viewport = 0);
00607 
00621         template <typename PointT> bool
00622         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00623                        const GeometryHandlerConstPtr &geometry_handler,
00624                        const ColorHandlerConstPtr &color_handler,
00625                        const std::string &id = "cloud", int viewport = 0);
00626 
00642         bool
00643         addPointCloud (const sensor_msgs::PointCloud2::ConstPtr &cloud,
00644                        const GeometryHandlerConstPtr &geometry_handler,
00645                        const ColorHandlerConstPtr &color_handler,
00646                        const Eigen::Vector4f& sensor_origin,
00647                        const Eigen::Quaternion<float>& sensor_orientation,
00648                        const std::string &id = "cloud", int viewport = 0);
00649 
00664         bool
00665         addPointCloud (const sensor_msgs::PointCloud2::ConstPtr &cloud,
00666                        const GeometryHandlerConstPtr &geometry_handler,
00667                        const Eigen::Vector4f& sensor_origin,
00668                        const Eigen::Quaternion<float>& sensor_orientation,
00669                        const std::string &id = "cloud", int viewport = 0);
00670 
00685         bool
00686         addPointCloud (const sensor_msgs::PointCloud2::ConstPtr &cloud,
00687                        const ColorHandlerConstPtr &color_handler,
00688                        const Eigen::Vector4f& sensor_origin,
00689                        const Eigen::Quaternion<float>& sensor_orientation,
00690                        const std::string &id = "cloud", int viewport = 0);
00691 
00699         template <typename PointT> bool
00700         addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00701                        const PointCloudColorHandler<PointT> &color_handler,
00702                        const PointCloudGeometryHandler<PointT> &geometry_handler,
00703                        const std::string &id = "cloud", int viewport = 0);
00704 
00710         inline bool
00711         addPointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud,
00712                        const std::string &id = "cloud", int viewport = 0)
00713         {
00714           return (addPointCloud<pcl::PointXYZ> (cloud, id, viewport));
00715         }
00716 
00717 
00723         inline bool
00724         addPointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud,
00725                        const std::string &id = "cloud", int viewport = 0)
00726         {
00727           pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud);
00728           return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler, id, viewport));
00729         }
00730 
00736         inline bool
00737         addPointCloud (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud,
00738                        const std::string &id = "cloud", int viewport = 0)
00739         {
00740           pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> color_handler (cloud);
00741           return (addPointCloud<pcl::PointXYZRGBA> (cloud, color_handler, id, viewport));
00742         }
00743 
00749         inline bool
00750         updatePointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud,
00751                           const std::string &id = "cloud")
00752         {
00753           return (updatePointCloud<pcl::PointXYZ> (cloud, id));
00754         }
00755 
00761         inline bool
00762         updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud,
00763                           const std::string &id = "cloud")
00764         {
00765           pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud);
00766           return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler, id));
00767         }
00768 
00774         inline bool
00775         updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud,
00776                           const std::string &id = "cloud")
00777         {
00778           pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> color_handler (cloud);
00779           return (updatePointCloud<pcl::PointXYZRGBA> (cloud, color_handler, id));
00780         }
00781 
00787         bool
00788         addPolygonMesh (const pcl::PolygonMesh &polymesh,
00789                         const std::string &id = "polygon",
00790                         int viewport = 0);
00791 
00798         template <typename PointT> bool
00799         addPolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00800                         const std::vector<pcl::Vertices> &vertices,
00801                         const std::string &id = "polygon",
00802                         int viewport = 0);
00803 
00810         template <typename PointT> bool
00811         updatePolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00812                            const std::vector<pcl::Vertices> &vertices,
00813                            const std::string &id = "polygon");
00814 
00820         bool
00821         addPolylineFromPolygonMesh (const pcl::PolygonMesh &polymesh,
00822                                     const std::string &id = "polyline",
00823                                     int viewport = 0);
00824 
00832         template <typename PointT> bool
00833         addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
00834                             const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
00835                             const std::vector<int> & correspondences,
00836                             const std::string &id = "correspondences",
00837                             int viewport = 0);
00838 
00846         template <typename PointT> bool
00847         addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
00848                             const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
00849                             const pcl::Correspondences &correspondences,
00850                             const std::string &id = "correspondences",
00851                             int viewport = 0);
00852 
00857         inline void
00858         removeCorrespondences (const std::string &id = "correspondences", int viewport = 0)
00859         {
00860           removeShape (id, viewport);
00861         }
00862 
00866         inline int
00867         getColorHandlerIndex (const std::string &id)
00868         {
00869           CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id);
00870           if (am_it == cloud_actor_map_->end ())
00871             return (-1);
00872 
00873           return (am_it->second.color_handler_index_);
00874         }
00875 
00879         inline int
00880         getGeometryHandlerIndex (const std::string &id)
00881         {
00882           CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id);
00883           if (am_it != cloud_actor_map_->end ())
00884             return (-1);
00885 
00886           return (am_it->second.geometry_handler_index_);
00887         }
00888 
00893         bool
00894         updateColorHandlerIndex (const std::string &id, int index);
00895 
00904         bool
00905         setPointCloudRenderingProperties (int property, double val1, double val2, double val3,
00906                                           const std::string &id = "cloud", int viewport = 0);
00907 
00914         bool
00915         setPointCloudRenderingProperties (int property, double value,
00916                                           const std::string &id = "cloud", int viewport = 0);
00917 
00923         bool
00924         getPointCloudRenderingProperties (int property, double &value,
00925                                           const std::string &id = "cloud");
00926 
00933         bool
00934         setShapeRenderingProperties (int property, double value,
00935                                      const std::string &id, int viewport = 0);
00936 
00945          bool
00946          setShapeRenderingProperties (int property, double val1, double val2, double val3,
00947                                       const std::string &id, int viewport = 0);
00948 
00949 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00950 
00951         bool
00952         wasStopped () const { if (interactor_ != NULL) return (interactor_->stopped); else return true; }
00953 
00955         void
00956         resetStoppedFlag () { if (interactor_ != NULL) interactor_->stopped = false; }
00957 #else
00958 
00959         bool
00960         wasStopped () const { if (interactor_ != NULL) return (stopped_); else return (true); }
00961 
00963         void
00964         resetStoppedFlag () { if (interactor_ != NULL) stopped_ = false; }
00965 #endif
00966 
00968         void
00969         close ()
00970         {
00971 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00972           interactor_->stopped = true;
00973           // This tends to close the window...
00974           interactor_->stopLoop ();
00975 #else
00976           stopped_ = true;
00977           // This tends to close the window...
00978           interactor_->TerminateApp ();
00979 #endif
00980         }
00981 
00993         void
00994         createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport);
00995 
01005         template <typename PointT> bool
01006         addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
01007                     double r, double g, double b,
01008                     const std::string &id = "polygon", int viewport = 0);
01009 
01016         template <typename PointT> bool
01017         addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
01018                     const std::string &id = "polygon",
01019                     int viewport = 0);
01020 
01027         template <typename P1, typename P2> bool
01028         addLine (const P1 &pt1, const P2 &pt2, const std::string &id = "line",
01029                  int viewport = 0);
01030 
01040         template <typename P1, typename P2> bool
01041         addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b,
01042                  const std::string &id = "line", int viewport = 0);
01043 
01053         template <typename P1, typename P2> bool
01054         addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b,
01055                   const std::string &id = "arrow", int viewport = 0);
01056 
01067         template <typename P1, typename P2> bool
01068         addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, bool display_length,
01069                   const std::string &id = "arrow", int viewport = 0);
01070 
01077         template <typename PointT> bool
01078         addSphere (const PointT &center, double radius, const std::string &id = "sphere",
01079                    int viewport = 0);
01080 
01090         template <typename PointT> bool
01091         addSphere (const PointT &center, double radius, double r, double g, double b,
01092                    const std::string &id = "sphere", int viewport = 0);
01093 
01102         template <typename PointT> bool
01103         updateSphere (const PointT &center, double radius, double r, double g, double b,
01104                       const std::string &id = "sphere");
01105 
01111         bool
01112         addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata,
01113                               const std::string & id = "PolyData",
01114                               int viewport = 0);
01115 
01122         bool
01123         addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata,
01124                               vtkSmartPointer<vtkTransform> transform,
01125                               const std::string &id = "PolyData",
01126                               int viewport = 0);
01127 
01133         bool
01134         addModelFromPLYFile (const std::string &filename,
01135                              const std::string &id = "PLYModel",
01136                              int viewport = 0);
01137 
01144         bool
01145         addModelFromPLYFile (const std::string &filename,
01146                              vtkSmartPointer<vtkTransform> transform,
01147                              const std::string &id = "PLYModel",
01148                              int viewport = 0);
01149 
01176         bool
01177         addCylinder (const pcl::ModelCoefficients &coefficients,
01178                      const std::string &id = "cylinder",
01179                      int viewport = 0);
01180 
01203         bool
01204         addSphere (const pcl::ModelCoefficients &coefficients,
01205                    const std::string &id = "sphere",
01206                    int viewport = 0);
01207 
01231         bool
01232         addLine (const pcl::ModelCoefficients &coefficients,
01233                  const std::string &id = "line",
01234                  int viewport = 0);
01235 
01256         bool
01257         addPlane (const pcl::ModelCoefficients &coefficients,
01258                   const std::string &id = "plane",
01259                   int viewport = 0);
01260 
01280         bool
01281         addCircle (const pcl::ModelCoefficients &coefficients,
01282                    const std::string &id = "circle",
01283                    int viewport = 0);
01284 
01290         bool
01291         addCone (const pcl::ModelCoefficients &coefficients,
01292                  const std::string &id = "cone",
01293                  int viewport = 0);
01294 
01300         bool
01301         addCube (const pcl::ModelCoefficients &coefficients,
01302                  const std::string &id = "cube",
01303                  int viewport = 0);
01304 
01314         bool
01315         addCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation,
01316                  double width, double height, double depth,
01317                  const std::string &id = "cube",
01318                  int viewport = 0);
01319         
01333         bool
01334         addCube (double x_min, double x_max,
01335                  double y_min, double y_max,
01336                  double z_min, double z_max,
01337                  double r = 1.0, double g = 1.0, double b = 1.0,
01338                  const std::string &id = "cube",
01339                  int viewport = 0);
01340 
01342         void
01343         setRepresentationToSurfaceForAllActors ();
01344 
01346         void
01347         setRepresentationToPointsForAllActors ();
01348 
01350         void
01351         setRepresentationToWireframeForAllActors ();
01352 
01360         void
01361         renderView (int xres, int yres, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
01362 
01380         void
01381         renderViewTesselatedSphere (
01382             int xres, int yres,
01383             std::vector<pcl::PointCloud<pcl::PointXYZ>,Eigen::aligned_allocator< pcl::PointCloud<pcl::PointXYZ> > > & cloud,
01384             std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies, int tesselation_level,
01385             float view_angle = 45, float radius_sphere = 1, bool use_vertices = true);
01386 
01388         Camera camera_;
01389 
01391         void
01392         initCameraParameters ();
01393 
01398         bool
01399         getCameraParameters (int argc, char **argv);
01400 
01402         bool
01403         cameraParamsSet () const;
01404 
01406         void
01407         updateCamera ();
01408 
01410         void
01411         resetCamera ();
01412 
01416         void
01417         resetCameraViewpoint (const std::string &id = "cloud");
01418 
01431         void
01432         setCameraPose (double posX, double posY, double posZ,
01433                        double viewX, double viewY, double viewZ,
01434                        double upX, double upY, double upZ, int viewport = 0);
01435 
01445         void
01446         setCameraPosition (double posX,double posY, double posZ,
01447                            double viewX, double viewY, double viewZ, int viewport = 0);
01448 
01450         void
01451         getCameras (std::vector<Camera>& cameras);
01452 
01454         Eigen::Affine3f
01455         getViewerPose ();
01456 
01460         void
01461         saveScreenshot (const std::string &file);
01462 
01464         vtkSmartPointer<vtkRenderWindow>
01465         getRenderWindow ()
01466         {
01467           return (win_);
01468         }
01469 
01471         void
01472         createInteractor ();
01473 
01479         void
01480         setupInteractor (vtkRenderWindowInteractor *iren,
01481                          vtkRenderWindow *win);
01482 
01484         inline vtkSmartPointer<PCLVisualizerInteractorStyle>
01485         getInteractorStyle ()
01486         {
01487           return (style_);
01488         }
01489       protected:
01491 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01492         vtkSmartPointer<PCLVisualizerInteractor> interactor_;
01493 #else
01494         vtkSmartPointer<vtkRenderWindowInteractor> interactor_;
01495 #endif
01496       private:
01497         struct ExitMainLoopTimerCallback : public vtkCommand
01498         {
01499           static ExitMainLoopTimerCallback* New()
01500           {
01501             return new ExitMainLoopTimerCallback;
01502           }
01503           virtual void Execute(vtkObject* vtkNotUsed(caller), unsigned long event_id, void* call_data)
01504           {
01505             if (event_id != vtkCommand::TimerEvent)
01506               return;
01507             int timer_id = *(int*)call_data;
01508             //PCL_WARN ("[pcl::visualization::PCLVisualizer::ExitMainLoopTimerCallback] Timer %d called.\n", timer_id);
01509             if (timer_id != right_timer_id)
01510               return;
01511             // Stop vtk loop and send notification to app to wake it up
01512 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01513             pcl_visualizer->interactor_->stopLoop ();
01514 #else
01515             pcl_visualizer->interactor_->TerminateApp ();
01516 #endif
01517           }
01518           int right_timer_id;
01519           PCLVisualizer* pcl_visualizer;
01520         };
01521         struct ExitCallback : public vtkCommand
01522         {
01523           static ExitCallback* New ()
01524           {
01525             return new ExitCallback;
01526           }
01527           virtual void Execute (vtkObject* caller, unsigned long event_id, void* call_data)
01528           {
01529             if (event_id != vtkCommand::ExitEvent)
01530               return;
01531 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01532             pcl_visualizer->interactor_->stopped = true;
01533             // This tends to close the window...
01534             pcl_visualizer->interactor_->stopLoop ();
01535 #else
01536             pcl_visualizer->stopped_ = true;
01537             // This tends to close the window...
01538             pcl_visualizer->interactor_->TerminateApp ();
01539 #endif
01540           }
01541           PCLVisualizer* pcl_visualizer;
01542         };
01543 
01544 #if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01545 
01546         bool stopped_;
01547 
01549         int timer_id_;
01550 #endif
01551 
01552         vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
01553         vtkSmartPointer<ExitCallback> exit_callback_;
01554 
01556         vtkSmartPointer<vtkRendererCollection> rens_;
01557 
01559         vtkSmartPointer<vtkRenderWindow> win_;
01560 
01562         vtkSmartPointer<PCLVisualizerInteractorStyle> style_;
01563 
01565         CloudActorMapPtr cloud_actor_map_;
01566 
01568         ShapeActorMapPtr shape_actor_map_;
01569 
01571         CoordinateActorMap coordinate_actor_map_;
01572 
01574         bool camera_set_;
01575 
01580         bool
01581         removeActorFromRenderer (const vtkSmartPointer<vtkLODActor> &actor,
01582                                  int viewport = 0);
01583 
01588         void
01589         addActorToRenderer (const vtkSmartPointer<vtkProp> &actor,
01590                             int viewport = 0);
01591 
01596         bool
01597         removeActorFromRenderer (const vtkSmartPointer<vtkProp> &actor,
01598                                  int viewport = 0);
01599 
01605         void
01606         createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data,
01607                                    vtkSmartPointer<vtkLODActor> &actor,
01608                                    bool use_scalars = true);
01609 
01616         template <typename PointT> void
01617         convertPointCloudToVTKPolyData (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
01618                                         vtkSmartPointer<vtkPolyData> &polydata,
01619                                         vtkSmartPointer<vtkIdTypeArray> &initcells);
01620 
01627         template <typename PointT> void
01628         convertPointCloudToVTKPolyData (const PointCloudGeometryHandler<PointT> &geometry_handler,
01629                                         vtkSmartPointer<vtkPolyData> &polydata,
01630                                         vtkSmartPointer<vtkIdTypeArray> &initcells);
01631 
01638         void
01639         convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler,
01640                                         vtkSmartPointer<vtkPolyData> &polydata,
01641                                         vtkSmartPointer<vtkIdTypeArray> &initcells);
01642 
01651         void
01652         updateCells (vtkSmartPointer<vtkIdTypeArray> &cells,
01653                      vtkSmartPointer<vtkIdTypeArray> &initcells,
01654                      vtkIdType nr_points);
01655 
01666         template <typename PointT> bool
01667         fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler,
01668                               const PointCloudColorHandler<PointT> &color_handler,
01669                               const std::string &id,
01670                               int viewport,
01671                               const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
01672                               const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
01673 
01684         template <typename PointT> bool
01685         fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler,
01686                               const ColorHandlerConstPtr &color_handler,
01687                               const std::string &id,
01688                               int viewport,
01689                               const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
01690                               const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
01691 
01702         bool
01703         fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler,
01704                               const ColorHandlerConstPtr &color_handler,
01705                               const std::string &id,
01706                               int viewport,
01707                               const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
01708                               const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
01709 
01720         template <typename PointT> bool
01721         fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler,
01722                               const PointCloudColorHandler<PointT> &color_handler,
01723                               const std::string &id,
01724                               int viewport,
01725                               const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
01726                               const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
01727 
01731         void
01732         allocVtkPolyData (vtkSmartPointer<vtkAppendPolyData> &polydata);
01733 
01737         void
01738         allocVtkPolyData (vtkSmartPointer<vtkPolyData> &polydata);
01739 
01743         void
01744         allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata);
01745 
01751         void
01752         getTransformationMatrix (const Eigen::Vector4f &origin,
01753                                  const Eigen::Quaternion<float> &orientation,
01754                                  Eigen::Matrix4f &transformation);
01755 
01760         void
01761         convertToVtkMatrix (const Eigen::Matrix4f &m,
01762                             vtkSmartPointer<vtkMatrix4x4> &vtk_matrix);
01763 
01769         void
01770         convertToVtkMatrix (const Eigen::Vector4f &origin,
01771                             const Eigen::Quaternion<float> &orientation,
01772                             vtkSmartPointer<vtkMatrix4x4> &vtk_matrix);
01773 
01774     };
01775   }
01776 }
01777 
01778 #include <pcl/visualization/impl/pcl_visualizer.hpp>
01779 
01780 #endif
01781 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:28