|
Point Cloud Library (PCL)
1.5.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 4702 2012-02-23 09:39:33Z gedikli $ 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 00405 template <typename PointT> bool 00406 addText3D (const std::string &text, 00407 const PointT &position, 00408 double textScale = 1.0, 00409 double r = 1.0, double g = 1.0, double b = 1.0, 00410 const std::string &id = "", int viewport = 0); 00411 00419 template <typename PointNT> bool 00420 addPointCloudNormals (const typename pcl::PointCloud<PointNT>::ConstPtr &cloud, 00421 int level = 100, double scale = 0.02, 00422 const std::string &id = "cloud", int viewport = 0); 00423 00432 template <typename PointT, typename PointNT> bool 00433 addPointCloudNormals (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00434 const typename pcl::PointCloud<PointNT>::ConstPtr &normals, 00435 int level = 100, double scale = 0.02, 00436 const std::string &id = "cloud", int viewport = 0); 00437 00447 bool 00448 addPointCloudPrincipalCurvatures ( 00449 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 00450 const pcl::PointCloud<pcl::Normal>::ConstPtr &normals, 00451 const pcl::PointCloud<pcl::PrincipalCurvatures>::ConstPtr &pcs, 00452 int level = 100, double scale = 1.0, 00453 const std::string &id = "cloud", int viewport = 0); 00454 00460 template <typename PointT> bool 00461 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00462 const std::string &id = "cloud", int viewport = 0); 00463 00469 template <typename PointT> bool 00470 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00471 const std::string &id = "cloud"); 00472 00479 template <typename PointT> bool 00480 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00481 const PointCloudGeometryHandler<PointT> &geometry_handler, 00482 const std::string &id = "cloud"); 00483 00490 template <typename PointT> bool 00491 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00492 const PointCloudColorHandler<PointT> &color_handler, 00493 const std::string &id = "cloud"); 00494 00495 // bool 00496 // updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 00497 // const PointCloudColorHandlerRGBField<pcl::PointXYZRGB> &color_handler, 00498 // const std::string &id = "cloud"); 00499 00506 template <typename PointT> bool 00507 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00508 const PointCloudGeometryHandler<PointT> &geometry_handler, 00509 const std::string &id = "cloud", int viewport = 0); 00510 00523 template <typename PointT> bool 00524 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00525 const GeometryHandlerConstPtr &geometry_handler, 00526 const std::string &id = "cloud", int viewport = 0); 00527 00534 template <typename PointT> bool 00535 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00536 const PointCloudColorHandler<PointT> &color_handler, 00537 const std::string &id = "cloud", int viewport = 0); 00538 00551 template <typename PointT> bool 00552 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00553 const ColorHandlerConstPtr &color_handler, 00554 const std::string &id = "cloud", int viewport = 0); 00555 00569 template <typename PointT> bool 00570 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00571 const GeometryHandlerConstPtr &geometry_handler, 00572 const ColorHandlerConstPtr &color_handler, 00573 const std::string &id = "cloud", int viewport = 0); 00574 00590 bool 00591 addPointCloud (const sensor_msgs::PointCloud2::ConstPtr &cloud, 00592 const GeometryHandlerConstPtr &geometry_handler, 00593 const ColorHandlerConstPtr &color_handler, 00594 const Eigen::Vector4f& sensor_origin, 00595 const Eigen::Quaternion<float>& sensor_orientation, 00596 const std::string &id = "cloud", int viewport = 0); 00597 00612 bool 00613 addPointCloud (const sensor_msgs::PointCloud2::ConstPtr &cloud, 00614 const GeometryHandlerConstPtr &geometry_handler, 00615 const Eigen::Vector4f& sensor_origin, 00616 const Eigen::Quaternion<float>& sensor_orientation, 00617 const std::string &id = "cloud", int viewport = 0); 00618 00633 bool 00634 addPointCloud (const sensor_msgs::PointCloud2::ConstPtr &cloud, 00635 const ColorHandlerConstPtr &color_handler, 00636 const Eigen::Vector4f& sensor_origin, 00637 const Eigen::Quaternion<float>& sensor_orientation, 00638 const std::string &id = "cloud", int viewport = 0); 00639 00647 template <typename PointT> bool 00648 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00649 const PointCloudColorHandler<PointT> &color_handler, 00650 const PointCloudGeometryHandler<PointT> &geometry_handler, 00651 const std::string &id = "cloud", int viewport = 0); 00652 00658 inline bool 00659 addPointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 00660 const std::string &id = "cloud", int viewport = 0) 00661 { 00662 return (addPointCloud<pcl::PointXYZ> (cloud, id, viewport)); 00663 } 00664 00665 00671 inline bool 00672 addPointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 00673 const std::string &id = "cloud", int viewport = 0) 00674 { 00675 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud); 00676 return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler, id, viewport)); 00677 } 00678 00684 inline bool 00685 addPointCloud (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud, 00686 const std::string &id = "cloud", int viewport = 0) 00687 { 00688 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> color_handler (cloud); 00689 return (addPointCloud<pcl::PointXYZRGBA> (cloud, color_handler, id, viewport)); 00690 } 00691 00697 inline bool 00698 updatePointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud, 00699 const std::string &id = "cloud") 00700 { 00701 return (updatePointCloud<pcl::PointXYZ> (cloud, id)); 00702 } 00703 00709 inline bool 00710 updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, 00711 const std::string &id = "cloud") 00712 { 00713 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud); 00714 return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler, id)); 00715 } 00716 00722 inline bool 00723 updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud, 00724 const std::string &id = "cloud") 00725 { 00726 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> color_handler (cloud); 00727 return (updatePointCloud<pcl::PointXYZRGBA> (cloud, color_handler, id)); 00728 } 00729 00735 bool 00736 addPolygonMesh (const pcl::PolygonMesh &polymesh, 00737 const std::string &id = "polygon", 00738 int viewport = 0); 00739 00746 template <typename PointT> bool 00747 addPolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00748 const std::vector<pcl::Vertices> &vertices, 00749 const std::string &id = "polygon", 00750 int viewport = 0); 00751 00758 template <typename PointT> bool 00759 updatePolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00760 const std::vector<pcl::Vertices> &vertices, 00761 const std::string &id = "polygon"); 00762 00768 bool 00769 addPolylineFromPolygonMesh (const pcl::PolygonMesh &polymesh, 00770 const std::string &id = "polyline", 00771 int viewport = 0); 00772 00780 template <typename PointT> bool 00781 addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points, 00782 const typename pcl::PointCloud<PointT>::ConstPtr &target_points, 00783 const std::vector<int> & correspondences, 00784 const std::string &id = "correspondences", 00785 int viewport = 0); 00786 00794 template <typename PointT> bool 00795 addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points, 00796 const typename pcl::PointCloud<PointT>::ConstPtr &target_points, 00797 const pcl::Correspondences &correspondences, 00798 const std::string &id = "correspondences", 00799 int viewport = 0); 00800 00805 inline void 00806 removeCorrespondences (const std::string &id = "correspondences", int viewport = 0) 00807 { 00808 removeShape (id, viewport); 00809 } 00810 00814 inline int 00815 getColorHandlerIndex (const std::string &id) 00816 { 00817 CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id); 00818 if (am_it == cloud_actor_map_->end ()) 00819 return (-1); 00820 00821 return (am_it->second.color_handler_index_); 00822 } 00823 00827 inline int 00828 getGeometryHandlerIndex (const std::string &id) 00829 { 00830 CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id); 00831 if (am_it != cloud_actor_map_->end ()) 00832 return (-1); 00833 00834 return (am_it->second.geometry_handler_index_); 00835 } 00836 00841 bool 00842 updateColorHandlerIndex (const std::string &id, int index); 00843 00852 bool 00853 setPointCloudRenderingProperties (int property, double val1, double val2, double val3, 00854 const std::string &id = "cloud", int viewport = 0); 00855 00862 bool 00863 setPointCloudRenderingProperties (int property, double value, 00864 const std::string &id = "cloud", int viewport = 0); 00865 00871 bool 00872 getPointCloudRenderingProperties (int property, double &value, 00873 const std::string &id = "cloud"); 00874 00881 bool 00882 setShapeRenderingProperties (int property, double value, 00883 const std::string &id, int viewport = 0); 00884 00893 bool 00894 setShapeRenderingProperties (int property, double val1, double val2, double val3, 00895 const std::string &id, int viewport = 0); 00896 00897 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 00898 00899 bool 00900 wasStopped () const { if (interactor_ != NULL) return (interactor_->stopped); else return true; } 00901 00903 void 00904 resetStoppedFlag () { if (interactor_ != NULL) interactor_->stopped = false; } 00905 #else 00906 00907 bool 00908 wasStopped () const { if (interactor_ != NULL) return (stopped_); else return (true); } 00909 00911 void 00912 resetStoppedFlag () { if (interactor_ != NULL) stopped_ = false; } 00913 #endif 00914 00921 void 00922 createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport); 00923 00933 template <typename PointT> bool 00934 addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00935 double r, double g, double b, 00936 const std::string &id = "polygon", int viewport = 0); 00937 00944 template <typename PointT> bool 00945 addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 00946 const std::string &id = "polygon", 00947 int viewport = 0); 00948 00955 template <typename P1, typename P2> bool 00956 addLine (const P1 &pt1, const P2 &pt2, const std::string &id = "line", 00957 int viewport = 0); 00958 00968 template <typename P1, typename P2> bool 00969 addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b, 00970 const std::string &id = "line", int viewport = 0); 00971 00981 template <typename P1, typename P2> bool 00982 addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, 00983 const std::string &id = "arrow", int viewport = 0); 00984 00991 template <typename PointT> bool 00992 addSphere (const PointT ¢er, double radius, const std::string &id = "sphere", 00993 int viewport = 0); 00994 01004 template <typename PointT> bool 01005 addSphere (const PointT ¢er, double radius, double r, double g, double b, 01006 const std::string &id = "sphere", int viewport = 0); 01007 01013 bool 01014 addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata, 01015 const std::string & id = "PolyData", 01016 int viewport = 0); 01017 01024 bool 01025 addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata, 01026 vtkSmartPointer<vtkTransform> transform, 01027 const std::string &id = "PolyData", 01028 int viewport = 0); 01029 01035 bool 01036 addModelFromPLYFile (const std::string &filename, 01037 const std::string &id = "PLYModel", 01038 int viewport = 0); 01039 01046 bool 01047 addModelFromPLYFile (const std::string &filename, 01048 vtkSmartPointer<vtkTransform> transform, 01049 const std::string &id = "PLYModel", 01050 int viewport = 0); 01051 01078 bool 01079 addCylinder (const pcl::ModelCoefficients &coefficients, 01080 const std::string &id = "cylinder", 01081 int viewport = 0); 01082 01105 bool 01106 addSphere (const pcl::ModelCoefficients &coefficients, 01107 const std::string &id = "sphere", 01108 int viewport = 0); 01109 01133 bool 01134 addLine (const pcl::ModelCoefficients &coefficients, 01135 const std::string &id = "line", 01136 int viewport = 0); 01137 01158 bool 01159 addPlane (const pcl::ModelCoefficients &coefficients, 01160 const std::string &id = "plane", 01161 int viewport = 0); 01162 01182 bool 01183 addCircle (const pcl::ModelCoefficients &coefficients, 01184 const std::string &id = "circle", 01185 int viewport = 0); 01186 01192 bool 01193 addCone (const pcl::ModelCoefficients &coefficients, 01194 const std::string &id = "cone", 01195 int viewport = 0); 01196 01202 bool 01203 addCube (const pcl::ModelCoefficients &coefficients, 01204 const std::string &id = "cube", 01205 int viewport = 0); 01206 01216 bool 01217 addCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation, 01218 double width, double height, double depth, 01219 const std::string &id = "cube", 01220 int viewport = 0); 01221 01223 void 01224 setRepresentationToSurfaceForAllActors (); 01225 01233 void 01234 renderView (int xres, int yres, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud); 01235 01253 void 01254 renderViewTesselatedSphere ( 01255 int xres, int yres, 01256 std::vector<pcl::PointCloud<pcl::PointXYZ>,Eigen::aligned_allocator< pcl::PointCloud<pcl::PointXYZ> > > & cloud, 01257 std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies, int tesselation_level, 01258 float view_angle = 45, float radius_sphere = 1, bool use_vertices = true); 01259 01261 Camera camera_; 01262 01264 void 01265 initCameraParameters (); 01266 01271 bool 01272 getCameraParameters (int argc, char **argv); 01273 01275 bool 01276 cameraParamsSet () const; 01277 01279 void 01280 updateCamera (); 01281 01283 void 01284 resetCamera (); 01285 01289 void 01290 resetCameraViewpoint (const std::string &id = "cloud"); 01291 01304 void 01305 setCameraPose (double posX, double posY, double posZ, 01306 double viewX, double viewY, double viewZ, 01307 double upX, double upY, double upZ, int viewport = 0); 01308 01318 void 01319 setCameraPosition (double posX,double posY, double posZ, 01320 double viewX, double viewY, double viewZ, int viewport = 0); 01321 01323 void 01324 getCameras (std::vector<Camera>& cameras); 01325 01327 Eigen::Affine3f 01328 getViewerPose (); 01329 01333 void 01334 saveScreenshot (const std::string &file); 01335 01337 vtkSmartPointer<vtkRenderWindow> 01338 getRenderWindow () 01339 { 01340 return (win_); 01341 } 01342 01344 void 01345 createInteractor (); 01346 01352 void 01353 setupInteractor (vtkRenderWindowInteractor *iren, 01354 vtkRenderWindow *win); 01355 01357 inline vtkSmartPointer<PCLVisualizerInteractorStyle> 01358 getInteractorStyle () 01359 { 01360 return (style_); 01361 } 01362 protected: 01364 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 01365 vtkSmartPointer<PCLVisualizerInteractor> interactor_; 01366 #else 01367 vtkSmartPointer<vtkRenderWindowInteractor> interactor_; 01368 #endif 01369 private: 01370 struct ExitMainLoopTimerCallback : public vtkCommand 01371 { 01372 static ExitMainLoopTimerCallback* New() 01373 { 01374 return new ExitMainLoopTimerCallback; 01375 } 01376 virtual void Execute(vtkObject* vtkNotUsed(caller), unsigned long event_id, void* call_data) 01377 { 01378 if (event_id != vtkCommand::TimerEvent) 01379 return; 01380 int timer_id = *(int*)call_data; 01381 //PCL_WARN ("[pcl::visualization::PCLVisualizer::ExitMainLoopTimerCallback] Timer %d called.\n", timer_id); 01382 if (timer_id != right_timer_id) 01383 return; 01384 // Stop vtk loop and send notification to app to wake it up 01385 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 01386 pcl_visualizer->interactor_->stopLoop (); 01387 #else 01388 pcl_visualizer->interactor_->TerminateApp (); 01389 #endif 01390 } 01391 int right_timer_id; 01392 PCLVisualizer* pcl_visualizer; 01393 }; 01394 struct ExitCallback : public vtkCommand 01395 { 01396 static ExitCallback* New () 01397 { 01398 return new ExitCallback; 01399 } 01400 virtual void Execute (vtkObject* caller, unsigned long event_id, void* call_data) 01401 { 01402 if (event_id != vtkCommand::ExitEvent) 01403 return; 01404 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 01405 pcl_visualizer->interactor_->stopped = true; 01406 // This tends to close the window... 01407 pcl_visualizer->interactor_->stopLoop (); 01408 #else 01409 pcl_visualizer->stopped_ = true; 01410 // This tends to close the window... 01411 pcl_visualizer->interactor_->TerminateApp (); 01412 #endif 01413 } 01414 PCLVisualizer* pcl_visualizer; 01415 }; 01416 01417 #if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4)) 01418 01419 bool stopped_; 01420 01422 int timer_id_; 01423 #endif 01424 01425 vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_; 01426 vtkSmartPointer<ExitCallback> exit_callback_; 01427 01429 vtkSmartPointer<vtkRendererCollection> rens_; 01430 01432 vtkSmartPointer<vtkRenderWindow> win_; 01433 01435 vtkSmartPointer<PCLVisualizerInteractorStyle> style_; 01436 01438 CloudActorMapPtr cloud_actor_map_; 01439 01441 ShapeActorMapPtr shape_actor_map_; 01442 01444 CoordinateActorMap coordinate_actor_map_; 01445 01447 bool camera_set_; 01448 01453 void 01454 removeActorFromRenderer (const vtkSmartPointer<vtkLODActor> &actor, 01455 int viewport = 0); 01456 01461 void 01462 addActorToRenderer (const vtkSmartPointer<vtkProp> &actor, 01463 int viewport = 0); 01464 01469 void 01470 removeActorFromRenderer (const vtkSmartPointer<vtkProp> &actor, 01471 int viewport = 0); 01472 01478 void 01479 createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data, 01480 vtkSmartPointer<vtkLODActor> &actor, 01481 bool use_scalars = true); 01482 01489 template <typename PointT> void 01490 convertPointCloudToVTKPolyData (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, 01491 vtkSmartPointer<vtkPolyData> &polydata, 01492 vtkSmartPointer<vtkIdTypeArray> &initcells); 01493 01500 template <typename PointT> void 01501 convertPointCloudToVTKPolyData (const PointCloudGeometryHandler<PointT> &geometry_handler, 01502 vtkSmartPointer<vtkPolyData> &polydata, 01503 vtkSmartPointer<vtkIdTypeArray> &initcells); 01504 01511 void 01512 convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler, 01513 vtkSmartPointer<vtkPolyData> &polydata, 01514 vtkSmartPointer<vtkIdTypeArray> &initcells); 01515 01524 void 01525 updateCells (vtkSmartPointer<vtkIdTypeArray> &cells, 01526 vtkSmartPointer<vtkIdTypeArray> &initcells, 01527 vtkIdType nr_points); 01528 01539 template <typename PointT> bool 01540 fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler, 01541 const PointCloudColorHandler<PointT> &color_handler, 01542 const std::string &id, 01543 int viewport, 01544 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0), 01545 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0)); 01546 01557 template <typename PointT> bool 01558 fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler, 01559 const ColorHandlerConstPtr &color_handler, 01560 const std::string &id, 01561 int viewport, 01562 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0), 01563 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0)); 01564 01575 bool 01576 fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler, 01577 const ColorHandlerConstPtr &color_handler, 01578 const std::string &id, 01579 int viewport, 01580 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0), 01581 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0)); 01582 01593 template <typename PointT> bool 01594 fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler, 01595 const PointCloudColorHandler<PointT> &color_handler, 01596 const std::string &id, 01597 int viewport, 01598 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0), 01599 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0)); 01600 01604 void 01605 allocVtkPolyData (vtkSmartPointer<vtkAppendPolyData> &polydata); 01606 01610 void 01611 allocVtkPolyData (vtkSmartPointer<vtkPolyData> &polydata); 01612 01616 void 01617 allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata); 01618 01624 void 01625 getTransformationMatrix (const Eigen::Vector4f &origin, 01626 const Eigen::Quaternion<float> &orientation, 01627 Eigen::Matrix4f &transformation); 01628 01633 void 01634 convertToVtkMatrix (const Eigen::Matrix4f &m, 01635 vtkSmartPointer<vtkMatrix4x4> &vtk_matrix); 01636 01642 void 01643 convertToVtkMatrix (const Eigen::Vector4f &origin, 01644 const Eigen::Quaternion<float> &orientation, 01645 vtkSmartPointer<vtkMatrix4x4> &vtk_matrix); 01646 01647 }; 01648 } 01649 } 01650 01651 #include <pcl/visualization/impl/pcl_visualizer.hpp> 01652 01653 #endif 01654
1.8.0