pcl_painter2D.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) 2012-, Open Perception, 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 the copyright holder(s) 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  *
00037  */
00038 
00039 #ifndef PCL_VISUALUALIZATION_PCL_PAINTER2D_H_
00040 #define PCL_VISUALUALIZATION_PCL_PAINTER2D_H_
00041 
00042 #include <iostream>
00043 #include <map>
00044 #include <vector>
00045 #include <vtkRenderer.h>
00046 #include <vtkRenderWindow.h>
00047 #include <vtkRenderWindowInteractor.h>
00048 #include <vtkSmartPointer.h>
00049 #include <vtkObjectFactory.h>
00050 #include <vtkContext2D.h>
00051 #include <vtkTransform2D.h>
00052 #include <vtkContextItem.h>
00053 #include <vtkContextView.h>
00054 #include <vtkContextScene.h>
00055 #include <vtkPen.h>
00056 #include <vtkBrush.h>
00057 #include <vtkTextProperty.h>
00058 #include <vtkOpenGLContextDevice2D.h>
00059 #include <vtkPoints2D.h>
00060 #include "vtkCommand.h"
00061 
00062 #include <vtkRegressionTestImage.h>
00063 
00064 namespace pcl
00065 {
00066   namespace visualization
00067   {
00068 
00073     struct Figure2D
00074     {
00075       std::vector<float> info_;     //information stored in a general form for every object
00076       vtkPen *pen_;                 //the corresponding pen and brush for the figure
00077       vtkBrush *brush_;
00078       vtkTransform2D *transform_;
00079       
00080       Figure2D (std::vector<float> info, vtkPen *p, vtkBrush * b, vtkTransform2D *t)
00081       {
00082         this->pen_ = vtkPen::New ();
00083         this->brush_ = vtkBrush::New ();
00084         this->transform_ = vtkTransform2D::New();
00085 
00086         this->pen_->DeepCopy (p);
00087         this->brush_->DeepCopy (b);
00088         this->transform_->SetMatrix (t->GetMatrix());
00089         this->info_ = info; //note: it copies :-)
00090       }
00091 
00092       Figure2D (vtkPen *p, vtkBrush * b, vtkTransform2D *t)
00093       {
00094         this->pen_ = vtkPen::New ();
00095         this->brush_ = vtkBrush::New ();
00096         this->transform_ = vtkTransform2D::New();
00097 
00098         this->pen_->DeepCopy (p);
00099         this->brush_->DeepCopy (b);
00100         this->transform_->SetMatrix (t->GetMatrix());
00101       }
00102       
00103       void applyInternals (vtkContext2D *painter)
00104       {
00105         painter->ApplyPen (pen_);
00106         painter->ApplyBrush (brush_);
00107         painter->GetDevice ()->SetMatrix (transform_->GetMatrix());
00108       }
00109                   
00110       virtual void draw (vtkContext2D *) {}
00111     };
00112     
00115     struct FPolyLine2D : public Figure2D
00116     {
00117 
00118       FPolyLine2D (std::vector<float> info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t){}
00119 
00120       void draw (vtkContext2D * painter)
00121       {
00122         applyInternals(painter);  
00123         painter->DrawPoly (&info_[0], static_cast<unsigned int> (info_.size ()) / 2);
00124       }
00125     };
00126 
00129     struct FPoints2D : public Figure2D
00130     {
00131 
00132       FPoints2D (std::vector<float> info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t) {}
00133 
00134       void draw (vtkContext2D * painter)
00135       {
00136         applyInternals(painter);  
00137         painter->DrawPoints (&info_[0], static_cast<unsigned int> (info_.size ()) / 2);
00138       }
00139     };
00140 
00143     struct FQuad2D : public Figure2D
00144     {
00145 
00146       FQuad2D (std::vector<float> info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t) {}
00147 
00148       void draw (vtkContext2D * painter)
00149       {
00150         applyInternals(painter);  
00151         painter->DrawQuad (&info_[0]);
00152       }
00153     };
00154     
00157     struct FPolygon2D : public Figure2D
00158     {
00159 
00160       FPolygon2D (std::vector<float> info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t){}
00161 
00162       void draw (vtkContext2D * painter)
00163       {
00164         applyInternals(painter);  
00165         painter->DrawPolygon (&info_[0], static_cast<unsigned int> (info_.size ()) / 2);
00166       }
00167     };
00168     
00171     struct FEllipticArc2D : public Figure2D
00172     {
00173 
00174       FEllipticArc2D (std::vector<float> info, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (info, p, b, t) {}
00175 
00176       FEllipticArc2D (float x, float y, float rx, float ry, float sa, float ea, vtkPen *p, vtkBrush * b, vtkTransform2D *t) : Figure2D (p, b, t)
00177       {
00178         info_.resize (6);
00179         info_[0] = x;
00180         info_[1] = y;
00181         info_[2] = rx;
00182         info_[3] = ry;
00183         info_[4] = sa;
00184         info_[5] = ea;
00185       }
00186 
00187       void draw (vtkContext2D * painter)
00188       {
00189         applyInternals(painter);  
00190         painter->DrawEllipticArc (info_[0], info_[1], info_[2], info_[3], info_[4], info_[5]);
00191       }
00192     };
00193 
00194 
00196 
00200     class PCLPainter2D: public vtkContextItem
00201     {
00202     public:
00203 
00204       //static PCLPainter2D *New();
00205       
00208       PCLPainter2D (char const * name = "PCLPainter2D");
00209       vtkTypeRevisionMacro (PCLPainter2D, vtkContextItem);
00210 
00214       virtual bool 
00215       Paint (vtkContext2D *painter);
00216 
00223       void 
00224       addLine (float x1, float y1, float x2, float y2);
00225       
00229       void 
00230       addLine (std::vector<float> p);
00231 
00232       
00237       void 
00238       addPoint (float x, float y);
00243       void 
00244       addPoints (std::vector<float> points);
00245       
00246       
00253       void 
00254       addRect (float x, float y, float width, float height);
00255       
00259       void 
00260       addQuad (std::vector<float> p);
00261       
00265       void 
00266       addPolygon (std::vector<float> p);
00267 
00268       
00275       void 
00276       addEllipse (float x, float y, float rx, float ry);
00277       
00283       void 
00284       addCircle (float x, float y, float r);
00285       
00294       void 
00295       addEllipticArc (float x, float y, float rx, float ry, float start_angle, float end_angle);
00296       
00304       void 
00305       addArc (float x, float y, float r, float start_angle, float end_angle);
00306 
00307 
00312       void 
00313       translatePen (double x, double y);
00314       
00318       void 
00319       rotatePen(double angle);
00320       
00325       void 
00326       scalePen(double x, double y);
00327       
00332       void 
00333       setTransform(vtkMatrix3x3 *matrix);
00334       
00337       vtkMatrix3x3 * 
00338       getTransform();
00339       
00342       void 
00343       clearTransform();
00344       
00347        void
00348        clearFigures();
00349 
00352       void setPenColor (unsigned char r, unsigned char g, unsigned char b, unsigned char a);
00353       void setPenWidth (float w);
00354       void setPenType (int type);
00355 
00358       unsigned char* getPenColor ();
00359       float getPenWidth ();
00360       int getPenType ();
00361       void setPen (vtkPen *pen);
00362       vtkPen* getPen ();
00363 
00366       void setBrush (vtkBrush *brush);
00367       vtkBrush* getBrush ();
00368       void setBrushColor (unsigned char r, unsigned char g, unsigned char b, unsigned char a);
00369       unsigned char* getBrushColor ();
00370 
00376       void
00377       setBackgroundColor (const double r, const double g, const double b);
00378 
00382       void
00383       setBackgroundColor (const double color[3]);
00384 
00388       double *
00389       getBackgroundColor ();
00390 
00391 
00396       void
00397       setWindowSize (int w, int h);
00398 
00402       int *
00403       getWindowSize ();
00404 
00407       void display ();
00408       
00412       void spinOnce ( const int spin_time = 0 );
00413         
00416       void spin ();
00417 
00418     private:
00419       //std::map< int, std::vector< std::vector<float> > > figures_; //FIG_TYPE -> vector<array>
00420 
00421       //All the figures drawn till now gets stored here
00422       std::vector<Figure2D *> figures_;
00423     
00424       //state variables of the class
00425       vtkPen *current_pen_;
00426       vtkBrush *current_brush_;
00427       vtkTransform2D *current_transform_;
00428       int win_width_, win_height_;
00429       double bkg_color_[3];
00430 
00431       vtkContextView *view_;
00432       
00433       //####event callback class####
00434         struct ExitMainLoopTimerCallback : public vtkCommand
00435         {
00436           static ExitMainLoopTimerCallback* New ()
00437           {
00438             return (new ExitMainLoopTimerCallback);
00439           }
00440           virtual void 
00441           Execute (vtkObject* vtkNotUsed (caller), unsigned long event_id, void* call_data)
00442           {
00443             if (event_id != vtkCommand::TimerEvent)
00444               return;
00445             int timer_id = *(reinterpret_cast<int*> (call_data));
00446 
00447             if (timer_id != right_timer_id)
00448               return;
00449 
00450             // Stop vtk loop and send notification to app to wake it up
00451 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00452             interactor->stopLoop ();
00453 #else
00454             interactor->TerminateApp ();
00455 #endif
00456           }
00457           int right_timer_id;
00458 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00459           PCLVisualizerInteractor *interactor;
00460 #else
00461           vtkRenderWindowInteractor *interactor;
00462 #endif
00463         };
00464         
00466         vtkSmartPointer<ExitMainLoopTimerCallback> exit_loop_timer_;
00467     };
00468 
00469   }
00470 }
00471 
00472 #endif  /* PCL_VISUALUALIZATION_PCL_PAINTER2D_H_ */
00473 


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