pcl_plotter.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 #ifndef PCL_VISUALUALIZATION_PCL_PLOTTER_H_
00039 #define PCL_VISUALUALIZATION_PCL_PLOTTER_H_
00040 
00041 #include <iostream>
00042 #include <vector>
00043 #include <utility>
00044 #include <cfloat>
00045 
00046 #include <pcl/visualization/common/common.h>
00047 #include <pcl/point_types.h>
00048 #include <pcl/correspondence.h>
00049 #include <pcl/point_cloud.h>
00050 #include <pcl/common/io.h>
00051 
00052 class PCLVisualizerInteractor;
00053 template <typename T> class vtkSmartPointer;
00054 class vtkRenderWindowInteractor;
00055 class vtkContextView;
00056 class vtkChartXY;
00057 class vtkColorSeries;
00058 
00059 #include <vtkCommand.h>
00060 #include <vtkChart.h>
00061 
00062 namespace pcl
00063 {
00064   namespace visualization
00065   {
00076     class PCL_EXPORTS PCLPlotter
00077     {
00078       public:
00079         
00082         typedef std::vector<double> PolynomialFunction;
00083         
00086         typedef std::pair<PolynomialFunction, PolynomialFunction> RationalFunction;
00087         
00091         PCLPlotter (char const * name = "PCL Plotter");
00092 
00094         ~PCLPlotter();
00095 
00104         void 
00105         addPlotData (double const *array_X, 
00106                      double const *array_Y, 
00107                      unsigned long size, 
00108                      char const * name = "Y Axis", 
00109                      int type  = vtkChart::LINE ,
00110                      char const *color=NULL);
00111         
00120         void 
00121         addPlotData (std::vector<double> const &array_X, 
00122                      std::vector<double>const &array_Y, 
00123                      char const * name = "Y Axis", 
00124                      int type = vtkChart::LINE,
00125                      std::vector<char> const &color = std::vector<char> ());
00126         
00132         void
00133         addPlotData (std::vector<std::pair<double, double> > const &plot_data, 
00134                     char const * name = "Y Axis",
00135                     int type = vtkChart::LINE,
00136                     std::vector<char> const &color = std::vector<char>());
00137         
00147         void
00148         addPlotData (PolynomialFunction const & p_function,
00149                      double x_min, double x_max,
00150                      char const *name = "Y Axis",
00151                      int num_points = 100,
00152                      int type = vtkChart::LINE,
00153                      std::vector<char> const &color = std::vector<char>());
00154         
00164         void
00165         addPlotData (RationalFunction const & r_function,
00166                      double x_min, double x_max,
00167                      char const *name = "Y Axis",
00168                      int num_points = 100,
00169                      int type = vtkChart::LINE,
00170                      std::vector<char> const &color = std::vector<char>());
00171         
00181         void
00182         addPlotData (double (*function)(double),
00183                      double x_min, double x_max,
00184                      char const *name = "Y Axis",
00185                      int num_points = 100,
00186                      int type = vtkChart::LINE,
00187                      std::vector<char> const &color = std::vector<char>());
00188         
00193         void
00194         addPlotData (char const * filename,
00195                      int type = vtkChart::LINE);
00196                     
00203         void
00204         addHistogramData (std::vector<double> const & data, 
00205                           int const nbins = 10, 
00206                           char const * name = "Histogram", 
00207                           std::vector<char> const &color = std::vector<char>());
00208         
00209         //##PCLHistogramVisulizer methods##
00217         template <typename PointT> bool 
00218         addFeatureHistogram (const pcl::PointCloud<PointT> &cloud, 
00219                              int hsize, 
00220                              const std::string &id = "cloud", int win_width = 640, int win_height = 200);
00221         
00229         bool 
00230         addFeatureHistogram (const pcl::PCLPointCloud2 &cloud,
00231                              const std::string &field_name, 
00232                              const std::string &id = "cloud", int win_width = 640, int win_height = 200);
00233         
00242         template <typename PointT> bool 
00243         addFeatureHistogram (const pcl::PointCloud<PointT> &cloud, 
00244                              const std::string &field_name, 
00245                              const int index,
00246                              const std::string &id = "cloud", int win_width = 640, int win_height = 200);
00247         
00256         bool 
00257         addFeatureHistogram (const pcl::PCLPointCloud2 &cloud,
00258                              const std::string &field_name, 
00259                              const int index,
00260                              const std::string &id = "cloud", int win_width = 640, int win_height = 200);
00261         
00263         void 
00264         plot ();
00265         
00269         void 
00270         spinOnce (const int spin_time = 1);
00271         
00273         void 
00274         spin ();
00275         
00277         void
00278         clearPlots();
00279         
00283         void
00284         setColorScheme (int scheme);
00285         
00289         int 
00290         getColorScheme ();
00291         
00297         void 
00298         setBackgroundColor (const double r, const double g, const double b);
00299         
00303         void
00304         setBackgroundColor (const double color[3]);
00305         
00309         double *
00310         getBackgroundColor ();
00311         
00316         void 
00317         setXRange (double min, double max);
00318         
00323         void
00324         setYRange (double min, double max);
00325         
00329         void 
00330         setTitle (const char *title);
00331         
00335         void 
00336         setXTitle (const char *title);
00337         
00341         void 
00342         setYTitle (const char *title);
00343         
00347         void 
00348         setShowLegend (bool flag);
00349         
00354         void
00355         setWindowSize (int w, int h);
00356         
00360         int*
00361         getWindowSize ();
00362 
00364         vtkSmartPointer<vtkRenderWindow>
00365         getRenderWindow ();
00366         
00368         void
00369         setViewInteractor (vtkSmartPointer<vtkRenderWindowInteractor> interactor);
00370         
00372         void
00373         startInteractor ();
00374         
00376         void renderOnce();
00377 
00379         bool
00380         wasStopped () const;
00381         
00383         void
00384         close ();
00385       
00386       private:
00387         vtkSmartPointer<vtkContextView> view_;  
00388         vtkSmartPointer<vtkChartXY> chart_;
00389         vtkSmartPointer<vtkColorSeries> color_series_;   //for automatic coloring
00390         
00391         //extra state variables
00392         int current_plot_;          //stores the id of the current (most recent) plot, used in automatic coloring and other state change schemes 
00393         int win_width_, win_height_;
00394         double bkg_color_[3];
00395           
00396         //####event callback class####
00397         struct ExitMainLoopTimerCallback : public vtkCommand
00398         {
00399           static ExitMainLoopTimerCallback* New ()
00400           {
00401             return (new ExitMainLoopTimerCallback);
00402           }
00403           virtual void 
00404           Execute (vtkObject*, unsigned long event_id, void* call_data);
00405 
00406           int right_timer_id;
00407 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00408           PCLVisualizerInteractor *interactor;
00409 #else
00410           vtkRenderWindowInteractor *interactor;
00411 #endif
00412         };
00413         
00414         struct ExitCallback : public vtkCommand
00415         {
00416           static ExitCallback* New ()
00417           {
00418             return new ExitCallback;
00419           }
00420           virtual void 
00421           Execute (vtkObject*, unsigned long event_id, void*);
00422 
00423           PCLPlotter *plotter;
00424         };
00425         
00427         bool stopped_;
00428         
00430         vtkSmartPointer<ExitMainLoopTimerCallback> exit_loop_timer_;
00431         vtkSmartPointer<ExitCallback> exit_callback_;
00432         
00434 
00438         double 
00439         compute (PolynomialFunction const & p_function, double val);
00440         
00445         double 
00446         compute (RationalFunction const & r_function, double val);
00447         
00453         void 
00454         computeHistogram (std::vector<double> const & data, int const nbins, std::vector<std::pair<double, double> > &histogram);
00455     };
00456   }
00457 }
00458 
00459 #include <pcl/visualization/impl/pcl_plotter.hpp>
00460 
00461 #endif  /* PCL_VISUALUALIZATION_PCL_PLOTTER_H_ */
00462 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:28:09