Point Cloud Library (PCL)
1.3.1
|
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 3000 2011-10-31 22:57:26Z 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&)>); 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&)>); 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&)>); 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 00265 void 00266 addCoordinateSystem (double scale, const Eigen::Matrix4f& t, int viewport = 0); 00267 00271 bool 00272 removeCoordinateSystem (int viewport = 0); 00273 00278 bool 00279 removePointCloud (const std::string &id = "cloud", int viewport = 0); 00280 00285 bool 00286 removeShape (const std::string &id = "cloud", int viewport = 0); 00287 00292 bool 00293 removeText3D (const std::string &id = "cloud", int viewport = 0); 00294 00298 bool 00299 removeAllPointClouds (int viewport = 0); 00300 00304 bool 00305 removeAllShapes (int viewport = 0); 00306 00313 void 00314 setBackgroundColor (const double &r, const double &g, const double &b, int viewport = 0); 00315 00323 bool 00324 addText (const std::string &text, 00325 int xpos, int ypos, 00326 const std::string &id = "", int viewport = 0); 00327 00338 bool 00339 addText (const std::string &text, int xpos, int ypos, double r, double g, double b, 00340 const std::string &id = "", int viewport = 0); 00341 00353 bool 00354 addText (const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b, 00355 const std::string &id = "", int viewport = 0); 00356 00357 00368 template <typename PointT> bool 00369 addText3D (const std::string &text, 00370 const PointT &position, 00371 double textScale = 1.0, 00372 double r = 1.0, double g = 1.0, double b = 1.0, 00373 const std::string &id = "", int viewport = 0); 00374 00382 template <typename PointNT> bool 00383 addPointCloudNormals (const typename pcl::PointCloud<PointNT>::ConstPtr &cloud, 00384 int level = 100, double scale = 0.02, 00385 const std::string &id = "cloud", int viewport = 0); 00386 00395 template <typename PointT, typename PointNT> bool 00396 addPointCloudNormals (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00397 const typename pcl::PointCloud<PointNT>::ConstPtr &normals, 00398 int level = 100, double scale = 0.02, 00399 const std::string &id = "cloud", int viewport = 0); 00400 00410 bool 00411 addPointCloudPrincipalCurvatures ( 00412 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 00413 const pcl::PointCloud<pcl::Normal>::ConstPtr &normals, 00414 const pcl::PointCloud<pcl::PrincipalCurvatures>::ConstPtr &pcs, 00415 int level = 100, double scale = 1.0, 00416 const std::string &id = "cloud", int viewport = 0); 00417 00423 template <typename PointT> bool 00424 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00425 const std::string &id = "cloud", int viewport = 0); 00426 00432 template <typename PointT> bool 00433 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00434 const std::string &id = "cloud"); 00435 00441 template <typename PointT> bool 00442 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00443 const PointCloudGeometryHandler<PointT> &geometry_handler, 00444 const std::string &id = "cloud"); 00445 00452 template <typename PointT> bool 00453 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00454 const PointCloudColorHandler<PointT> &color_handler, 00455 const std::string &id = "cloud"); 00456 00457 // /** \brief Updates the XYZRGB data for an existing cloud object id on screen. 00458 // * \param cloud the input point cloud dataset 00459 // * \param color_handler the RGB color handler to use 00460 // * \param id the point cloud object id to update (default: cloud) 00461 // * \return false if no cloud with the specified ID was found 00462 // */ 00463 // bool 00464 // updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 00465 // const PointCloudColorHandlerRGBField<pcl::PointXYZRGB> &color_handler, 00466 // const std::string &id = "cloud"); 00467 00474 template <typename PointT> bool 00475 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00476 const PointCloudGeometryHandler<PointT> &geometry_handler, 00477 const std::string &id = "cloud", int viewport = 0); 00478 00491 template <typename PointT> bool 00492 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00493 const GeometryHandlerConstPtr &geometry_handler, 00494 const std::string &id = "cloud", int viewport = 0); 00495 00502 template <typename PointT> bool 00503 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00504 const PointCloudColorHandler<PointT> &color_handler, 00505 const std::string &id = "cloud", int viewport = 0); 00506 00519 template <typename PointT> bool 00520 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00521 const ColorHandlerConstPtr &color_handler, 00522 const std::string &id = "cloud", int viewport = 0); 00523 00537 template <typename PointT> bool 00538 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00539 const GeometryHandlerConstPtr &geometry_handler, 00540 const ColorHandlerConstPtr &color_handler, 00541 const std::string &id = "cloud", int viewport = 0); 00542 00550 template <typename PointT> bool 00551 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00552 const PointCloudColorHandler<PointT> &color_handler, 00553 const PointCloudGeometryHandler<PointT> &geometry_handler, 00554 const std::string &id = "cloud", int viewport = 0); 00555 00561 inline bool 00562 addPointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 00563 const std::string &id = "cloud", int viewport = 0) 00564 { 00565 return (addPointCloud<pcl::PointXYZ> (cloud, id, viewport)); 00566 } 00567 00568 00574 inline bool 00575 addPointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 00576 const std::string &id = "cloud", int viewport = 0) 00577 { 00578 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud); 00579 return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler, id, viewport)); 00580 } 00581 00587 inline bool 00588 updatePointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 00589 const std::string &id = "cloud") 00590 { 00591 return (updatePointCloud<pcl::PointXYZ> (cloud, id)); 00592 } 00593 00599 inline bool 00600 updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 00601 const std::string &id = "cloud") 00602 { 00603 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud); 00604 return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler, id)); 00605 } 00606 00612 bool 00613 addPolygonMesh (const pcl::PolygonMesh &polymesh, 00614 const std::string &id = "polygon", 00615 int viewport = 0); 00616 00623 template <typename PointT> bool 00624 addPolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00625 const std::vector<pcl::Vertices> &vertices, 00626 const std::string &id = "polygon", 00627 int viewport = 0); 00628 00634 bool 00635 addPolylineFromPolygonMesh (const pcl::PolygonMesh &polymesh, 00636 const std::string &id = "polyline", 00637 int viewport = 0); 00638 00647 template <typename PointT> bool 00648 addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points, 00649 const typename pcl::PointCloud<PointT>::ConstPtr &target_points, 00650 const std::vector<int> & correspondences, 00651 const std::string &id = "correspondences", 00652 int viewport = 0); 00653 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 pcl::Correspondences &correspondences, 00666 const std::string &id = "correspondences", 00667 int viewport = 0); 00668 00673 inline void 00674 removeCorrespondences (const std::string &id = "correspondences", int viewport = 0) 00675 { 00676 removeShape (id, viewport); 00677 } 00678 00682 inline int 00683 getColorHandlerIndex (const std::string &id) 00684 { 00685 CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id); 00686 if (am_it == cloud_actor_map_->end ()) 00687 return (-1); 00688 00689 return (am_it->second.color_handler_index_); 00690 } 00691 00695 inline int 00696 getGeometryHandlerIndex (const std::string &id) 00697 { 00698 CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id); 00699 if (am_it != cloud_actor_map_->end ()) 00700 return (-1); 00701 00702 return (am_it->second.geometry_handler_index_); 00703 } 00704 00709 bool 00710 updateColorHandlerIndex (const std::string &id, int index); 00711 00720 bool 00721 setPointCloudRenderingProperties (int property, double val1, double val2, double val3, 00722 const std::string &id = "cloud", int viewport = 0); 00723 00730 bool 00731 setPointCloudRenderingProperties (int property, double value, 00732 const std::string &id = "cloud", int viewport = 0); 00733 00739 bool 00740 getPointCloudRenderingProperties (int property, double &value, 00741 const std::string &id = "cloud"); 00742 00749 bool 00750 setShapeRenderingProperties (int property, double value, 00751 const std::string &id, int viewport = 0); 00752 00761 bool 00762 setShapeRenderingProperties (int property, double val1, double val2, double val3, 00763 const std::string &id, int viewport = 0); 00764 00765 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 00766 00767 bool 00768 wasStopped () const { if (interactor_ != NULL) return (interactor_->stopped); else return true; } 00769 00771 void 00772 resetStoppedFlag () { if (interactor_ != NULL) interactor_->stopped = false; } 00773 #else 00774 00775 bool 00776 wasStopped () const { if (interactor_ != NULL) return (stopped_); else return (true); } 00777 00779 void 00780 resetStoppedFlag () { if (interactor_ != NULL) stopped_ = false; } 00781 #endif 00782 00789 void 00790 createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport); 00791 00801 template <typename PointT> bool 00802 addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00803 double r, double g, double b, 00804 const std::string &id = "polygon", int viewport = 0); 00805 00812 template <typename PointT> bool 00813 addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00814 const std::string &id = "polygon", 00815 int viewport = 0); 00816 00823 template <typename P1, typename P2> bool 00824 addLine (const P1 &pt1, const P2 &pt2, const std::string &id = "line", 00825 int viewport = 0); 00826 00836 template <typename P1, typename P2> bool 00837 addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b, 00838 const std::string &id = "line", int viewport = 0); 00839 00849 template <typename P1, typename P2> bool 00850 addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, 00851 const std::string &id = "arrow", int viewport = 0); 00852 00859 template <typename PointT> bool 00860 addSphere (const PointT ¢er, double radius, const std::string &id = "sphere", 00861 int viewport = 0); 00862 00872 template <typename PointT> bool 00873 addSphere (const PointT ¢er, double radius, double r, double g, double b, 00874 const std::string &id = "sphere", int viewport = 0); 00875 00882 bool 00883 addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata, 00884 const std::string & id = "PolyData", 00885 int viewport = 0); 00886 00894 bool 00895 addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata, 00896 vtkSmartPointer<vtkTransform> transform, 00897 const std::string &id = "PolyData", 00898 int viewport = 0); 00899 00906 bool 00907 addModelFromPLYFile (const std::string &filename, 00908 const std::string &id = "PLYModel", 00909 int viewport = 0); 00910 00918 bool 00919 addModelFromPLYFile (const std::string &filename, 00920 vtkSmartPointer<vtkTransform> transform, 00921 const std::string &id = "PLYModel", 00922 int viewport = 0); 00923 00950 bool 00951 addCylinder (const pcl::ModelCoefficients &coefficients, 00952 const std::string &id = "cylinder", 00953 int viewport = 0); 00954 00977 bool 00978 addSphere (const pcl::ModelCoefficients &coefficients, 00979 const std::string &id = "sphere", 00980 int viewport = 0); 00981 01005 bool 01006 addLine (const pcl::ModelCoefficients &coefficients, 01007 const std::string &id = "line", 01008 int viewport = 0); 01009 01030 bool 01031 addPlane (const pcl::ModelCoefficients &coefficients, 01032 const std::string &id = "plane", 01033 int viewport = 0); 01034 01054 bool 01055 addCircle (const pcl::ModelCoefficients &coefficients, 01056 const std::string &id = "circle", 01057 int viewport = 0); 01058 01064 bool 01065 addCone (const pcl::ModelCoefficients &coefficients, 01066 const std::string &id = "cone", 01067 int viewport = 0); 01068 01074 bool 01075 addCube (const pcl::ModelCoefficients &coefficients, 01076 const std::string &id = "cube", 01077 int viewport = 0); 01078 01080 void 01081 setRepresentationToSurfaceForAllActors (); 01082 01089 void 01090 renderView (int xres, int yres, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud); 01091 01106 void 01107 renderViewTesselatedSphere ( 01108 int xres, int yres, 01109 std::vector<pcl::PointCloud<pcl::PointXYZ>,Eigen::aligned_allocator< pcl::PointCloud<pcl::PointXYZ> > > & cloud, 01110 std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies, int tesselation_level, 01111 float view_angle = 45, float radius_sphere = 1, bool use_vertices = true); 01112 01114 Camera camera_; 01115 01117 void 01118 initCameraParameters (); 01119 01124 bool 01125 getCameraParameters (int argc, char **argv); 01126 01128 bool 01129 cameraParamsSet() const; 01130 01132 void 01133 updateCamera (); 01134 01136 void 01137 resetCamera (); 01138 01142 void 01143 resetCameraViewpoint (const std::string &id = "cloud"); 01144 01153 void 01154 setCameraPosition (double posX,double posY, double posZ, 01155 double viewX, double viewY, double viewZ); 01156 01158 void 01159 getCameras (std::vector<Camera>& cameras); 01160 01162 Eigen::Affine3f 01163 getViewerPose (); 01164 01168 void 01169 saveScreenshot (const std::string &file); 01170 01172 vtkSmartPointer<vtkRenderWindow> 01173 getRenderWindow () 01174 { 01175 return (win_); 01176 } 01177 01179 void 01180 createInteractor (); 01181 01182 protected: 01184 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 01185 vtkSmartPointer<PCLVisualizerInteractor> interactor_; 01186 #else 01187 vtkSmartPointer<vtkRenderWindowInteractor> interactor_; 01188 #endif 01189 private: 01190 struct ExitMainLoopTimerCallback : public vtkCommand 01191 { 01192 static ExitMainLoopTimerCallback* New() 01193 { 01194 return new ExitMainLoopTimerCallback; 01195 } 01196 virtual void Execute(vtkObject* vtkNotUsed(caller), unsigned long event_id, void* call_data) 01197 { 01198 if (event_id != vtkCommand::TimerEvent) 01199 return; 01200 int timer_id = *(int*)call_data; 01201 //PCL_WARN ("[pcl::visualization::PCLVisualizer::ExitMainLoopTimerCallback] Timer %d called.\n", timer_id); 01202 if (timer_id != right_timer_id) 01203 return; 01204 // Stop vtk loop and send notification to app to wake it up 01205 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 01206 pcl_visualizer->interactor_->stopLoop (); 01207 #else 01208 pcl_visualizer->interactor_->TerminateApp (); 01209 #endif 01210 } 01211 int right_timer_id; 01212 PCLVisualizer* pcl_visualizer; 01213 }; 01214 struct ExitCallback : public vtkCommand 01215 { 01216 static ExitCallback* New () 01217 { 01218 return new ExitCallback; 01219 } 01220 virtual void Execute (vtkObject* caller, unsigned long event_id, void* call_data) 01221 { 01222 if (event_id != vtkCommand::ExitEvent) 01223 return; 01224 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 01225 pcl_visualizer->interactor_->stopped = true; 01226 // This tends to close the window... 01227 pcl_visualizer->interactor_->stopLoop (); 01228 #else 01229 pcl_visualizer->stopped_ = true; 01230 // This tends to close the window... 01231 pcl_visualizer->interactor_->TerminateApp (); 01232 #endif 01233 } 01234 PCLVisualizer* pcl_visualizer; 01235 }; 01236 01237 #if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 01238 01239 bool stopped_; 01240 01242 int timer_id_; 01243 #endif 01244 01245 vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_; 01246 vtkSmartPointer<ExitCallback> exit_callback_; 01247 01249 vtkSmartPointer<vtkRendererCollection> rens_; 01250 01252 vtkSmartPointer<vtkRenderWindow> win_; 01253 01255 vtkSmartPointer<PCLVisualizerInteractorStyle> style_; 01256 01258 CloudActorMapPtr cloud_actor_map_; 01259 01261 ShapeActorMapPtr shape_actor_map_; 01262 01264 CoordinateActorMap coordinate_actor_map_; 01265 01267 bool camera_set_; 01268 01273 void 01274 removeActorFromRenderer (const vtkSmartPointer<vtkLODActor> &actor, 01275 int viewport = 0); 01276 01281 void 01282 addActorToRenderer (const vtkSmartPointer<vtkProp> &actor, 01283 int viewport = 0); 01284 01289 void 01290 removeActorFromRenderer (const vtkSmartPointer<vtkProp> &actor, 01291 int viewport = 0); 01292 01297 void 01298 createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data, 01299 vtkSmartPointer<vtkLODActor> &actor); 01300 01307 template <typename PointT> void 01308 convertPointCloudToVTKPolyData (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 01309 vtkSmartPointer<vtkPolyData> &polydata, 01310 vtkSmartPointer<vtkIdTypeArray> &initcells); 01311 01318 template <typename PointT> void 01319 convertPointCloudToVTKPolyData (const PointCloudGeometryHandler<PointT> &geometry_handler, 01320 vtkSmartPointer<vtkPolyData> &polydata, 01321 vtkSmartPointer<vtkIdTypeArray> &initcells); 01322 01329 void 01330 convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler, 01331 vtkSmartPointer<vtkPolyData> &polydata, 01332 vtkSmartPointer<vtkIdTypeArray> &initcells); 01333 01342 void 01343 updateCells (vtkSmartPointer<vtkIdTypeArray> &cells, 01344 vtkSmartPointer<vtkIdTypeArray> &initcells, 01345 vtkIdType nr_points); 01346 01355 template <typename PointT> bool 01356 fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler, 01357 const PointCloudColorHandler<PointT> &color_handler, 01358 const std::string &id, 01359 int viewport); 01360 01369 template <typename PointT> bool 01370 fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler, 01371 const ColorHandlerConstPtr &color_handler, 01372 const std::string &id, 01373 int viewport); 01374 01383 bool 01384 fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler, 01385 const ColorHandlerConstPtr &color_handler, 01386 const std::string &id, 01387 int viewport); 01388 01397 template <typename PointT> bool 01398 fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler, 01399 const PointCloudColorHandler<PointT> &color_handler, 01400 const std::string &id, 01401 int viewport); 01402 01406 void 01407 allocVtkPolyData (vtkSmartPointer<vtkAppendPolyData> &polydata); 01408 01412 void 01413 allocVtkPolyData (vtkSmartPointer<vtkPolyData> &polydata); 01414 01418 void 01419 allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata); 01420 }; 01421 } 01422 } 01423 01424 #include <pcl/visualization/impl/pcl_visualizer.hpp> 01425 01426 #endif 01427