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 #ifndef PCL_PCL_VISUALIZER_H_
00038 #define PCL_PCL_VISUALIZER_H_
00039
00040
00041 #include <pcl/point_types.h>
00042 #include <pcl/point_cloud.h>
00043
00044 #include <terminal_tools/print.h>
00045 #include <pcl_visualization/interactor.h>
00046 #include <pcl_visualization/interactor_style.h>
00047 #include <pcl_visualization/common/common.h>
00048 #include <pcl_visualization/common/shapes.h>
00049 #include <boost/make_shared.hpp>
00050 #include <boost/algorithm/string/split.hpp>
00051 #include <boost/algorithm/string/classification.hpp>
00052
00053 #include <vtkAxes.h>
00054 #include <vtkFloatArray.h>
00055 #include <vtkAppendPolyData.h>
00056 #include <vtkPointData.h>
00057 #include <vtkTubeFilter.h>
00058 #include <vtkPolyDataMapper.h>
00059 #include <vtkDataSetMapper.h>
00060 #include <vtkCellArray.h>
00061 #include <vtkCommand.h>
00062 #include <vtkPLYReader.h>
00063 #include <vtkTransformFilter.h>
00064
00065 namespace pcl_visualization
00066 {
00070 class PCLVisualizer
00071 {
00072 public:
00073 typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2> GeometryHandler;
00074 typedef GeometryHandler::Ptr GeometryHandlerPtr;
00075 typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr;
00076
00077 typedef PointCloudColorHandler<sensor_msgs::PointCloud2> ColorHandler;
00078 typedef ColorHandler::Ptr ColorHandlerPtr;
00079 typedef ColorHandler::ConstPtr ColorHandlerConstPtr;
00080
00084 PCLVisualizer (const std::string &name = "");
00091 PCLVisualizer (int &argc, char **argv, const std::string &name = "", PCLVisualizerInteractorStyle* style = PCLVisualizerInteractorStyle::New ());
00092
00094 virtual ~PCLVisualizer ();
00095
00097 void spin ();
00098
00104 void spinOnce (int time = 1, bool force_redraw = false);
00105
00110 void addCoordinateSystem (double scale = 1.0, int viewport = 0);
00118 void addCoordinateSystem (double scale, float x, float y, float z, int viewport = 0);
00119
00123 void removeCoordinateSystem (int viewport = 0);
00124
00129 bool removePointCloud (const std::string &id = "cloud", int viewport = 0);
00130
00135 bool removeShape (const std::string &id = "cloud", int viewport = 0);
00136
00143 void setBackgroundColor (const double &r, const double &g, const double &b, int viewport = 0);
00144
00152 bool addText (const std::string &text, int xpos, int ypos, const std::string &id = "", int viewport = 0);
00153
00164 bool addText (const std::string &text, int xpos, int ypos, int r, int g, int b, const std::string &id = "", int viewport = 0);
00165
00173 template <typename PointNT>
00174 bool addPointCloudNormals (const pcl::PointCloud<PointNT> &cloud,
00175 int level = 100, double scale = 0.02,
00176 const std::string &id = "cloud", int viewport = 0);
00185 template <typename PointT, typename PointNT>
00186 bool addPointCloudNormals (const pcl::PointCloud<PointT> &cloud,
00187 const pcl::PointCloud<PointNT> &normals,
00188 int level = 100, double scale = 0.02,
00189 const std::string &id = "cloud", int viewport = 0);
00199 bool addPointCloudPrincipalCurvatures (const pcl::PointCloud<pcl::PointXYZ> &cloud,
00200 const pcl::PointCloud<pcl::Normal> &normals,
00201 const pcl::PointCloud<pcl::PrincipalCurvatures> &pcs,
00202 int level = 100, double scale = 1.0,
00203 const std::string &id = "cloud", int viewport = 0);
00204
00210 bool addPointCloud (const pcl::PointCloud<pcl::PointXYZ> &cloud,
00211 const std::string &id = "cloud", int viewport = 0);
00212
00218 template <typename PointT> bool
00219 addPointCloud (const pcl::PointCloud<PointT> &cloud,
00220 const std::string &id = "cloud", int viewport = 0);
00221
00228 template <typename PointT> bool
00229 addPointCloud (const pcl::PointCloud<PointT> &cloud,
00230 const PointCloudGeometryHandler<PointT> &geometry_handler,
00231 const std::string &id = "cloud", int viewport = 0);
00232
00239 template <typename PointT> bool
00240 addPointCloud (const pcl::PointCloud<PointT> &cloud,
00241 const GeometryHandlerConstPtr &geometry_handler,
00242 const std::string &id = "cloud", int viewport = 0);
00243
00250 template <typename PointT> bool
00251 addPointCloud (const pcl::PointCloud<PointT> &cloud,
00252 const PointCloudColorHandler<PointT> &color_handler,
00253 const std::string &id = "cloud", int viewport = 0);
00254
00261 template <typename PointT> bool
00262 addPointCloud (const pcl::PointCloud<PointT> &cloud,
00263 const ColorHandlerConstPtr &color_handler,
00264 const std::string &id = "cloud", int viewport = 0);
00265
00273 template <typename PointT> bool
00274 addPointCloud (const pcl::PointCloud<PointT> &cloud,
00275 const GeometryHandlerConstPtr &geometry_handler,
00276 const ColorHandlerConstPtr &color_handler,
00277 const std::string &id = "cloud", int viewport = 0);
00278
00286 template <typename PointT> bool
00287 addPointCloud (const pcl::PointCloud<PointT> &cloud,
00288 const PointCloudColorHandler<PointT> &color_handler,
00289 const PointCloudGeometryHandler<PointT> &geometry_handler,
00290 const std::string &id = "cloud", int viewport = 0);
00291
00295 inline int getColorHandlerIndex (const std::string &id)
00296 {
00297 CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id);
00298 if (am_it == cloud_actor_map_.end ())
00299 return (-1);
00300
00301 return (am_it->second.color_handler_index_);
00302 }
00306 inline int getGeometryHandlerIndex (const std::string &id)
00307 {
00308 CloudActorMap::iterator am_it = style_->getCloudActorMap ()->find (id);
00309 if (am_it != cloud_actor_map_.end ())
00310 return (-1);
00311
00312 return (am_it->second.geometry_handler_index_);
00313 }
00314
00319 bool updateColorHandlerIndex (const std::string &id, int index);
00320
00329 bool setPointCloudRenderingProperties (int property, double val1, double val2, double val3, const std::string &id = "cloud", int viewport = 0);
00330
00337 bool setPointCloudRenderingProperties (int property, double value, const std::string &id = "cloud", int viewport = 0);
00338
00344 bool getPointCloudRenderingProperties (int property, double &value, const std::string &id = "cloud");
00345
00352 bool setShapeRenderingProperties (int property, double value, const std::string &id, int viewport = 0);
00353
00355 bool wasStopped () const { return (interactor_->stopped); }
00357 void resetStoppedFlag () { interactor_->stopped = false; }
00358
00366 void createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport);
00367
00377 template <typename PointT> bool
00378 addPolygon (const pcl::PointCloud<PointT> &cloud, double r, double g, double b, const std::string &id = "polygon", int viewport = 0);
00379
00386 template <typename PointT> bool
00387 addPolygon (const pcl::PointCloud<PointT> &cloud, const std::string &id = "polygon", int viewport = 0);
00388
00395 template <typename P1, typename P2> bool addLine (const P1 &pt1, const P2 &pt2, const std::string &id = "line", int viewport = 0);
00396
00406 template <typename P1, typename P2> bool addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b, const std::string &id = "line", int viewport = 0);
00407
00414
00415
00422 template <typename PointT> bool addSphere (const PointT ¢er, double radius, const std::string &id = "sphere", int viewport = 0);
00423
00433 template <typename PointT> bool addSphere (const PointT ¢er, double radius, double r, double g, double b, const std::string &id = "sphere", int viewport = 0);
00434
00440 bool addModelFromPLYFile (const std::string & filename, const std::string & id = "PLYModel", int viewport = 0);
00441
00449 bool addModelFromPLYFile (const std::string & filename, vtkSmartPointer<vtkTransform> transform, const std::string & id =
00450 "PLYModel", int viewport = 0);
00456 bool addCylinder (const pcl::ModelCoefficients &coefficients, const std::string &id = "cylinder", int viewport = 0);
00462 bool addSphere (const pcl::ModelCoefficients &coefficients, const std::string &id = "sphere", int viewport = 0);
00468 bool addLine (const pcl::ModelCoefficients &coefficients, const std::string &id = "line", int viewport = 0);
00474 bool addPlane (const pcl::ModelCoefficients &coefficients, const std::string &id = "plane", int viewport = 0);
00480 bool addCircle (const pcl::ModelCoefficients &coefficients, const std::string &id = "circle", int viewport = 0);
00486 bool addCone (const pcl::ModelCoefficients &coefficients, const std::string &id = "cone", int viewport = 0);
00487
00489 Camera camera_;
00490
00492 void initCameraParameters ();
00493
00498 bool getCameraParameters (int argc, char **argv);
00499
00501 void updateCamera ();
00502
00504 void resetCamera ();
00505
00506 protected:
00508 vtkSmartPointer<PCLVisualizerInteractor> interactor_;
00509
00510 private:
00511 struct ExitMainLoopTimerCallback : public vtkCommand
00512 {
00513 static ExitMainLoopTimerCallback* New()
00514 {
00515 return new ExitMainLoopTimerCallback;
00516 }
00517 virtual void Execute(vtkObject* vtkNotUsed(caller), unsigned long event_id, void* call_data)
00518 {
00519 if (event_id != vtkCommand::TimerEvent)
00520 return;
00521 int timer_id = *(int*)call_data;
00522
00523 if (timer_id != right_timer_id)
00524 return;
00525
00526 pcl_visualizer->interactor_->stopLoop ();
00527 }
00528 int right_timer_id;
00529 PCLVisualizer* pcl_visualizer;
00530 };
00531 struct ExitCallback : public vtkCommand
00532 {
00533 static ExitCallback* New ()
00534 {
00535 return new ExitCallback;
00536 }
00537 virtual void Execute (vtkObject* caller, unsigned long event_id, void* call_data)
00538 {
00539 if (event_id != vtkCommand::ExitEvent)
00540 return;
00541
00542 pcl_visualizer->interactor_->stopped = true;
00543 }
00544 PCLVisualizer* pcl_visualizer;
00545 };
00546
00547
00549 vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
00550 vtkSmartPointer<ExitCallback> exit_callback_;
00551
00553 vtkSmartPointer<vtkRendererCollection> rens_;
00555 vtkSmartPointer<vtkRenderWindow> win_;
00556
00558 vtkSmartPointer<PCLVisualizerInteractorStyle> style_;
00559
00561 CloudActorMap cloud_actor_map_;
00562
00564 ShapeActorMap shape_actor_map_;
00565
00566
00571 void removeActorFromRenderer (const vtkSmartPointer<vtkLODActor> &actor, int viewport = 0);
00572
00577 void addActorToRenderer (const vtkSmartPointer<vtkProp> &actor, int viewport = 0);
00578
00583 void removeActorFromRenderer (const vtkSmartPointer<vtkProp> &actor, int viewport = 0);
00584
00589 void createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data, vtkSmartPointer<vtkLODActor> &actor);
00590
00595 void convertPointCloudToVTKPolyData (const pcl::PointCloud<pcl::PointXYZ> &cloud, vtkSmartPointer<vtkPolyData> &polydata);
00596
00601 template <typename PointT> void
00602 convertPointCloudToVTKPolyData (const pcl::PointCloud<PointT> &cloud, vtkSmartPointer<vtkPolyData> &polydata);
00603
00608 template <typename PointT> void
00609 convertPointCloudToVTKPolyData (const PointCloudGeometryHandler<PointT> &geometry_handler, vtkSmartPointer<vtkPolyData> &polydata);
00610
00615 void convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler, vtkSmartPointer<vtkPolyData> &polydata);
00616 };
00617 }
00618
00619 #include "libpcl_visualization/pcl_visualizer.hpp"
00620
00621 #endif