00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_PCL_VISUALIZER_H_
00039 #define PCL_PCL_VISUALIZER_H_
00040
00041
00042 #include <pcl/correspondence.h>
00043 #include <pcl/ModelCoefficients.h>
00044 #include <pcl/PolygonMesh.h>
00045
00046 #include <pcl/console/print.h>
00047 #include <pcl/visualization/common/actor_map.h>
00048 #include <pcl/visualization/common/common.h>
00049 #include <pcl/visualization/point_cloud_geometry_handlers.h>
00050 #include <pcl/visualization/point_cloud_color_handlers.h>
00051 #include <pcl/visualization/point_picking_event.h>
00052 #include <pcl/visualization/area_picking_event.h>
00053 #include <pcl/visualization/interactor_style.h>
00054
00055
00056 class vtkPolyData;
00057 class vtkTextActor;
00058 class vtkRenderWindow;
00059 class vtkOrientationMarkerWidget;
00060 class vtkAppendPolyData;
00061 class vtkRenderWindow;
00062 class vtkRenderWindowInteractor;
00063 class vtkTransform;
00064 class vtkInteractorStyle;
00065 class vtkLODActor;
00066 class vtkProp;
00067 class vtkActor;
00068 class vtkDataSet;
00069 class vtkUnstructuredGrid;
00070
00071 namespace pcl
00072 {
00073 template <typename T> class PointCloud;
00074 template <typename T> class PlanarPolygon;
00075
00076 namespace visualization
00077 {
00085 class PCL_EXPORTS PCLVisualizer
00086 {
00087 public:
00088 typedef boost::shared_ptr<PCLVisualizer> Ptr;
00089 typedef boost::shared_ptr<const PCLVisualizer> ConstPtr;
00090
00091 typedef PointCloudGeometryHandler<pcl::PCLPointCloud2> GeometryHandler;
00092 typedef GeometryHandler::Ptr GeometryHandlerPtr;
00093 typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr;
00094
00095 typedef PointCloudColorHandler<pcl::PCLPointCloud2> ColorHandler;
00096 typedef ColorHandler::Ptr ColorHandlerPtr;
00097 typedef ColorHandler::ConstPtr ColorHandlerConstPtr;
00098
00103 PCLVisualizer (const std::string &name = "", const bool create_interactor = true);
00104
00112 PCLVisualizer (int &argc, char **argv, const std::string &name = "",
00113 PCLVisualizerInteractorStyle* style = PCLVisualizerInteractorStyle::New (), const bool create_interactor = true);
00114
00116 virtual ~PCLVisualizer ();
00117
00123 void
00124 setFullScreen (bool mode);
00125
00129 void
00130 setWindowName (const std::string &name);
00131
00137 void
00138 setWindowBorders (bool mode);
00139
00144 boost::signals2::connection
00145 registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> cb);
00146
00152 inline boost::signals2::connection
00153 registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*), void* cookie = NULL)
00154 {
00155 return (registerKeyboardCallback (boost::bind (callback, _1, cookie)));
00156 }
00157
00164 template<typename T> inline boost::signals2::connection
00165 registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*), T& instance, void* cookie = NULL)
00166 {
00167 return (registerKeyboardCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00168 }
00169
00174 boost::signals2::connection
00175 registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> cb);
00176
00182 inline boost::signals2::connection
00183 registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*), void* cookie = NULL)
00184 {
00185 return (registerMouseCallback (boost::bind (callback, _1, cookie)));
00186 }
00187
00194 template<typename T> inline boost::signals2::connection
00195 registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*), T& instance, void* cookie = NULL)
00196 {
00197 return (registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00198 }
00199
00204 boost::signals2::connection
00205 registerPointPickingCallback (boost::function<void (const pcl::visualization::PointPickingEvent&)> cb);
00206
00212 boost::signals2::connection
00213 registerPointPickingCallback (void (*callback) (const pcl::visualization::PointPickingEvent&, void*), void* cookie = NULL);
00214
00221 template<typename T> inline boost::signals2::connection
00222 registerPointPickingCallback (void (T::*callback) (const pcl::visualization::PointPickingEvent&, void*), T& instance, void* cookie = NULL)
00223 {
00224 return (registerPointPickingCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00225 }
00226
00231 boost::signals2::connection
00232 registerAreaPickingCallback (boost::function<void (const pcl::visualization::AreaPickingEvent&)> cb);
00233
00239 boost::signals2::connection
00240 registerAreaPickingCallback (void (*callback) (const pcl::visualization::AreaPickingEvent&, void*), void* cookie = NULL);
00241
00248 template<typename T> inline boost::signals2::connection
00249 registerAreaPickingCallback (void (T::*callback) (const pcl::visualization::AreaPickingEvent&, void*), T& instance, void* cookie = NULL)
00250 {
00251 return (registerAreaPickingCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00252 }
00253
00255 void
00256 spin ();
00257
00263 void
00264 spinOnce (int time = 1, bool force_redraw = false);
00265
00269 void
00270 addOrientationMarkerWidgetAxes (vtkRenderWindowInteractor* interactor);
00271
00273 void
00274 removeOrientationMarkerWidgetAxes ();
00275
00280 void
00281 addCoordinateSystem (double scale = 1.0, int viewport = 0);
00282
00290 void
00291 addCoordinateSystem (double scale, float x, float y, float z, int viewport = 0);
00292
00324 void
00325 addCoordinateSystem (double scale, const Eigen::Affine3f& t, int viewport = 0);
00326
00330 bool
00331 removeCoordinateSystem (int viewport = 0);
00332
00339 bool
00340 removePointCloud (const std::string &id = "cloud", int viewport = 0);
00341
00346 inline bool
00347 removePolygonMesh (const std::string &id = "polygon", int viewport = 0)
00348 {
00349
00350 return (removePointCloud (id, viewport));
00351 }
00352
00358 bool
00359 removeShape (const std::string &id = "cloud", int viewport = 0);
00360
00365 bool
00366 removeText3D (const std::string &id = "cloud", int viewport = 0);
00367
00371 bool
00372 removeAllPointClouds (int viewport = 0);
00373
00377 bool
00378 removeAllShapes (int viewport = 0);
00379
00386 void
00387 setBackgroundColor (const double &r, const double &g, const double &b, int viewport = 0);
00388
00396 bool
00397 addText (const std::string &text,
00398 int xpos, int ypos,
00399 const std::string &id = "", int viewport = 0);
00400
00411 bool
00412 addText (const std::string &text, int xpos, int ypos, double r, double g, double b,
00413 const std::string &id = "", int viewport = 0);
00414
00426 bool
00427 addText (const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b,
00428 const std::string &id = "", int viewport = 0);
00429
00430
00437 bool
00438 updateText (const std::string &text,
00439 int xpos, int ypos,
00440 const std::string &id = "");
00441
00451 bool
00452 updateText (const std::string &text,
00453 int xpos, int ypos, double r, double g, double b,
00454 const std::string &id = "");
00455
00466 bool
00467 updateText (const std::string &text,
00468 int xpos, int ypos, int fontsize, double r, double g, double b,
00469 const std::string &id = "");
00470
00480 bool
00481 updateShapePose (const std::string &id, const Eigen::Affine3f& pose);
00482
00492 bool
00493 updatePointCloudPose (const std::string &id, const Eigen::Affine3f& pose);
00494
00505 template <typename PointT> bool
00506 addText3D (const std::string &text,
00507 const PointT &position,
00508 double textScale = 1.0,
00509 double r = 1.0, double g = 1.0, double b = 1.0,
00510 const std::string &id = "", int viewport = 0);
00511
00519 template <typename PointNT> bool
00520 addPointCloudNormals (const typename pcl::PointCloud<PointNT>::ConstPtr &cloud,
00521 int level = 100, float scale = 0.02f,
00522 const std::string &id = "cloud", int viewport = 0);
00523
00532 template <typename PointT, typename PointNT> bool
00533 addPointCloudNormals (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00534 const typename pcl::PointCloud<PointNT>::ConstPtr &normals,
00535 int level = 100, float scale = 0.02f,
00536 const std::string &id = "cloud", int viewport = 0);
00537
00547 bool
00548 addPointCloudPrincipalCurvatures (
00549 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud,
00550 const pcl::PointCloud<pcl::Normal>::ConstPtr &normals,
00551 const pcl::PointCloud<pcl::PrincipalCurvatures>::ConstPtr &pcs,
00552 int level = 100, float scale = 1.0f,
00553 const std::string &id = "cloud", int viewport = 0);
00554
00563 template <typename PointT, typename GradientT> bool
00564 addPointCloudIntensityGradients (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00565 const typename pcl::PointCloud<GradientT>::ConstPtr &gradients,
00566 int level = 100, double scale = 1e-6,
00567 const std::string &id = "cloud", int viewport = 0);
00568
00574 template <typename PointT> bool
00575 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00576 const std::string &id = "cloud", int viewport = 0);
00577
00583 template <typename PointT> bool
00584 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00585 const std::string &id = "cloud");
00586
00593 template <typename PointT> bool
00594 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00595 const PointCloudGeometryHandler<PointT> &geometry_handler,
00596 const std::string &id = "cloud");
00597
00604 template <typename PointT> bool
00605 updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00606 const PointCloudColorHandler<PointT> &color_handler,
00607 const std::string &id = "cloud");
00608
00615 template <typename PointT> bool
00616 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00617 const PointCloudGeometryHandler<PointT> &geometry_handler,
00618 const std::string &id = "cloud", int viewport = 0);
00619
00632 template <typename PointT> bool
00633 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00634 const GeometryHandlerConstPtr &geometry_handler,
00635 const std::string &id = "cloud", int viewport = 0);
00636
00643 template <typename PointT> bool
00644 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00645 const PointCloudColorHandler<PointT> &color_handler,
00646 const std::string &id = "cloud", int viewport = 0);
00647
00660 template <typename PointT> bool
00661 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00662 const ColorHandlerConstPtr &color_handler,
00663 const std::string &id = "cloud", int viewport = 0);
00664
00678 template <typename PointT> bool
00679 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00680 const GeometryHandlerConstPtr &geometry_handler,
00681 const ColorHandlerConstPtr &color_handler,
00682 const std::string &id = "cloud", int viewport = 0);
00683
00699 bool
00700 addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud,
00701 const GeometryHandlerConstPtr &geometry_handler,
00702 const ColorHandlerConstPtr &color_handler,
00703 const Eigen::Vector4f& sensor_origin,
00704 const Eigen::Quaternion<float>& sensor_orientation,
00705 const std::string &id = "cloud", int viewport = 0);
00706
00721 bool
00722 addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud,
00723 const GeometryHandlerConstPtr &geometry_handler,
00724 const Eigen::Vector4f& sensor_origin,
00725 const Eigen::Quaternion<float>& sensor_orientation,
00726 const std::string &id = "cloud", int viewport = 0);
00727
00742 bool
00743 addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud,
00744 const ColorHandlerConstPtr &color_handler,
00745 const Eigen::Vector4f& sensor_origin,
00746 const Eigen::Quaternion<float>& sensor_orientation,
00747 const std::string &id = "cloud", int viewport = 0);
00748
00756 template <typename PointT> bool
00757 addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00758 const PointCloudColorHandler<PointT> &color_handler,
00759 const PointCloudGeometryHandler<PointT> &geometry_handler,
00760 const std::string &id = "cloud", int viewport = 0);
00761
00767 inline bool
00768 addPointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud,
00769 const std::string &id = "cloud", int viewport = 0)
00770 {
00771 return (addPointCloud<pcl::PointXYZ> (cloud, id, viewport));
00772 }
00773
00774
00780 inline bool
00781 addPointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud,
00782 const std::string &id = "cloud", int viewport = 0)
00783 {
00784 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud);
00785 return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler, id, viewport));
00786 }
00787
00793 inline bool
00794 addPointCloud (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud,
00795 const std::string &id = "cloud", int viewport = 0)
00796 {
00797 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> color_handler (cloud);
00798 return (addPointCloud<pcl::PointXYZRGBA> (cloud, color_handler, id, viewport));
00799 }
00800
00806 inline bool
00807 updatePointCloud (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &cloud,
00808 const std::string &id = "cloud")
00809 {
00810 return (updatePointCloud<pcl::PointXYZ> (cloud, id));
00811 }
00812
00818 inline bool
00819 updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud,
00820 const std::string &id = "cloud")
00821 {
00822 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler (cloud);
00823 return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler, id));
00824 }
00825
00831 inline bool
00832 updatePointCloud (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud,
00833 const std::string &id = "cloud")
00834 {
00835 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> color_handler (cloud);
00836 return (updatePointCloud<pcl::PointXYZRGBA> (cloud, color_handler, id));
00837 }
00838
00844 bool
00845 addPolygonMesh (const pcl::PolygonMesh &polymesh,
00846 const std::string &id = "polygon",
00847 int viewport = 0);
00848
00855 template <typename PointT> bool
00856 addPolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00857 const std::vector<pcl::Vertices> &vertices,
00858 const std::string &id = "polygon",
00859 int viewport = 0);
00860
00867 template <typename PointT> bool
00868 updatePolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00869 const std::vector<pcl::Vertices> &vertices,
00870 const std::string &id = "polygon");
00871
00877 bool
00878 updatePolygonMesh (const pcl::PolygonMesh &polymesh,
00879 const std::string &id = "polygon");
00880
00886 bool
00887 addPolylineFromPolygonMesh (const pcl::PolygonMesh &polymesh,
00888 const std::string &id = "polyline",
00889 int viewport = 0);
00890
00898 template <typename PointT> bool
00899 addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
00900 const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
00901 const std::vector<int> & correspondences,
00902 const std::string &id = "correspondences",
00903 int viewport = 0);
00904
00913 template <typename PointT> bool
00914 addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
00915 const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
00916 const pcl::Correspondences &correspondences,
00917 int nth,
00918 const std::string &id = "correspondences",
00919 int viewport = 0);
00920
00928 template <typename PointT> bool
00929 addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
00930 const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
00931 const pcl::Correspondences &correspondences,
00932 const std::string &id = "correspondences",
00933 int viewport = 0)
00934 {
00935
00936 return (addCorrespondences<PointT> (source_points, target_points,
00937 correspondences, 1, id, viewport));
00938 }
00939
00947 template <typename PointT> bool
00948 updateCorrespondences (
00949 const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
00950 const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
00951 const pcl::Correspondences &correspondences,
00952 int nth,
00953 const std::string &id = "correspondences");
00954
00959 void
00960 removeCorrespondences (const std::string &id = "correspondences", int viewport = 0);
00961
00965 int
00966 getColorHandlerIndex (const std::string &id);
00967
00971 int
00972 getGeometryHandlerIndex (const std::string &id);
00973
00978 bool
00979 updateColorHandlerIndex (const std::string &id, int index);
00980
00989 bool
00990 setPointCloudRenderingProperties (int property, double val1, double val2, double val3,
00991 const std::string &id = "cloud", int viewport = 0);
00992
00999 bool
01000 setPointCloudRenderingProperties (int property, double value,
01001 const std::string &id = "cloud", int viewport = 0);
01002
01008 bool
01009 getPointCloudRenderingProperties (int property, double &value,
01010 const std::string &id = "cloud");
01011
01016 bool
01017 setPointCloudSelected (const bool selected, const std::string &id = "cloud" );
01018
01025 bool
01026 setShapeRenderingProperties (int property, double value,
01027 const std::string &id, int viewport = 0);
01028
01037 bool
01038 setShapeRenderingProperties (int property, double val1, double val2, double val3,
01039 const std::string &id, int viewport = 0);
01040
01042 bool
01043 wasStopped () const;
01044
01046 void
01047 resetStoppedFlag ();
01048
01050 void
01051 close ();
01052
01064 void
01065 createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport);
01066
01070 void
01071 createViewPortCamera (const int viewport);
01072
01082 template <typename PointT> bool
01083 addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
01084 double r, double g, double b,
01085 const std::string &id = "polygon", int viewport = 0);
01086
01093 template <typename PointT> bool
01094 addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
01095 const std::string &id = "polygon",
01096 int viewport = 0);
01097
01106 template <typename PointT> bool
01107 addPolygon (const pcl::PlanarPolygon<PointT> &polygon,
01108 double r, double g, double b,
01109 const std::string &id = "polygon",
01110 int viewport = 0);
01111
01118 template <typename P1, typename P2> bool
01119 addLine (const P1 &pt1, const P2 &pt2, const std::string &id = "line",
01120 int viewport = 0);
01121
01131 template <typename P1, typename P2> bool
01132 addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b,
01133 const std::string &id = "line", int viewport = 0);
01134
01144 template <typename P1, typename P2> bool
01145 addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b,
01146 const std::string &id = "arrow", int viewport = 0);
01147
01158 template <typename P1, typename P2> bool
01159 addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, bool display_length,
01160 const std::string &id = "arrow", int viewport = 0);
01161
01174 template <typename P1, typename P2> bool
01175 addArrow (const P1 &pt1, const P2 &pt2,
01176 double r_line, double g_line, double b_line,
01177 double r_text, double g_text, double b_text,
01178 const std::string &id = "arrow", int viewport = 0);
01179
01180
01187 template <typename PointT> bool
01188 addSphere (const PointT ¢er, double radius, const std::string &id = "sphere",
01189 int viewport = 0);
01190
01200 template <typename PointT> bool
01201 addSphere (const PointT ¢er, double radius, double r, double g, double b,
01202 const std::string &id = "sphere", int viewport = 0);
01203
01212 template <typename PointT> bool
01213 updateSphere (const PointT ¢er, double radius, double r, double g, double b,
01214 const std::string &id = "sphere");
01215
01221 bool
01222 addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata,
01223 const std::string & id = "PolyData",
01224 int viewport = 0);
01225
01232 bool
01233 addModelFromPolyData (vtkSmartPointer<vtkPolyData> polydata,
01234 vtkSmartPointer<vtkTransform> transform,
01235 const std::string &id = "PolyData",
01236 int viewport = 0);
01237
01243 bool
01244 addModelFromPLYFile (const std::string &filename,
01245 const std::string &id = "PLYModel",
01246 int viewport = 0);
01247
01254 bool
01255 addModelFromPLYFile (const std::string &filename,
01256 vtkSmartPointer<vtkTransform> transform,
01257 const std::string &id = "PLYModel",
01258 int viewport = 0);
01259
01286 bool
01287 addCylinder (const pcl::ModelCoefficients &coefficients,
01288 const std::string &id = "cylinder",
01289 int viewport = 0);
01290
01313 bool
01314 addSphere (const pcl::ModelCoefficients &coefficients,
01315 const std::string &id = "sphere",
01316 int viewport = 0);
01317
01341 bool
01342 addLine (const pcl::ModelCoefficients &coefficients,
01343 const std::string &id = "line",
01344 int viewport = 0);
01345
01366 bool
01367 addPlane (const pcl::ModelCoefficients &coefficients,
01368 const std::string &id = "plane",
01369 int viewport = 0);
01370
01371 bool
01372 addPlane (const pcl::ModelCoefficients &coefficients, double x, double y, double z,
01373 const std::string &id = "plane",
01374 int viewport = 0);
01394 bool
01395 addCircle (const pcl::ModelCoefficients &coefficients,
01396 const std::string &id = "circle",
01397 int viewport = 0);
01398
01404 bool
01405 addCone (const pcl::ModelCoefficients &coefficients,
01406 const std::string &id = "cone",
01407 int viewport = 0);
01408
01414 bool
01415 addCube (const pcl::ModelCoefficients &coefficients,
01416 const std::string &id = "cube",
01417 int viewport = 0);
01418
01428 bool
01429 addCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation,
01430 double width, double height, double depth,
01431 const std::string &id = "cube",
01432 int viewport = 0);
01433
01447 bool
01448 addCube (float x_min, float x_max, float y_min, float y_max, float z_min, float z_max,
01449 double r = 1.0, double g = 1.0, double b = 1.0, const std::string &id = "cube", int viewport = 0);
01450
01452 void
01453 setRepresentationToSurfaceForAllActors ();
01454
01456 void
01457 setRepresentationToPointsForAllActors ();
01458
01460 void
01461 setRepresentationToWireframeForAllActors ();
01462
01466 void
01467 setShowFPS (bool show_fps);
01468
01476 void
01477 renderView (int xres, int yres, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
01478
01496 void
01497 renderViewTesselatedSphere (
01498 int xres, int yres,
01499 pcl::PointCloud<pcl::PointXYZ>::CloudVectorType & cloud,
01500 std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies, int tesselation_level,
01501 float view_angle = 45, float radius_sphere = 1, bool use_vertices = true);
01502
01503
01505 void
01506 initCameraParameters ();
01507
01512 bool
01513 getCameraParameters (int argc, char **argv);
01514
01516 bool
01517 cameraParamsSet () const;
01518
01520 void
01521 updateCamera ();
01522
01524 void
01525 resetCamera ();
01526
01530 void
01531 resetCameraViewpoint (const std::string &id = "cloud");
01532
01545 void
01546 setCameraPosition (double pos_x, double pos_y, double pos_z,
01547 double view_x, double view_y, double view_z,
01548 double up_x, double up_y, double up_z, int viewport = 0);
01549
01559 void
01560 setCameraPosition (double pos_x, double pos_y, double pos_z,
01561 double up_x, double up_y, double up_z, int viewport = 0);
01562
01569 void
01570 setCameraParameters (const Eigen::Matrix3f &intrinsics, const Eigen::Matrix4f &extrinsics, int viewport = 0);
01571
01576 void
01577 setCameraParameters (const Camera &camera, int viewport = 0);
01578
01583 void
01584 setCameraClipDistances (double near, double far, int viewport = 0);
01585
01590 void
01591 setCameraFieldOfView (double fovy, int viewport = 0);
01592
01594 void
01595 getCameras (std::vector<Camera>& cameras);
01596
01597
01599 Eigen::Affine3f
01600 getViewerPose (int viewport = 0);
01601
01605 void
01606 saveScreenshot (const std::string &file);
01607
01609 vtkSmartPointer<vtkRenderWindow>
01610 getRenderWindow ()
01611 {
01612 return (win_);
01613 }
01614
01616 vtkSmartPointer<vtkRendererCollection>
01617 getRendererCollection ()
01618 {
01619 return (rens_);
01620 }
01621
01623 CloudActorMapPtr
01624 getCloudActorMap ()
01625 {
01626 return (cloud_actor_map_);
01627 }
01628
01629
01634 void
01635 setPosition (int x, int y);
01636
01641 void
01642 setSize (int xw, int yw);
01643
01647 void
01648 setUseVbos (bool use_vbos);
01649
01651 void
01652 createInteractor ();
01653
01659 void
01660 setupInteractor (vtkRenderWindowInteractor *iren,
01661 vtkRenderWindow *win);
01662
01669 void
01670 setupInteractor (vtkRenderWindowInteractor *iren,
01671 vtkRenderWindow *win,
01672 vtkInteractorStyle *style);
01673
01675 inline vtkSmartPointer<PCLVisualizerInteractorStyle>
01676 getInteractorStyle ()
01677 {
01678 return (style_);
01679 }
01680 protected:
01682 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01683 vtkSmartPointer<PCLVisualizerInteractor> interactor_;
01684 #else
01685 vtkSmartPointer<vtkRenderWindowInteractor> interactor_;
01686 #endif
01687 private:
01688 struct ExitMainLoopTimerCallback : public vtkCommand
01689 {
01690 static ExitMainLoopTimerCallback* New ()
01691 {
01692 return (new ExitMainLoopTimerCallback);
01693 }
01694 virtual void
01695 Execute (vtkObject*, unsigned long event_id, void*);
01696
01697 int right_timer_id;
01698 PCLVisualizer* pcl_visualizer;
01699 };
01700
01701 struct ExitCallback : public vtkCommand
01702 {
01703 static ExitCallback* New ()
01704 {
01705 return (new ExitCallback);
01706 }
01707 virtual void
01708 Execute (vtkObject*, unsigned long event_id, void*);
01709
01710 PCLVisualizer* pcl_visualizer;
01711 };
01712
01714 struct FPSCallback : public vtkCommand
01715 {
01716 static FPSCallback *New () { return (new FPSCallback); }
01717
01718 FPSCallback () : actor (), pcl_visualizer (), decimated () {}
01719 FPSCallback (const FPSCallback& src) : vtkCommand (), actor (src.actor), pcl_visualizer (src.pcl_visualizer), decimated (src.decimated) {}
01720 FPSCallback& operator = (const FPSCallback& src) { actor = src.actor; pcl_visualizer = src.pcl_visualizer; decimated = src.decimated; return (*this); }
01721
01722 virtual void
01723 Execute (vtkObject*, unsigned long event_id, void*);
01724
01725 vtkTextActor *actor;
01726 PCLVisualizer* pcl_visualizer;
01727 bool decimated;
01728 };
01729
01731 vtkSmartPointer<FPSCallback> update_fps_;
01732
01733 #if !((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
01734
01735 bool stopped_;
01736
01738 int timer_id_;
01739 #endif
01740
01741 vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
01742 vtkSmartPointer<ExitCallback> exit_callback_;
01743
01745 vtkSmartPointer<vtkRendererCollection> rens_;
01746
01748 vtkSmartPointer<vtkRenderWindow> win_;
01749
01751 vtkSmartPointer<PCLVisualizerInteractorStyle> style_;
01752
01754 CloudActorMapPtr cloud_actor_map_;
01755
01757 ShapeActorMapPtr shape_actor_map_;
01758
01760 CoordinateActorMap coordinate_actor_map_;
01761
01763 vtkSmartPointer<vtkOrientationMarkerWidget> axes_widget_;
01764
01766 bool camera_set_;
01767
01769 bool use_vbos_;
01770
01775 bool
01776 removeActorFromRenderer (const vtkSmartPointer<vtkLODActor> &actor,
01777 int viewport = 0);
01778
01783 bool
01784 removeActorFromRenderer (const vtkSmartPointer<vtkActor> &actor,
01785 int viewport = 0);
01786
01794 void
01795 addActorToRenderer (const vtkSmartPointer<vtkProp> &actor,
01796 int viewport = 0);
01797
01802 bool
01803 removeActorFromRenderer (const vtkSmartPointer<vtkProp> &actor,
01804 int viewport = 0);
01805
01811 void
01812 createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data,
01813 vtkSmartPointer<vtkActor> &actor,
01814 bool use_scalars = true);
01815
01821 void
01822 createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data,
01823 vtkSmartPointer<vtkLODActor> &actor,
01824 bool use_scalars = true);
01825
01832 template <typename PointT> void
01833 convertPointCloudToVTKPolyData (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
01834 vtkSmartPointer<vtkPolyData> &polydata,
01835 vtkSmartPointer<vtkIdTypeArray> &initcells);
01836
01843 template <typename PointT> void
01844 convertPointCloudToVTKPolyData (const PointCloudGeometryHandler<PointT> &geometry_handler,
01845 vtkSmartPointer<vtkPolyData> &polydata,
01846 vtkSmartPointer<vtkIdTypeArray> &initcells);
01847
01854 void
01855 convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler,
01856 vtkSmartPointer<vtkPolyData> &polydata,
01857 vtkSmartPointer<vtkIdTypeArray> &initcells);
01858
01867 void
01868 updateCells (vtkSmartPointer<vtkIdTypeArray> &cells,
01869 vtkSmartPointer<vtkIdTypeArray> &initcells,
01870 vtkIdType nr_points);
01871
01882 template <typename PointT> bool
01883 fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler,
01884 const PointCloudColorHandler<PointT> &color_handler,
01885 const std::string &id,
01886 int viewport,
01887 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
01888 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
01889
01900 template <typename PointT> bool
01901 fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler,
01902 const ColorHandlerConstPtr &color_handler,
01903 const std::string &id,
01904 int viewport,
01905 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
01906 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
01907
01918 bool
01919 fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler,
01920 const ColorHandlerConstPtr &color_handler,
01921 const std::string &id,
01922 int viewport,
01923 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
01924 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
01925
01936 template <typename PointT> bool
01937 fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler,
01938 const PointCloudColorHandler<PointT> &color_handler,
01939 const std::string &id,
01940 int viewport,
01941 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
01942 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
01943
01947 void
01948 allocVtkPolyData (vtkSmartPointer<vtkAppendPolyData> &polydata);
01949
01953 void
01954 allocVtkPolyData (vtkSmartPointer<vtkPolyData> &polydata);
01955
01959 void
01960 allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata);
01961
01967 void
01968 getTransformationMatrix (const Eigen::Vector4f &origin,
01969 const Eigen::Quaternion<float> &orientation,
01970 Eigen::Matrix4f &transformation);
01971
01972
01973 public:
01978 static void
01979 convertToVtkMatrix (const Eigen::Matrix4f &m,
01980 vtkSmartPointer<vtkMatrix4x4> &vtk_matrix);
01981
01987 static void
01988 convertToVtkMatrix (const Eigen::Vector4f &origin,
01989 const Eigen::Quaternion<float> &orientation,
01990 vtkSmartPointer<vtkMatrix4x4> &vtk_matrix);
01991
01996 static void
01997 convertToEigenMatrix (const vtkSmartPointer<vtkMatrix4x4> &vtk_matrix,
01998 Eigen::Matrix4f &m);
01999
02000 };
02001 }
02002 }
02003
02004 #include <pcl/visualization/impl/pcl_visualizer.hpp>
02005
02006 #endif
02007