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 #include <vector>
00042 #include <tf/LinearMath/Vector3.h>
00043 
00048 namespace shapes
00049 {
00050     
00052     enum ShapeType { UNKNOWN_SHAPE, SPHERE, CYLINDER, BOX, MESH };
00053 
00054     enum StaticShapeType { UNKNOWN_STATIC_SHAPE, PLANE };
00055     
00056     
00058     class Shape
00059     {               
00060     public:         
00061         Shape(void)
00062         {
00063             type = UNKNOWN_SHAPE;
00064         }
00065         
00066         virtual ~Shape(void)
00067         {
00068         }
00069 
00070         ShapeType type;
00071     };
00072 
00074     class StaticShape
00075     {
00076     public:
00077         StaticShape(void)
00078         {
00079             type = UNKNOWN_STATIC_SHAPE;
00080         }
00081         
00082         virtual ~StaticShape(void)
00083         {
00084         }
00085         
00086         StaticShapeType type;
00087     };
00088     
00090     class Sphere : public Shape
00091     {
00092     public:
00093         Sphere(void) : Shape()
00094         {
00095             type   = SPHERE;
00096             radius = 0.0;
00097         }
00098         
00099         Sphere(double r) : Shape()
00100         {
00101             type   = SPHERE;
00102             radius = r;
00103         }
00104         
00105         double radius; 
00106     };
00107     
00109     class Cylinder : public Shape
00110     {
00111     public:
00112         Cylinder(void) : Shape()
00113         {
00114             type   = CYLINDER;
00115             length = radius = 0.0;
00116         }
00117         
00118         Cylinder(double r, double l) : Shape()
00119         {
00120             type   = CYLINDER;
00121             length = l;
00122             radius = r;
00123         }
00124         
00125         double length, radius; 
00126     };
00127     
00129     class Box : public Shape
00130     {
00131     public:
00132         Box(void) : Shape()
00133         {
00134             type = BOX;
00135             size[0] = size[1] = size[2] = 0.0;
00136         }
00137         
00138         Box(double x, double y, double z) : Shape()
00139         {
00140             type = BOX;
00141             size[0] = x;
00142             size[1] = y;
00143             size[2] = z;
00144         }
00145         
00147         double size[3]; 
00148     };
00149     
00151     class Mesh : public Shape
00152     {
00153     public:
00154         Mesh(void) : Shape()
00155         {
00156             type = MESH;
00157             vertexCount = 0;
00158             vertices = NULL;
00159             triangleCount = 0;
00160             triangles = NULL;
00161             normals = NULL;
00162         }
00163         
00164         Mesh(unsigned int vCount, unsigned int tCount) : Shape()
00165         {
00166             type = MESH;
00167             vertexCount = vCount;
00168             vertices = new double[vCount * 3];
00169             triangleCount = tCount;
00170             triangles = new unsigned int[tCount * 3];
00171             normals = new double[tCount * 3];
00172         }
00173         
00174         virtual ~Mesh(void)
00175         {
00176             if (vertices)
00177                 delete[] vertices;
00178             if (triangles)
00179                 delete[] triangles;
00180             if (normals)
00181                 delete[] normals;
00182         }
00183         
00185         unsigned int  vertexCount;       
00186 
00189         double       *vertices;          
00190 
00192         unsigned int  triangleCount;     
00193 
00196         unsigned int *triangles;
00197         
00200         double       *normals;       
00201     };
00202 
00204     class Plane : public StaticShape
00205     {
00206     public:
00207         
00208         Plane(void) : StaticShape()
00209         {
00210             type = PLANE;
00211             a = b = c = d = 0.0;            
00212         }
00213         
00214         Plane(double pa, double pb, double pc, double pd) : StaticShape()
00215         {
00216             type = PLANE;
00217             a = pa; b = pb; c = pc; d = pd;
00218         }
00219         
00220         double a, b, c, d;
00221     };
00222     
00223     
00228     Mesh* createMeshFromVertices(const std::vector<tf::Vector3> &vertices, const std::vector<unsigned int> &triangles);
00229     
00234     Mesh* createMeshFromVertices(const std::vector<tf::Vector3> &source);
00235 
00238     Mesh* createMeshFromBinaryStl(const char *filename);
00239 
00242     Mesh* createMeshFromBinaryStlData(const char *data, unsigned int size);
00243 
00245     Shape* cloneShape(const Shape *shape);
00246 
00248     StaticShape* cloneShape(const StaticShape *shape);
00249     
00250 }
00251 
00252 #endif


pr2_navigation_self_filter
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Dec 2 2013 13:15:43