pcl_context_item.cpp
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 #include <vtkObjectFactory.h>
00039 #include <vtkSmartPointer.h>
00040 #include <vtkContext2D.h>
00041 #include <vtkImageData.h>
00042 #include <vtkPen.h>
00043 #include <vtkBrush.h>
00044 
00045 #include <pcl/visualization/vtk/pcl_context_item.h>
00046 
00047 namespace pcl
00048 {
00049   namespace visualization
00050   {
00051     // Standard VTK macro for *New ()
00052     vtkStandardNewMacro (PCLContextItem);
00053     vtkStandardNewMacro (PCLContextImageItem);
00054     namespace context_items
00055     {
00056       vtkStandardNewMacro (Point);
00057       vtkStandardNewMacro (Line);
00058       vtkStandardNewMacro (Circle);
00059       vtkStandardNewMacro (Disk);
00060       vtkStandardNewMacro (Rectangle);
00061       vtkStandardNewMacro (FilledRectangle);
00062       vtkStandardNewMacro (Points);
00063       vtkStandardNewMacro (Polygon);
00064     }
00065   }
00066 }
00067 
00069 void
00070 pcl::visualization::PCLContextItem::setColors (unsigned char r, unsigned char g, unsigned char b)
00071 {
00072   colors[0] = r; colors[1] = g; colors[2] = b;
00073 }
00074 
00076 void
00077 pcl::visualization::PCLContextImageItem::set (float _x, float _y, vtkImageData *_image)
00078 {
00079   x = _x;
00080   y = _y;
00081   image->DeepCopy (_image);
00082 }
00083 
00085 bool
00086 pcl::visualization::PCLContextImageItem::Paint (vtkContext2D *painter)
00087 {
00088   SetOpacity (1.0);
00089   painter->DrawImage (x, y, image);
00090   return (true);
00091 }
00092 
00094 void
00095 pcl::visualization::context_items::Point::set (float x, float y)
00096 {
00097   params.resize (2);
00098   params[0] = x; params[1] = y;
00099 }
00100 
00102 void
00103 pcl::visualization::context_items::Circle::set (float x, float y, float radius)
00104 {
00105   params.resize (4);
00106   params[0] = x; params[1] = y; params[2] = radius; params[3] = radius - 1;
00107 }
00108 
00110 void
00111 pcl::visualization::context_items::Rectangle::set (float x, float y, float w, float h)
00112 {
00113   params.resize (4);
00114   params[0] = x; params[1] = y; params[2] = w; params[3] = h;
00115 }
00116 
00118 void
00119 pcl::visualization::context_items::Line::set (float start_x, float start_y, float end_x, float end_y)
00120 {
00121   params.resize (4);
00122   params[0] = start_x; params[1] = start_y; params[2] = end_x; params[3] = end_y;
00123 }
00124 
00126 bool
00127 pcl::visualization::context_items::Circle::Paint (vtkContext2D *painter)
00128 {
00129   painter->GetPen ()->SetColor (colors);
00130   painter->GetBrush ()->SetColor (colors);
00131   painter->DrawWedge (params[0], params[1], params[2], params[3], 0.0, 360.0);
00132   return (true);
00133 }
00134 
00136 bool
00137 pcl::visualization::context_items::Disk::Paint (vtkContext2D *painter)
00138 {
00139   painter->GetBrush ()->SetColor (colors);
00140   painter->GetPen ()->SetColor (colors);
00141   painter->DrawEllipse (params[0], params[1], params[2], params[2]);
00142   return (true);
00143 }
00144 
00146 bool
00147 pcl::visualization::context_items::Rectangle::Paint (vtkContext2D *painter)
00148 {
00149   painter->GetPen ()->SetColor (colors);
00150   float p[] = 
00151   { 
00152     params[0], params[1], 
00153     params[0]+params[2], params[1],
00154     params[0]+params[2], params[1]+params[3],
00155     params[0],       params[1]+params[3],
00156     params[0], params[1]
00157   };
00158 
00159   painter->DrawPoly (p, 5);
00160   return (true);
00161 }
00162 
00164 bool
00165 pcl::visualization::context_items::FilledRectangle::Paint (vtkContext2D *painter)
00166 {
00167   painter->GetBrush ()->SetColor (colors);
00168   painter->GetPen ()->SetColor (colors);
00169   painter->DrawRect (params[0], params[1], params[2], params[3]);
00170   return (true);
00171 }
00172 
00174 bool
00175 pcl::visualization::context_items::Line::Paint (vtkContext2D *painter)
00176 {
00177   painter->GetPen ()->SetColor (colors);
00178   painter->DrawLine (params[0], params[1], params[2], params[3]);
00179   return (true);
00180 }
00181 
00183 bool
00184 pcl::visualization::context_items::Polygon::Paint (vtkContext2D *painter)
00185 {
00186   painter->GetBrush ()->SetColor (colors);
00187   painter->GetPen ()->SetColor (colors);
00188   painter->DrawPolygon (&params[0], static_cast<int> (params.size () / 2));
00189   return (true);
00190 }
00191 
00193 bool
00194 pcl::visualization::context_items::Point::Paint (vtkContext2D *painter)
00195 {
00196   painter->GetPen ()->SetColor (colors);
00197   painter->DrawPoint (params[0], params[1]);
00198   return (true);
00199 }
00200 
00202 bool
00203 pcl::visualization::context_items::Points::Paint (vtkContext2D *painter)
00204 {
00205   painter->GetPen ()->SetColor (colors);
00206   painter->DrawPoints (&params[0], static_cast<int> (params.size () / 2));
00207   return (true);
00208 }
00209 
00211 pcl::visualization::PCLContextImageItem::PCLContextImageItem ()
00212 {
00213   image = vtkSmartPointer<vtkImageData>::New ();
00214 }
00215 


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