histogram_visualizer.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  *
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$
00037  *
00038  */
00039 #ifndef PCL_PCL_HISTOGRAM_VISUALIZER_H_
00040 #define PCL_PCL_HISTOGRAM_VISUALIZER_H_
00041 
00042 #include <pcl/visualization/interactor_style.h>
00043 #include <pcl/visualization/common/common.h>
00044 #include <pcl/visualization/common/ren_win_interact_map.h>
00045 
00046 class vtkRenderWindowInteractor;
00047 
00048 namespace pcl
00049 {
00050   namespace visualization
00051   {
00056     class PCL_EXPORTS PCLHistogramVisualizer
00057     {
00058       public:
00060         PCLHistogramVisualizer ();
00061 
00062         virtual ~PCLHistogramVisualizer () {}
00066 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00067         void 
00068         spinOnce (int time = 1, bool force_redraw = false);
00069 #else
00070         void 
00071         spinOnce (int time = 1);
00072 #endif
00073 
00074         void 
00075         spin ();
00076         
00082         void 
00083         setBackgroundColor (const double &r, const double &g, const double &b);
00084 
00092         template <typename PointT> bool 
00093         addFeatureHistogram (const pcl::PointCloud<PointT> &cloud, 
00094                              int hsize, 
00095                              const std::string &id = "cloud", int win_width = 640, int win_height = 200);
00096 
00104         bool 
00105         addFeatureHistogram (const pcl::PCLPointCloud2 &cloud,
00106                              const std::string &field_name, 
00107                              const std::string &id = "cloud", int win_width = 640, int win_height = 200);
00108 
00117         template <typename PointT> bool 
00118         addFeatureHistogram (const pcl::PointCloud<PointT> &cloud, 
00119                              const std::string &field_name, 
00120                              const int index,
00121                              const std::string &id = "cloud", int win_width = 640, int win_height = 200);
00122 
00131         bool 
00132         addFeatureHistogram (const pcl::PCLPointCloud2 &cloud,
00133                              const std::string &field_name, 
00134                              const int index,
00135                              const std::string &id = "cloud", int win_width = 640, int win_height = 200);
00136         
00142         template <typename PointT> bool 
00143         updateFeatureHistogram (const pcl::PointCloud<PointT> &cloud, int hsize, const std::string &id = "cloud");
00144         
00145                              
00151         bool 
00152         updateFeatureHistogram (const pcl::PCLPointCloud2 &cloud,
00153                                 const std::string &field_name, 
00154                                 const std::string &id = "cloud");
00155                              
00156         
00163         template <typename PointT> bool 
00164         updateFeatureHistogram (const pcl::PointCloud<PointT> &cloud, const std::string &field_name,
00165                                                    const int index, const std::string &id = "cloud");
00166         
00167                              
00174         bool 
00175         updateFeatureHistogram (const pcl::PCLPointCloud2 &cloud,
00176                                 const std::string &field_name, const int index,
00177                                 const std::string &id = "cloud");         
00178 
00179 
00184         void 
00185         setGlobalYRange (float minp, float maxp);
00186 
00188         void 
00189         updateWindowPositions ();
00190 #if ((VTK_MAJOR_VERSION) == 5 && (VTK_MINOR_VERSION <= 4))
00191 
00192         bool 
00193         wasStopped ();
00194         
00196         void 
00197         resetStoppedFlag ();
00198 #endif
00199       protected:
00200 
00208         void
00209         createActor (const vtkSmartPointer<vtkDoubleArray> &xy_array, 
00210                      RenWinInteract &renwinint,
00211                      const std::string &id, const int win_width, const int win_height);
00212         
00218         void
00219         reCreateActor (const vtkSmartPointer<vtkDoubleArray> &xy_array, 
00220                        RenWinInteract* renwinupd, const int hsize);
00221 
00222       private:
00224         RenWinInteractMap wins_;
00225 
00226         struct ExitMainLoopTimerCallback : public vtkCommand
00227         {
00228           static ExitMainLoopTimerCallback* New ()
00229           {
00230             return (new ExitMainLoopTimerCallback);
00231           }
00232           virtual void 
00233           Execute (vtkObject*, unsigned long event_id, void* call_data);
00234 
00235           int right_timer_id;
00236 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00237           PCLVisualizerInteractor *interact;
00238 #else
00239           vtkRenderWindowInteractor *interact;
00240 #endif
00241         };
00242         
00243         struct ExitCallback : public vtkCommand
00244         {
00245           ExitCallback () : his () {}
00246 
00247           static ExitCallback* New ()
00248           {
00249             return (new ExitCallback);
00250           }
00251 
00252           virtual void 
00253           Execute (vtkObject*, unsigned long event_id, void*);
00254 
00255           PCLHistogramVisualizer *his;
00256         };
00257 
00259         vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
00260         vtkSmartPointer<ExitCallback> exit_callback_;
00262         bool stopped_;
00263     };
00264   }
00265 }
00266 
00267 #include <pcl/visualization/impl/histogram_visualizer.hpp>
00268 
00269 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:43