pcl_context_item.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 #ifndef PCL_VISUALIZATION_PCL_CONTEXT_ITEM_H_
00039 #define PCL_VISUALIZATION_PCL_CONTEXT_ITEM_H_
00040 
00041 #include <pcl/pcl_macros.h>
00042 #include <vtkContextItem.h>
00043 #include <vector>
00044 
00045 template <typename T> class vtkSmartPointer;
00046 class vtkImageData;
00047 class vtkContext2D;
00048 
00049 namespace pcl
00050 {
00051   namespace visualization
00052   {
00058     struct PCL_EXPORTS PCLContextItem : public vtkContextItem
00059     {
00060       vtkTypeMacro (PCLContextItem, vtkContextItem);
00061       static PCLContextItem *New();
00062       virtual bool Paint (vtkContext2D *) { return (false); };
00063       void setColors (unsigned char r, unsigned char g, unsigned char b);
00064       void setColors (unsigned char rgb[3]) { memcpy (colors, rgb, 3 * sizeof (unsigned char)); }
00065       void setOpacity (double opacity) { SetOpacity (opacity); };
00066       unsigned char colors[3];
00067       double opacity;
00068       std::vector<float> params;
00069     };
00070 
00076     struct PCL_EXPORTS PCLContextImageItem : public vtkContextItem
00077     {
00078       vtkTypeMacro (PCLContextImageItem, vtkContextItem);
00079       PCLContextImageItem ();
00080 
00081       static PCLContextImageItem *New ();
00082       virtual bool Paint (vtkContext2D *painter);
00083       void set (float _x, float _y, vtkImageData *_image);
00084       vtkSmartPointer<vtkImageData> image;
00085       float x, y;
00086     };
00087 
00088     namespace context_items
00089     {
00090       struct PCL_EXPORTS Point : public PCLContextItem
00091       {
00092         vtkTypeMacro (Point, PCLContextItem);
00093         static Point *New();
00094         virtual bool Paint (vtkContext2D *painter);
00095         virtual void set (float _x, float _y);
00096       };
00097 
00098       struct PCL_EXPORTS Line : public PCLContextItem
00099       {
00100         vtkTypeMacro (Line, PCLContextItem);
00101         static Line *New();
00102         virtual bool Paint (vtkContext2D *painter);
00103         virtual void set (float _x_1, float _y_1, float _x_2, float _y_2);
00104       };
00105 
00106       struct PCL_EXPORTS Circle : public PCLContextItem
00107       {
00108         vtkTypeMacro (Circle, PCLContextItem);
00109         static Circle *New();
00110         virtual bool Paint (vtkContext2D *painter);
00111         virtual void set (float _x, float _y, float _r);
00112       };
00113 
00114       struct PCL_EXPORTS Disk : public Circle
00115       {
00116         vtkTypeMacro (Disk, Circle);
00117         static Disk *New();
00118         virtual bool Paint (vtkContext2D *painter);
00119       };
00120 
00121       struct PCL_EXPORTS Rectangle : public PCLContextItem
00122       {
00123         vtkTypeMacro (Rectangle, Point);
00124         static Rectangle *New();
00125         virtual bool Paint (vtkContext2D *painter);
00126         virtual void set (float _x, float _y, float _w, float _h);
00127       };
00128 
00129       struct PCL_EXPORTS FilledRectangle : public Rectangle
00130       {
00131         vtkTypeMacro (FilledRectangle, Rectangle);
00132         static FilledRectangle *New();
00133         virtual bool Paint (vtkContext2D *painter);
00134       };
00135 
00136       struct PCL_EXPORTS Points : public PCLContextItem
00137       {
00138         vtkTypeMacro (Points, PCLContextItem);
00139         static Points *New();
00140         virtual bool Paint (vtkContext2D *painter);
00141         void set (const std::vector<float>& _xy)  { params = _xy; }
00142       };
00143 
00144       struct PCL_EXPORTS Polygon : public Points
00145       {
00146         vtkTypeMacro (Polygon, Points);
00147         static Polygon *New();
00148         virtual bool Paint (vtkContext2D *painter);
00149       };
00150     }
00151   }
00152 }
00153 
00154 #endif


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