Go to the documentation of this file.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
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/vtk.h>
00044 #include <pcl/visualization/common/common.h>
00045 #include <pcl/visualization/common/ren_win_interact_map.h>
00046
00047 namespace pcl
00048 {
00049 namespace visualization
00050 {
00055 class PCL_EXPORTS PCLHistogramVisualizer
00056 {
00057 public:
00059 PCLHistogramVisualizer ();
00060
00061 virtual ~PCLHistogramVisualizer () {}
00065 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00066 void
00067 spinOnce (int time = 1, bool force_redraw = false);
00068 #else
00069 void
00070 spinOnce (int time = 1);
00071 #endif
00072
00073 void
00074 spin ();
00075
00082 void
00083 setBackgroundColor (const double &r, const double &g, const double &b, int viewport = 0);
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 sensor_msgs::PointCloud2 &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 sensor_msgs::PointCloud2 &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 sensor_msgs::PointCloud2 &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 sensor_msgs::PointCloud2 &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* vtkNotUsed (caller), unsigned long event_id, void* call_data)
00234 {
00235 if (event_id != vtkCommand::TimerEvent)
00236 return;
00237 int timer_id = *(reinterpret_cast<int*> (call_data));
00238
00239 if (timer_id != right_timer_id)
00240 return;
00241
00242
00243 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00244 interact->stopLoop ();
00245 #else
00246 interact->TerminateApp ();
00247 #endif
00248 }
00249 int right_timer_id;
00250 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00251 PCLVisualizerInteractor *interact;
00252 #else
00253 vtkRenderWindowInteractor *interact;
00254 #endif
00255 };
00256
00257 struct ExitCallback : public vtkCommand
00258 {
00259 ExitCallback () : his () {}
00260
00261 static ExitCallback* New ()
00262 {
00263 return (new ExitCallback);
00264 }
00265
00266 virtual void
00267 Execute (vtkObject*, unsigned long event_id, void*)
00268 {
00269 if (event_id != vtkCommand::ExitEvent)
00270 return;
00271 his->stopped_ = true;
00272 }
00273 PCLHistogramVisualizer *his;
00274 };
00275
00277 vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
00278 vtkSmartPointer<ExitCallback> exit_callback_;
00280 bool stopped_;
00281 };
00282 }
00283 }
00284
00285 #include <pcl/visualization/impl/histogram_visualizer.hpp>
00286
00287 #endif