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_VISUALIZATION_IMAGE_VISUALIZER_H__
00040 #define PCL_VISUALIZATION_IMAGE_VISUALIZER_H__
00041
00042 #include <pcl/pcl_macros.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/console/print.h>
00045 #include <pcl/visualization/interactor.h>
00046 #include <pcl/visualization/interactor_style.h>
00047 #include <pcl/visualization/vtk/pcl_image_canvas_source_2d.h>
00048 #include <pcl/visualization/vtk/pcl_context_item.h>
00049 #include <pcl/geometry/planar_polygon.h>
00050 #include <pcl/correspondence.h>
00051
00052 #include <boost/shared_array.hpp>
00053
00054 #include <vtkInteractorStyleImage.h>
00055
00056 class vtkImageSlice;
00057 class vtkContextActor;
00058 class vtkImageViewer;
00059 class vtkImageFlip;
00060
00061 namespace pcl
00062 {
00063 namespace visualization
00064 {
00065 typedef Eigen::Array<unsigned char, 3, 1> Vector3ub;
00066 static const Vector3ub green_color (0, 255, 0);
00067 static const Vector3ub red_color (255, 0, 0);
00068 static const Vector3ub blue_color (0, 0, 255);
00069
00074 class PCL_EXPORTS ImageViewerInteractorStyle : public vtkInteractorStyleImage
00075 {
00076 public:
00077 static ImageViewerInteractorStyle *New ();
00078 ImageViewerInteractorStyle ();
00079
00080 virtual void OnMouseWheelForward () {}
00081 virtual void OnMouseWheelBackward () {}
00082 virtual void OnMiddleButtonDown () {}
00083 virtual void OnRightButtonDown () {}
00084 virtual void OnLeftButtonDown ();
00085
00086 virtual void
00087 OnChar ();
00088
00089 void
00090 adjustCamera (vtkImageData *image, vtkRenderer *ren);
00091
00092 void
00093 adjustCamera (vtkRenderer *ren);
00094 };
00095
00117 class PCL_EXPORTS ImageViewer
00118 {
00119 public:
00120 typedef boost::shared_ptr<ImageViewer> Ptr;
00121
00125 ImageViewer (const std::string& window_title = "");
00126
00128 virtual ~ImageViewer ();
00129
00137 void
00138 showMonoImage (const unsigned char* data, unsigned width, unsigned height,
00139 const std::string &layer_id = "mono_image", double opacity = 1.0);
00140
00148 void
00149 addMonoImage (const unsigned char* data, unsigned width, unsigned height,
00150 const std::string &layer_id = "mono_image", double opacity = 1.0);
00151
00157 inline void
00158 showMonoImage (const pcl::PointCloud<pcl::Intensity>::ConstPtr &cloud,
00159 const std::string &layer_id = "mono_image", double opacity = 1.0)
00160 {
00161 return (showMonoImage (*cloud, layer_id, opacity));
00162 }
00163
00169 inline void
00170 addMonoImage (const pcl::PointCloud<pcl::Intensity>::ConstPtr &cloud,
00171 const std::string &layer_id = "mono_image", double opacity = 1.0)
00172 {
00173 return (addMonoImage (*cloud, layer_id, opacity));
00174 }
00175
00181 void
00182 showMonoImage (const pcl::PointCloud<pcl::Intensity> &cloud,
00183 const std::string &layer_id = "mono_image", double opacity = 1.0);
00184
00190 void
00191 addMonoImage (const pcl::PointCloud<pcl::Intensity> &cloud,
00192 const std::string &layer_id = "mono_image", double opacity = 1.0);
00193
00199 inline void
00200 showMonoImage (const pcl::PointCloud<pcl::Intensity8u>::ConstPtr &cloud,
00201 const std::string &layer_id = "mono_image", double opacity = 1.0)
00202 {
00203 return (showMonoImage (*cloud, layer_id, opacity));
00204 }
00205
00211 inline void
00212 addMonoImage (const pcl::PointCloud<pcl::Intensity8u>::ConstPtr &cloud,
00213 const std::string &layer_id = "mono_image", double opacity = 1.0)
00214 {
00215 return (addMonoImage (*cloud, layer_id, opacity));
00216 }
00217
00223 void
00224 showMonoImage (const pcl::PointCloud<pcl::Intensity8u> &cloud,
00225 const std::string &layer_id = "mono_image", double opacity = 1.0);
00226
00232 void
00233 addMonoImage (const pcl::PointCloud<pcl::Intensity8u> &cloud,
00234 const std::string &layer_id = "mono_image", double opacity = 1.0);
00235
00243 void
00244 showRGBImage (const unsigned char* data, unsigned width, unsigned height,
00245 const std::string &layer_id = "rgb_image", double opacity = 1.0);
00246
00254 void
00255 addRGBImage (const unsigned char* data, unsigned width, unsigned height,
00256 const std::string &layer_id = "rgb_image", double opacity = 1.0);
00257
00263 template <typename T> inline void
00264 showRGBImage (const typename pcl::PointCloud<T>::ConstPtr &cloud,
00265 const std::string &layer_id = "rgb_image", double opacity = 1.0)
00266 {
00267 return (showRGBImage<T> (*cloud, layer_id, opacity));
00268 }
00269
00275 template <typename T> inline void
00276 addRGBImage (const typename pcl::PointCloud<T>::ConstPtr &cloud,
00277 const std::string &layer_id = "rgb_image", double opacity = 1.0)
00278 {
00279 return (addRGBImage<T> (*cloud, layer_id, opacity));
00280 }
00281
00287 template <typename T> void
00288 showRGBImage (const pcl::PointCloud<T> &cloud,
00289 const std::string &layer_id = "rgb_image", double opacity = 1.0);
00290
00296 template <typename T> void
00297 addRGBImage (const pcl::PointCloud<T> &cloud,
00298 const std::string &layer_id = "rgb_image", double opacity = 1.0);
00299
00310 void
00311 showFloatImage (const float* data, unsigned int width, unsigned int height,
00312 float min_value = std::numeric_limits<float>::min (),
00313 float max_value = std::numeric_limits<float>::max (), bool grayscale = false,
00314 const std::string &layer_id = "float_image", double opacity = 1.0);
00315
00326 void
00327 addFloatImage (const float* data, unsigned int width, unsigned int height,
00328 float min_value = std::numeric_limits<float>::min (),
00329 float max_value = std::numeric_limits<float>::max (), bool grayscale = false,
00330 const std::string &layer_id = "float_image", double opacity = 1.0);
00331
00342 void
00343 showShortImage (const unsigned short* short_image, unsigned int width, unsigned int height,
00344 unsigned short min_value = std::numeric_limits<unsigned short>::min (),
00345 unsigned short max_value = std::numeric_limits<unsigned short>::max (), bool grayscale = false,
00346 const std::string &layer_id = "short_image", double opacity = 1.0);
00347
00358 void
00359 addShortImage (const unsigned short* short_image, unsigned int width, unsigned int height,
00360 unsigned short min_value = std::numeric_limits<unsigned short>::min (),
00361 unsigned short max_value = std::numeric_limits<unsigned short>::max (), bool grayscale = false,
00362 const std::string &layer_id = "short_image", double opacity = 1.0);
00363
00371 void
00372 showAngleImage (const float* data, unsigned width, unsigned height,
00373 const std::string &layer_id = "angle_image", double opacity = 1.0);
00374
00382 void
00383 addAngleImage (const float* data, unsigned width, unsigned height,
00384 const std::string &layer_id = "angle_image", double opacity = 1.0);
00385
00393 void
00394 showHalfAngleImage (const float* data, unsigned width, unsigned height,
00395 const std::string &layer_id = "half_angle_image", double opacity = 1.0);
00396
00404 void
00405 addHalfAngleImage (const float* data, unsigned width, unsigned height,
00406 const std::string &layer_id = "half_angle_image", double opacity = 1.0);
00407
00417 void
00418 markPoint (size_t u, size_t v, Vector3ub fg_color, Vector3ub bg_color = red_color, double radius = 3.0,
00419 const std::string &layer_id = "points", double opacity = 1.0);
00420
00424 void
00425 setWindowTitle (const std::string& name);
00426
00428 void
00429 spin ();
00430
00436 void
00437 spinOnce (int time = 1, bool force_redraw = true);
00438
00444 boost::signals2::connection
00445 registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*),
00446 void* cookie = NULL)
00447 {
00448 return (registerKeyboardCallback (boost::bind (callback, _1, cookie)));
00449 }
00450
00457 template<typename T> boost::signals2::connection
00458 registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*),
00459 T& instance, void* cookie = NULL)
00460 {
00461 return (registerKeyboardCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00462 }
00463
00468 boost::signals2::connection
00469 registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> cb);
00470
00476 boost::signals2::connection
00477 registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*),
00478 void* cookie = NULL)
00479 {
00480 return (registerMouseCallback (boost::bind (callback, _1, cookie)));
00481 }
00482
00489 template<typename T> boost::signals2::connection
00490 registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*),
00491 T& instance, void* cookie = NULL)
00492 {
00493 return (registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00494 }
00495
00500 boost::signals2::connection
00501 registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> cb);
00502
00507 void
00508 setPosition (int x, int y);
00509
00514 void
00515 setSize (int xw, int yw);
00516
00518 int*
00519 getSize ();
00520
00522 bool
00523 wasStopped () const { return (stopped_); }
00524
00526 void
00527 close ()
00528 {
00529 stopped_ = true;
00530
00531 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00532 interactor_->stopLoop ();
00533 #else
00534 interactor_->TerminateApp ();
00535 #endif
00536 }
00537
00545 bool
00546 addCircle (unsigned int x, unsigned int y, double radius,
00547 const std::string &layer_id = "circles", double opacity = 1.0);
00548
00559 bool
00560 addCircle (unsigned int x, unsigned int y, double radius,
00561 double r, double g, double b,
00562 const std::string &layer_id = "circles", double opacity = 1.0);
00563
00570 bool
00571 addRectangle (const pcl::PointXY &min_pt, const pcl::PointXY &max_pt,
00572 const std::string &layer_id = "rectangles", double opacity = 1.0);
00573
00583 bool
00584 addRectangle (const pcl::PointXY &min_pt, const pcl::PointXY &max_pt,
00585 double r, double g, double b,
00586 const std::string &layer_id = "rectangles", double opacity = 1.0);
00587
00596 bool
00597 addRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00598 const std::string &layer_id = "rectangles", double opacity = 1.0);
00599
00611 bool
00612 addRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00613 double r, double g, double b,
00614 const std::string &layer_id = "rectangles", double opacity = 1.0);
00615
00623 template <typename T> bool
00624 addRectangle (const typename pcl::PointCloud<T>::ConstPtr &image,
00625 const T &min_pt, const T &max_pt,
00626 const std::string &layer_id = "rectangles", double opacity = 1.0);
00627
00638 template <typename T> bool
00639 addRectangle (const typename pcl::PointCloud<T>::ConstPtr &image,
00640 const T &min_pt, const T &max_pt,
00641 double r, double g, double b,
00642 const std::string &layer_id = "rectangles", double opacity = 1.0);
00643
00653 template <typename T> bool
00654 addRectangle (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PointCloud<T> &mask,
00655 double r, double g, double b,
00656 const std::string &layer_id = "rectangles", double opacity = 1.0);
00657
00664 template <typename T> bool
00665 addRectangle (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PointCloud<T> &mask,
00666 const std::string &layer_id = "image_mask", double opacity = 1.0);
00667
00676 bool
00677 addFilledRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00678 const std::string &layer_id = "boxes", double opacity = 0.5);
00679
00691 bool
00692 addFilledRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00693 double r, double g, double b,
00694 const std::string &layer_id = "boxes", double opacity = 0.5);
00695
00707 bool
00708 addLine (unsigned int x_min, unsigned int y_min, unsigned int x_max, unsigned int y_max,
00709 double r, double g, double b,
00710 const std::string &layer_id = "line", double opacity = 1.0);
00711
00720 bool
00721 addLine (unsigned int x_min, unsigned int y_min, unsigned int x_max, unsigned int y_max,
00722 const std::string &layer_id = "line", double opacity = 1.0);
00723
00724
00734 template <typename T> bool
00735 addMask (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PointCloud<T> &mask,
00736 double r, double g, double b,
00737 const std::string &layer_id = "image_mask", double opacity = 0.5);
00738
00745 template <typename T> bool
00746 addMask (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PointCloud<T> &mask,
00747 const std::string &layer_id = "image_mask", double opacity = 0.5);
00748
00759 template <typename T> bool
00760 addPlanarPolygon (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PlanarPolygon<T> &polygon,
00761 double r, double g, double b,
00762 const std::string &layer_id = "planar_polygon", double opacity = 1.0);
00763
00771 template <typename T> bool
00772 addPlanarPolygon (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PlanarPolygon<T> &polygon,
00773 const std::string &layer_id = "planar_polygon", double opacity = 1.0);
00774
00781 bool
00782 addLayer (const std::string &layer_id, int width, int height, double opacity = 0.5);
00783
00787 void
00788 removeLayer (const std::string &layer_id);
00789
00797 template <typename PointT> bool
00798 showCorrespondences (const pcl::PointCloud<PointT> &source_img,
00799 const pcl::PointCloud<PointT> &target_img,
00800 const pcl::Correspondences &correspondences,
00801 int nth = 1,
00802 const std::string &layer_id = "correspondences");
00803
00804 protected:
00806 void
00807 render ();
00808
00815 void
00816 convertIntensityCloudToUChar (const pcl::PointCloud<pcl::Intensity> &cloud,
00817 boost::shared_array<unsigned char> data);
00818
00825 void
00826 convertIntensityCloud8uToUChar (const pcl::PointCloud<pcl::Intensity8u> &cloud,
00827 boost::shared_array<unsigned char> data);
00828
00835 template <typename T> void
00836 convertRGBCloudToUChar (const pcl::PointCloud<T> &cloud,
00837 boost::shared_array<unsigned char> &data);
00838
00840 void
00841 resetStoppedFlag () { stopped_ = false; }
00842
00846 void
00847 emitMouseEvent (unsigned long event_id);
00848
00852 void
00853 emitKeyboardEvent (unsigned long event_id);
00854
00855
00856 static void
00857 MouseCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata);
00858 static void
00859 KeyboardCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata);
00860
00861 protected:
00862 struct ExitMainLoopTimerCallback : public vtkCommand
00863 {
00864 ExitMainLoopTimerCallback () : right_timer_id (), window () {}
00865
00866 static ExitMainLoopTimerCallback* New ()
00867 {
00868 return (new ExitMainLoopTimerCallback);
00869 }
00870 virtual void
00871 Execute (vtkObject* vtkNotUsed (caller), unsigned long event_id, void* call_data)
00872 {
00873 if (event_id != vtkCommand::TimerEvent)
00874 return;
00875 int timer_id = *static_cast<int*> (call_data);
00876 if (timer_id != right_timer_id)
00877 return;
00878 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00879 window->interactor_->stopLoop ();
00880 #else
00881 window->interactor_->TerminateApp ();
00882 #endif
00883 }
00884 int right_timer_id;
00885 ImageViewer* window;
00886 };
00887 struct ExitCallback : public vtkCommand
00888 {
00889 ExitCallback () : window () {}
00890
00891 static ExitCallback* New ()
00892 {
00893 return (new ExitCallback);
00894 }
00895 virtual void
00896 Execute (vtkObject*, unsigned long event_id, void*)
00897 {
00898 if (event_id != vtkCommand::ExitEvent)
00899 return;
00900 window->stopped_ = true;
00901 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00902 window->interactor_->stopLoop ();
00903 #else
00904 window->interactor_->TerminateApp ();
00905 #endif
00906 }
00907 ImageViewer* window;
00908 };
00909
00910 private:
00912 struct Layer
00913 {
00914 Layer () : actor (), layer_name () {}
00915 vtkSmartPointer<vtkContextActor> actor;
00916 std::string layer_name;
00917 };
00918
00919 typedef std::vector<Layer> LayerMap;
00920
00928 LayerMap::iterator
00929 createLayer (const std::string &layer_id, int width, int height, double opacity = 0.5, bool fill_box = true);
00930
00931 boost::signals2::signal<void (const pcl::visualization::MouseEvent&)> mouse_signal_;
00932 boost::signals2::signal<void (const pcl::visualization::KeyboardEvent&)> keyboard_signal_;
00933
00934 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00935 vtkSmartPointer<PCLVisualizerInteractor> interactor_;
00936 #else
00937 vtkSmartPointer<vtkRenderWindowInteractor> interactor_;
00938 #endif
00939 vtkSmartPointer<vtkCallbackCommand> mouse_command_;
00940 vtkSmartPointer<vtkCallbackCommand> keyboard_command_;
00941
00943 vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
00944 vtkSmartPointer<ExitCallback> exit_callback_;
00945
00947 vtkSmartPointer<vtkImageViewer> image_viewer_;
00948
00950 vtkSmartPointer<vtkRenderWindow> win_;
00951
00953 vtkSmartPointer<vtkRenderer> ren_;
00954
00955 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION >= 10))
00956
00957 vtkSmartPointer<vtkImageSlice> slice_;
00958 #endif
00959
00960 vtkSmartPointer<ImageViewerInteractorStyle> interactor_style_;
00961
00963 boost::shared_array<unsigned char> data_;
00964
00966 size_t data_size_;
00967
00969 bool stopped_;
00970
00972 int timer_id_;
00973
00974
00975
00976
00978 LayerMap layer_map_;
00979
00981 vtkSmartPointer<vtkImageFlip> algo_;
00982
00986 std::vector<unsigned char*> image_data_;
00987
00988 struct LayerComparator
00989 {
00990 LayerComparator (const std::string &str) : str_ (str) {}
00991 const std::string &str_;
00992
00993 bool
00994 operator () (const Layer &layer)
00995 {
00996 return (layer.layer_name == str_);
00997 }
00998 };
00999
01000 public:
01001 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
01002 };
01003 }
01004 }
01005
01006 #include <pcl/visualization/impl/image_viewer.hpp>
01007
01008 #endif
01009