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 #ifndef PCL_VISUALIZATION_IMAGE_VISUALIZER_H__
00039 #define PCL_VISUALIZATION_IMAGE_VISUALIZER_H__
00040
00041 #include <boost/shared_array.hpp>
00042 #include <pcl/pcl_macros.h>
00043 #include <pcl/console/print.h>
00044 #include <boost/signals2.hpp>
00045 #include <pcl/visualization/interactor_style.h>
00046 #include <pcl/visualization/vtk.h>
00047 #include <pcl/visualization/vtk/pcl_image_canvas_source_2d.h>
00048 #include <pcl/geometry/planar_polygon.h>
00049
00050 namespace pcl
00051 {
00052 namespace visualization
00053 {
00054 typedef Eigen::Array<unsigned char, 3, 1> Vector3ub;
00055 static const Vector3ub green_color (0, 255, 0);
00056 static const Vector3ub red_color (255, 0, 0);
00057 static const Vector3ub blue_color (0, 0, 255);
00058
00080 class PCL_EXPORTS ImageViewer
00081 {
00082 public:
00086 ImageViewer (const std::string& window_title = "");
00087
00089 virtual ~ImageViewer ();
00090
00098 void
00099 showMonoImage (const unsigned char* data, unsigned width, unsigned height,
00100 const std::string &layer_id = "mono_image", double opacity = 1.0);
00101
00109 void
00110 addMonoImage (const unsigned char* data, unsigned width, unsigned height,
00111 const std::string &layer_id = "mono_image", double opacity = 1.0);
00112
00120 void
00121 showRGBImage (const unsigned char* data, unsigned width, unsigned height,
00122 const std::string &layer_id = "rgb_image", double opacity = 1.0);
00123
00131 void
00132 addRGBImage (const unsigned char* data, unsigned width, unsigned height,
00133 const std::string &layer_id = "rgb_image", double opacity = 1.0);
00134
00140 template <typename T> inline void
00141 showRGBImage (const typename pcl::PointCloud<T>::ConstPtr &cloud,
00142 const std::string &layer_id = "rgb_image", double opacity = 1.0)
00143 {
00144 return (showRGBImage<T> (*cloud, layer_id, opacity));
00145 }
00146
00152 template <typename T> inline void
00153 addRGBImage (const typename pcl::PointCloud<T>::ConstPtr &cloud,
00154 const std::string &layer_id = "rgb_image", double opacity = 1.0)
00155 {
00156 return (addRGBImage<T> (*cloud, layer_id, opacity));
00157 }
00158
00164 template <typename T> void
00165 showRGBImage (const pcl::PointCloud<T> &cloud,
00166 const std::string &layer_id = "rgb_image", double opacity = 1.0);
00167
00173 template <typename T> void
00174 addRGBImage (const pcl::PointCloud<T> &cloud,
00175 const std::string &layer_id = "rgb_image", double opacity = 1.0);
00176
00187 void
00188 showFloatImage (const float* data, unsigned int width, unsigned int height,
00189 float min_value = std::numeric_limits<float>::min (),
00190 float max_value = std::numeric_limits<float>::max (), bool grayscale = false,
00191 const std::string &layer_id = "float_image", double opacity = 1.0);
00192
00203 void
00204 addFloatImage (const float* data, unsigned int width, unsigned int height,
00205 float min_value = std::numeric_limits<float>::min (),
00206 float max_value = std::numeric_limits<float>::max (), bool grayscale = false,
00207 const std::string &layer_id = "float_image", double opacity = 1.0);
00208
00219 void
00220 showShortImage (const unsigned short* short_image, unsigned int width, unsigned int height,
00221 unsigned short min_value = std::numeric_limits<unsigned short>::min (),
00222 unsigned short max_value = std::numeric_limits<unsigned short>::max (), bool grayscale = false,
00223 const std::string &layer_id = "short_image", double opacity = 1.0);
00224
00235 void
00236 addShortImage (const unsigned short* short_image, unsigned int width, unsigned int height,
00237 unsigned short min_value = std::numeric_limits<unsigned short>::min (),
00238 unsigned short max_value = std::numeric_limits<unsigned short>::max (), bool grayscale = false,
00239 const std::string &layer_id = "short_image", double opacity = 1.0);
00240
00248 void
00249 showAngleImage (const float* data, unsigned width, unsigned height,
00250 const std::string &layer_id = "angle_image", double opacity = 1.0);
00251
00259 void
00260 addAngleImage (const float* data, unsigned width, unsigned height,
00261 const std::string &layer_id = "angle_image", double opacity = 1.0);
00262
00270 void
00271 showHalfAngleImage (const float* data, unsigned width, unsigned height,
00272 const std::string &layer_id = "half_angle_image", double opacity = 1.0);
00273
00281 void
00282 addHalfAngleImage (const float* data, unsigned width, unsigned height,
00283 const std::string &layer_id = "half_angle_image", double opacity = 1.0);
00284
00294 void
00295 markPoint (size_t u, size_t v, Vector3ub fg_color, Vector3ub bg_color = red_color, double radius = 3.0,
00296 const std::string &layer_id = "points", double opacity = 1.0);
00297
00301 void
00302 setWindowTitle (const std::string& name)
00303 {
00304 image_viewer_->GetRenderWindow ()->SetWindowName (name.c_str ());
00305 }
00306
00308 void
00309 spin ();
00310
00316 void
00317 spinOnce (int time = 1, bool force_redraw = true);
00318
00324 boost::signals2::connection
00325 registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*),
00326 void* cookie = NULL)
00327 {
00328 return (registerKeyboardCallback (boost::bind (callback, _1, cookie)));
00329 }
00330
00337 template<typename T> boost::signals2::connection
00338 registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*),
00339 T& instance, void* cookie = NULL)
00340 {
00341 return (registerKeyboardCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00342 }
00343
00348 boost::signals2::connection
00349 registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> cb);
00350
00356 boost::signals2::connection
00357 registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*),
00358 void* cookie = NULL)
00359 {
00360 return (registerMouseCallback (boost::bind (callback, _1, cookie)));
00361 }
00362
00369 template<typename T> boost::signals2::connection
00370 registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*),
00371 T& instance, void* cookie = NULL)
00372 {
00373 return (registerMouseCallback (boost::bind (callback, boost::ref (instance), _1, cookie)));
00374 }
00375
00380 boost::signals2::connection
00381 registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> cb);
00382
00387 void
00388 setPosition (int x, int y)
00389 {
00390 image_viewer_->SetPosition (x, y);
00391 }
00392
00397 void
00398 setSize (int xw, int yw)
00399 {
00400 image_viewer_->SetSize (xw, yw);
00401 }
00402
00404 bool
00405 wasStopped () const { if (image_viewer_) return (stopped_); else return (true); }
00406
00414 bool
00415 addCircle (unsigned int x, unsigned int y, double radius,
00416 const std::string &layer_id = "circles", double opacity = 1.0);
00417
00428 bool
00429 addCircle (unsigned int x, unsigned int y, double radius,
00430 double r, double g, double b,
00431 const std::string &layer_id = "circles", double opacity = 1.0);
00432
00439 bool
00440 addRectangle (const pcl::PointXY &min_pt, const pcl::PointXY &max_pt,
00441 const std::string &layer_id = "rectangles", double opacity = 1.0);
00442
00452 bool
00453 addRectangle (const pcl::PointXY &min_pt, const pcl::PointXY &max_pt,
00454 double r, double g, double b,
00455 const std::string &layer_id = "rectangles", double opacity = 1.0);
00456
00465 bool
00466 addRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00467 const std::string &layer_id = "rectangles", double opacity = 1.0);
00468
00480 bool
00481 addRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00482 double r, double g, double b,
00483 const std::string &layer_id = "rectangles", double opacity = 1.0);
00484
00492 template <typename T> bool
00493 addRectangle (const typename pcl::PointCloud<T>::ConstPtr &image,
00494 const T &min_pt, const T &max_pt,
00495 const std::string &layer_id = "rectangles", double opacity = 1.0);
00496
00507 template <typename T> bool
00508 addRectangle (const typename pcl::PointCloud<T>::ConstPtr &image,
00509 const T &min_pt, const T &max_pt,
00510 double r, double g, double b,
00511 const std::string &layer_id = "rectangles", double opacity = 1.0);
00512
00522 template <typename T> bool
00523 addRectangle (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PointCloud<T> &mask,
00524 double r, double g, double b,
00525 const std::string &layer_id = "rectangles", double opacity = 1.0);
00526
00533 template <typename T> bool
00534 addRectangle (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PointCloud<T> &mask,
00535 const std::string &layer_id = "image_mask", double opacity = 1.0);
00536
00545 bool
00546 addFilledRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00547 const std::string &layer_id = "boxes", double opacity = 0.5);
00548
00560 bool
00561 addFilledRectangle (unsigned int x_min, unsigned int x_max, unsigned int y_min, unsigned int y_max,
00562 double r, double g, double b,
00563 const std::string &layer_id = "boxes", double opacity = 0.5);
00564
00576 bool
00577 addLine (unsigned int x_min, unsigned int y_min, unsigned int x_max, unsigned int y_max,
00578 double r, double g, double b,
00579 const std::string &layer_id = "line", double opacity = 1.0);
00580
00589 bool
00590 addLine (unsigned int x_min, unsigned int y_min, unsigned int x_max, unsigned int y_max,
00591 const std::string &layer_id = "line", double opacity = 1.0);
00592
00593
00603 template <typename T> bool
00604 addMask (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PointCloud<T> &mask,
00605 double r, double g, double b,
00606 const std::string &layer_id = "image_mask", double opacity = 0.5);
00607
00614 template <typename T> bool
00615 addMask (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PointCloud<T> &mask,
00616 const std::string &layer_id = "image_mask", double opacity = 0.5);
00617
00628 template <typename T> bool
00629 addPlanarPolygon (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PlanarPolygon<T> &polygon,
00630 double r, double g, double b,
00631 const std::string &layer_id = "planar_polygon", double opacity = 1.0);
00632
00640 template <typename T> bool
00641 addPlanarPolygon (const typename pcl::PointCloud<T>::ConstPtr &image, const pcl::PlanarPolygon<T> &polygon,
00642 const std::string &layer_id = "planar_polygon", double opacity = 1.0);
00643
00650 bool
00651 addLayer (const std::string &layer_id, int width, int height, double opacity = 0.5);
00652
00656 void
00657 removeLayer (const std::string &layer_id);
00658 protected:
00660 void
00661 resetStoppedFlag () { if (image_viewer_) stopped_ = false; }
00662
00666 void
00667 emitMouseEvent (unsigned long event_id);
00668
00672 void
00673 emitKeyboardEvent (unsigned long event_id);
00674
00675
00676 static void
00677 MouseCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata);
00678 static void
00679 KeyboardCallback (vtkObject*, unsigned long eid, void* clientdata, void *calldata);
00680
00681 protected:
00682 struct ExitMainLoopTimerCallback : public vtkCommand
00683 {
00684 ExitMainLoopTimerCallback () : right_timer_id (), window () {}
00685
00686 static ExitMainLoopTimerCallback* New ()
00687 {
00688 return (new ExitMainLoopTimerCallback);
00689 }
00690 virtual void
00691 Execute (vtkObject* vtkNotUsed (caller), unsigned long event_id, void* call_data)
00692 {
00693 if (event_id != vtkCommand::TimerEvent)
00694 return;
00695 int timer_id = *static_cast<int*> (call_data);
00696 if (timer_id != right_timer_id)
00697 return;
00698 window->interactor_->TerminateApp ();
00699 }
00700 int right_timer_id;
00701 ImageViewer* window;
00702 };
00703 struct ExitCallback : public vtkCommand
00704 {
00705 ExitCallback () : window () {}
00706
00707 static ExitCallback* New ()
00708 {
00709 return (new ExitCallback);
00710 }
00711 virtual void
00712 Execute (vtkObject*, unsigned long event_id, void*)
00713 {
00714 if (event_id != vtkCommand::ExitEvent)
00715 return;
00716 window->stopped_ = true;
00717 window->interactor_->TerminateApp ();
00718 }
00719 ImageViewer* window;
00720 };
00721
00722 private:
00723
00725 struct Layer
00726 {
00727 Layer () : canvas (), layer_name (), opacity () {}
00728 vtkSmartPointer<PCLImageCanvasSource2D> canvas;
00729 std::string layer_name;
00730 double opacity;
00731 };
00732
00733 typedef std::vector<Layer> LayerMap;
00734
00742 LayerMap::iterator
00743 createLayer (const std::string &layer_id, int width, int height, double opacity = 0.5, bool fill_box = true);
00744
00745 boost::signals2::signal<void (const pcl::visualization::MouseEvent&)> mouse_signal_;
00746 boost::signals2::signal<void (const pcl::visualization::KeyboardEvent&)> keyboard_signal_;
00747
00748 vtkSmartPointer<vtkRenderWindowInteractor> interactor_;
00749 vtkSmartPointer<vtkCallbackCommand> mouse_command_;
00750 vtkSmartPointer<vtkCallbackCommand> keyboard_command_;
00751
00753 vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
00754 vtkSmartPointer<ExitCallback> exit_callback_;
00755
00757 vtkSmartPointer<vtkImageViewer> image_viewer_;
00758
00760 boost::shared_array<unsigned char> data_;
00761
00763 size_t data_size_;
00764
00766 bool stopped_;
00767
00769 int timer_id_;
00770
00772 vtkSmartPointer<vtkImageBlend> blend_;
00773
00775 LayerMap layer_map_;
00776
00777 struct LayerComparator
00778 {
00779 LayerComparator (const std::string &str) : str_ (str) {}
00780 const std::string &str_;
00781
00782 bool
00783 operator () (const Layer &layer)
00784 {
00785 return (layer.layer_name == str_);
00786 }
00787 };
00788
00789 public:
00790 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00791 };
00792 }
00793 }
00794
00795 #include <pcl/visualization/impl/image_viewer.hpp>
00796
00797 #endif
00798