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 #include <pcl/visualization/pcl_painter2D.h>
00040 
00041 vtkCxxRevisionMacro (pcl::visualization::PCLPainter2D, "$Revision: 1.2 $");
00042 
00044 pcl::visualization::PCLPainter2D::PCLPainter2D(char const * name)
00045 {
00046   
00047   view_ = vtkContextView::New ();
00048   current_pen_ = vtkPen::New ();
00049   current_brush_ = vtkBrush::New ();
00050   current_transform_ = vtkTransform2D::New ();
00051   exit_loop_timer_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
00052   
00053   
00054   view_->GetScene ()->AddItem (this);
00055   view_->GetRenderWindow ()->SetWindowName (name);
00056   
00057   exit_loop_timer_->interactor = view_->GetInteractor ();
00058   
00059   
00060   win_width_ = 640;
00061   win_height_ = 480;
00062   bkg_color_[0] = 1; bkg_color_[1] = 1; bkg_color_[2] = 1;
00063 }
00064 
00066 void 
00067 pcl::visualization::PCLPainter2D::addLine (float x1, float y1, float x2, float y2)
00068 {
00069   std::vector<float> line (4);
00070   line[0] = x1;
00071   line[1] = y1;
00072   line[2] = x2;
00073   line[3] = y2;
00074 
00075   FPolyLine2D *pline = new FPolyLine2D(line, current_pen_, current_brush_, current_transform_);
00076   figures_.push_back (pline);
00077 }
00078 
00080 void 
00081 pcl::visualization::PCLPainter2D::addLine (std::vector<float> p)
00082 {
00083   figures_.push_back (new FPolyLine2D(p, current_pen_, current_brush_, current_transform_));
00084 }
00085 
00087 void 
00088 pcl::visualization::PCLPainter2D::addPoint (float x, float y)
00089 {
00090   std::vector<float> points(2);
00091   points[0] = x; points[1] = y;
00092   
00093   figures_.push_back (new FPoints2D(points, current_pen_, current_brush_, current_transform_));
00094 }
00095 
00097 void 
00098 pcl::visualization::PCLPainter2D::addPoints (std::vector<float> p)
00099 {
00100   figures_.push_back (new FPoints2D(p, current_pen_, current_brush_, current_transform_));
00101 }
00102 
00104 void 
00105 pcl::visualization::PCLPainter2D::addRect (float x, float y, float width, float height)
00106 {
00107   float p[] = { x,       y,
00108                 x+width, y,
00109                 x+width, y+height,
00110                 x,       y+height};
00111   
00112   std::vector<float> quad (p, p+8);
00113   
00114   figures_.push_back (new FQuad2D(quad, current_pen_, current_brush_, current_transform_));
00115 }
00116 
00118 void 
00119 pcl::visualization::PCLPainter2D::addQuad (std::vector<float> p)
00120 {
00121   figures_.push_back (new FQuad2D(p, current_pen_, current_brush_, current_transform_));
00122 }
00123 
00125 void 
00126 pcl::visualization::PCLPainter2D::addPolygon (std::vector<float> p)
00127 {
00128   figures_.push_back (new FPolygon2D(p, current_pen_, current_brush_, current_transform_));
00129 }
00130 
00132 void 
00133 pcl::visualization::PCLPainter2D::addEllipse (float x, float y, float rx, float ry)
00134 { 
00135   figures_.push_back (new FEllipticArc2D(x, y, rx, ry, 0, 360, current_pen_, current_brush_, current_transform_));
00136 }
00137 
00139 void 
00140 pcl::visualization::PCLPainter2D::addCircle (float x, float y, float r)
00141 {  
00142   figures_.push_back (new FEllipticArc2D(x, y, r, r, 0, 360, current_pen_, current_brush_, current_transform_));
00143 }
00144 
00146 void 
00147 pcl::visualization::PCLPainter2D::addEllipticArc (float x, float y, float rx, float ry, float start_angle, float end_angle)
00148 { 
00149   figures_.push_back (new FEllipticArc2D(x, y, rx, ry, start_angle, end_angle, current_pen_, current_brush_, current_transform_));
00150 }
00151 
00153 void 
00154 pcl::visualization::PCLPainter2D::addArc (float x, float y, float r, float start_angle, float end_angle)
00155 { 
00156   figures_.push_back (new FEllipticArc2D(x, y, r, r, start_angle, end_angle, current_pen_, current_brush_, current_transform_));
00157 }
00158 
00159 
00161 void pcl::visualization::PCLPainter2D::setPenColor (unsigned char r, unsigned char g, unsigned char b, unsigned char a)
00162 {
00163   current_pen_->SetColor (r, g, b, a);
00164 }
00165 
00166 void pcl::visualization::PCLPainter2D::setPenWidth (float w)
00167 {
00168   current_pen_->SetWidth (w);
00169 }
00170 
00171 void pcl::visualization::PCLPainter2D::setPenType (int type)
00172 {
00173   current_pen_->SetLineType (type);
00174 }
00175 
00176 unsigned char* pcl::visualization::PCLPainter2D::getPenColor ()
00177 {
00178   return current_pen_->GetColor ();
00179 }
00180 
00181 float pcl::visualization::PCLPainter2D::getPenWidth ()
00182 {
00183   return current_pen_->GetWidth ();
00184 }
00185 
00186 int pcl::visualization::PCLPainter2D::getPenType ()
00187 {
00188   return current_pen_->GetLineType ();
00189 }
00190  
00191 void pcl::visualization::PCLPainter2D::setBrushColor (unsigned char r, unsigned char g, unsigned char b, unsigned char a)
00192 {
00193   current_brush_->SetColor (r, g, b, a);
00194 }
00195 
00196 unsigned char* pcl::visualization::PCLPainter2D::getBrushColor ()
00197 {
00198   return current_brush_->GetColor ();
00199 }
00200 
00201 void pcl::visualization::PCLPainter2D::setPen (vtkPen *pen)
00202 {
00203   current_pen_->DeepCopy (pen);
00204 }
00205 
00206 vtkPen * pcl::visualization::PCLPainter2D::getPen ()
00207 {
00208   return current_pen_;
00209 }
00210 
00211 void pcl::visualization::PCLPainter2D::setBrush (vtkBrush *brush)
00212 {
00213   current_brush_->DeepCopy (brush);
00214 }
00215 
00216 vtkBrush * pcl::visualization::PCLPainter2D::getBrush ()
00217 {
00218   return current_brush_;
00219 }
00221 
00222 void 
00223 pcl::visualization::PCLPainter2D::translatePen (double x, double y)
00224 {
00225   current_transform_->Translate(x, y);
00226 }
00227 
00229 void 
00230 pcl::visualization::PCLPainter2D::rotatePen (double angle)
00231 {
00232   current_transform_->Rotate(angle);
00233 }
00234 
00236 void 
00237 pcl::visualization::PCLPainter2D::scalePen (double x, double y)
00238 {
00239   current_transform_->Scale(x, y);
00240 }
00241 
00243 void 
00244 pcl::visualization::PCLPainter2D::setTransform(vtkMatrix3x3 *matrix)
00245 {
00246   current_transform_->SetMatrix(matrix);
00247 }
00248 
00250 vtkMatrix3x3 * 
00251 pcl::visualization::PCLPainter2D::getTransform()
00252 {
00253   return current_transform_->GetMatrix ();
00254 }
00255 
00257 void 
00258 pcl::visualization::PCLPainter2D::clearTransform()
00259 {
00260   current_transform_->Identity();
00261 }
00262 
00264 void 
00265 pcl::visualization::PCLPainter2D::clearFigures()
00266 {
00267   figures_.clear();
00268   view_->GetScene()->SetDirty(true);
00269 }
00270 
00272 void
00273 pcl::visualization::PCLPainter2D::display ()
00274 {
00275   view_->GetRenderer ()->SetBackground (bkg_color_[0], bkg_color_[1], bkg_color_[2]);
00276   view_->GetRenderWindow ()->SetSize (win_width_, win_height_);
00277   
00278   
00279   
00280   
00281   view_->GetInteractor ()->Initialize ();
00282   view_->GetRenderer ()->Render ();
00283   view_->GetInteractor ()->Start ();
00284 }
00285 
00287 void 
00288 pcl::visualization::PCLPainter2D::spinOnce( const int spin_time )
00289 {
00290   
00291   view_->GetRenderer ()->SetBackground (bkg_color_[0], bkg_color_[1], bkg_color_[2]);
00292   view_->GetRenderWindow ()->SetSize (win_width_, win_height_);
00293   
00294   
00295   if (!view_->GetInteractor ()->GetEnabled ())
00296   {
00297     view_->GetInteractor ()->Initialize ();
00298     view_->GetInteractor ()->AddObserver ( vtkCommand::TimerEvent, exit_loop_timer_ );
00299   }
00300   exit_loop_timer_->right_timer_id = view_->GetInteractor()->CreateOneShotTimer( spin_time );
00301   
00302   
00303   this->Update();
00304   view_->GetRenderer ()->Render ();
00305         view_->GetInteractor()->Start();
00306 }
00307 
00309 void 
00310 pcl::visualization::PCLPainter2D::spin()
00311 {
00312   this->display();
00313 }
00314 
00316 void
00317 pcl::visualization::PCLPainter2D::setBackgroundColor (const double r, const double g, const double b)
00318 {
00319   bkg_color_[0] = r;
00320   bkg_color_[1] = g;
00321   bkg_color_[2] = b;
00322 }
00323 
00325 void
00326 pcl::visualization::PCLPainter2D::setBackgroundColor (const double color[3])
00327 {
00328   bkg_color_[0] = color[0];
00329   bkg_color_[1] = color[1];
00330   bkg_color_[2] = color[2];
00331 }
00332 
00334 double*
00335 pcl::visualization::PCLPainter2D::getBackgroundColor ()
00336 {
00337   double *bc = new double[3];
00338   bc[0] = bkg_color_[0];
00339   bc[1] = bkg_color_[1];
00340   bc[2] = bkg_color_[2];
00341   return (bc);
00342 }
00343 
00345 void
00346 pcl::visualization::PCLPainter2D::setWindowSize (int w, int h)
00347 {
00348   win_width_ = w;
00349   win_height_ = h;
00350 }
00351 
00353 int*
00354 pcl::visualization::PCLPainter2D::getWindowSize ()
00355 {
00356   int *sz = new int[2];
00357   sz[0] = win_width_;
00358   sz[1] = win_height_;
00359   return (sz);
00360 }
00361 
00363 bool 
00364 pcl::visualization::PCLPainter2D::Paint (vtkContext2D *painter)
00365 {  
00366   
00367   for (size_t i = 0; i < figures_.size (); i++)
00368   {
00369     figures_[i]->draw (painter);        
00370   }
00371   
00372   return true;
00373 }
00374 
00375