shapes.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00037 #ifndef GEOMETRIC_SHAPES_SHAPES_
00038 #define GEOMETRIC_SHAPES_SHAPES_
00039 
00040 #include <cstdlib>
00041 
00046 namespace shapes
00047 {
00048     
00050     enum ShapeType { UNKNOWN_SHAPE, SPHERE, CYLINDER, BOX, MESH };
00051 
00053     enum StaticShapeType { UNKNOWN_STATIC_SHAPE, PLANE };
00054     
00055     
00057     class Shape
00058     {               
00059     public:         
00060         Shape(void)
00061         {
00062             type = UNKNOWN_SHAPE;
00063         }
00064         
00065         virtual ~Shape(void)
00066         {
00067         }
00068 
00069         ShapeType type;
00070     };
00071 
00073     class StaticShape
00074     {
00075     public:
00076         StaticShape(void)
00077         {
00078             type = UNKNOWN_STATIC_SHAPE;
00079         }
00080         
00081         virtual ~StaticShape(void)
00082         {
00083         }
00084         
00085         StaticShapeType type;
00086     };
00087     
00089     class Sphere : public Shape
00090     {
00091     public:
00092         Sphere(void) : Shape()
00093         {
00094             type   = SPHERE;
00095             radius = 0.0;
00096         }
00097         
00098         Sphere(double r) : Shape()
00099         {
00100             type   = SPHERE;
00101             radius = r;
00102         }
00103         
00104         double radius; 
00105     };
00106     
00108     class Cylinder : public Shape
00109     {
00110     public:
00111         Cylinder(void) : Shape()
00112         {
00113             type   = CYLINDER;
00114             length = radius = 0.0;
00115         }
00116         
00117         Cylinder(double r, double l) : Shape()
00118         {
00119             type   = CYLINDER;
00120             length = l;
00121             radius = r;
00122         }
00123         
00124         double length, radius; 
00125     };
00126     
00128     class Box : public Shape
00129     {
00130     public:
00131         Box(void) : Shape()
00132         {
00133             type = BOX;
00134             size[0] = size[1] = size[2] = 0.0;
00135         }
00136         
00137         Box(double x, double y, double z) : Shape()
00138         {
00139             type = BOX;
00140             size[0] = x;
00141             size[1] = y;
00142             size[2] = z;
00143         }
00144         
00146         double size[3]; 
00147     };
00148     
00150     class Mesh : public Shape
00151     {
00152     public:
00153         Mesh(void) : Shape()
00154         {
00155             type = MESH;
00156             vertexCount = 0;
00157             vertices = NULL;
00158             triangleCount = 0;
00159             triangles = NULL;
00160             normals = NULL;
00161         }
00162         
00163         Mesh(unsigned int vCount, unsigned int tCount) : Shape()
00164         {
00165             type = MESH;
00166             vertexCount = vCount;
00167             vertices = new double[vCount * 3];
00168             triangleCount = tCount;
00169             triangles = new unsigned int[tCount * 3];
00170             normals = new double[tCount * 3];
00171         }
00172         
00173         virtual ~Mesh(void)
00174         {
00175             if (vertices)
00176                 delete[] vertices;
00177             if (triangles)
00178                 delete[] triangles;
00179             if (normals)
00180                 delete[] normals;
00181         }
00182         
00184         unsigned int  vertexCount;       
00185 
00188         double       *vertices;          
00189 
00191         unsigned int  triangleCount;     
00192 
00195         unsigned int *triangles;
00196         
00199         double       *normals;       
00200     };
00201 
00203     class Plane : public StaticShape
00204     {
00205     public:
00206         
00207         Plane(void) : StaticShape()
00208         {
00209             type = PLANE;
00210             a = b = c = d = 0.0;            
00211         }
00212         
00213         Plane(double pa, double pb, double pc, double pd) : StaticShape()
00214         {
00215             type = PLANE;
00216             a = pa; b = pb; c = pc; d = pd;
00217         }
00218         
00219         double a, b, c, d;
00220     };
00221     
00222 }
00223 
00224 #endif


geometric_shapes
Author(s): Ioan Sucan
autogenerated on Thu Dec 12 2013 11:08:55