shapes.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
37 #ifndef GEOMETRIC_SHAPES_SHAPES_
38 #define GEOMETRIC_SHAPES_SHAPES_
39 
40 #include <cstdlib>
41 #include <vector>
42 #include <tf/LinearMath/Vector3.h>
43 
48 namespace shapes
49 {
50 
53 
55 
56 
58  class Shape
59  {
60  public:
61  Shape(void)
62  {
64  }
65 
66  virtual ~Shape(void)
67  {
68  }
69 
71  };
72 
75  {
76  public:
78  {
80  }
81 
82  virtual ~StaticShape(void)
83  {
84  }
85 
87  };
88 
90  class Sphere : public Shape
91  {
92  public:
93  Sphere(void) : Shape()
94  {
95  type = SPHERE;
96  radius = 0.0;
97  }
98 
99  Sphere(double r) : Shape()
100  {
101  type = SPHERE;
102  radius = r;
103  }
104 
105  double radius;
106  };
107 
109  class Cylinder : public Shape
110  {
111  public:
112  Cylinder(void) : Shape()
113  {
114  type = CYLINDER;
115  length = radius = 0.0;
116  }
117 
118  Cylinder(double r, double l) : Shape()
119  {
120  type = CYLINDER;
121  length = l;
122  radius = r;
123  }
124 
125  double length, radius;
126  };
127 
129  class Box : public Shape
130  {
131  public:
132  Box(void) : Shape()
133  {
134  type = BOX;
135  size[0] = size[1] = size[2] = 0.0;
136  }
137 
138  Box(double x, double y, double z) : Shape()
139  {
140  type = BOX;
141  size[0] = x;
142  size[1] = y;
143  size[2] = z;
144  }
145 
147  double size[3];
148  };
149 
151  class Mesh : public Shape
152  {
153  public:
154  Mesh(void) : Shape()
155  {
156  type = MESH;
157  vertexCount = 0;
158  vertices = NULL;
159  triangleCount = 0;
160  triangles = NULL;
161  normals = NULL;
162  }
163 
164  Mesh(unsigned int vCount, unsigned int tCount) : Shape()
165  {
166  type = MESH;
167  vertexCount = vCount;
168  vertices = new double[vCount * 3];
169  triangleCount = tCount;
170  triangles = new unsigned int[tCount * 3];
171  normals = new double[tCount * 3];
172  }
173 
174  virtual ~Mesh(void)
175  {
176  if (vertices)
177  delete[] vertices;
178  if (triangles)
179  delete[] triangles;
180  if (normals)
181  delete[] normals;
182  }
183 
185  unsigned int vertexCount;
186 
189  double *vertices;
190 
192  unsigned int triangleCount;
193 
196  unsigned int *triangles;
197 
200  double *normals;
201  };
202 
204  class Plane : public StaticShape
205  {
206  public:
207 
208  Plane(void) : StaticShape()
209  {
210  type = PLANE;
211  a = b = c = d = 0.0;
212  }
213 
214  Plane(double pa, double pb, double pc, double pd) : StaticShape()
215  {
216  type = PLANE;
217  a = pa; b = pb; c = pc; d = pd;
218  }
219 
220  double a, b, c, d;
221  };
222 
223 
228  Mesh* createMeshFromVertices(const std::vector<tf::Vector3> &vertices, const std::vector<unsigned int> &triangles);
229 
234  Mesh* createMeshFromVertices(const std::vector<tf::Vector3> &source);
235 
238  Mesh* createMeshFromBinaryStl(const char *filename);
239 
242  Mesh* createMeshFromBinaryStlData(const char *data, unsigned int size);
243 
246  Mesh* createMeshFromBinaryDAE(const char* filename);
247 
248 
250  Shape* cloneShape(const Shape *shape);
251 
253  StaticShape* cloneShape(const StaticShape *shape);
254 
255 }
256 
257 #endif
d
Mesh * createMeshFromBinaryStl(const char *filename)
Load a mesh from a binary STL file. Normals are recomputed and repeating vertices are identified...
Definition: load_mesh.cpp:534
Definition: shapes.h:48
double radius
Definition: shapes.h:125
Plane(double pa, double pb, double pc, double pd)
Definition: shapes.h:214
Definition of a cylinder.
Definition: shapes.h:109
Mesh * createMeshFromVertices(const std::vector< tf::Vector3 > &vertices, const std::vector< unsigned int > &triangles)
Load a mesh from a set of vertices. Triangles are constructed using index values from the triangles v...
Definition: load_mesh.cpp:354
StaticShapeType
Definition: shapes.h:54
Mesh(void)
Definition: shapes.h:154
ShapeType type
Definition: shapes.h:70
Plane(void)
Definition: shapes.h:208
Sphere(void)
Definition: shapes.h:93
double d
Definition: shapes.h:220
unsigned int * triangles
the vertex indices for each triangle triangle k has vertices at index (3k, 3k+1, 3k+2) = (v1...
Definition: shapes.h:196
Definition of a plane with equation ax + by + cz + d = 0.
Definition: shapes.h:204
Mesh * createMeshFromBinaryStlData(const char *data, unsigned int size)
Load a mesh from a binary STL stream. Normals are recomputed and repeating vertices are identified...
Definition: load_mesh.cpp:462
unsigned int triangleCount
the number of triangles formed with the vertices
Definition: shapes.h:192
Mesh * createMeshFromBinaryDAE(const char *filename)
Load a mesh from a binary DAE file. Normals are recomputed and repeating vertices are identified...
Definition: load_mesh.cpp:520
A basic definition of a static shape. Static shapes do not have a pose.
Definition: shapes.h:74
A basic definition of a shape. Shapes are considered centered at origin.
Definition: shapes.h:58
unsigned int vertexCount
the number of available vertices
Definition: shapes.h:185
virtual ~Mesh(void)
Definition: shapes.h:174
Shape(void)
Definition: shapes.h:61
ShapeType
A list of known shape types.
Definition: shapes.h:52
double * vertices
the position for each vertex vertex k has values at index (3k, 3k+1, 3k+2) = (x,y,z)
Definition: shapes.h:189
Sphere(double r)
Definition: shapes.h:99
virtual ~Shape(void)
Definition: shapes.h:66
Mesh(unsigned int vCount, unsigned int tCount)
Definition: shapes.h:164
Definition of a sphere.
Definition: shapes.h:90
Box(void)
Definition: shapes.h:132
Cylinder(void)
Definition: shapes.h:112
Box(double x, double y, double z)
Definition: shapes.h:138
Definition of a mesh.
Definition: shapes.h:151
Definition of a box.
Definition: shapes.h:129
StaticShapeType type
Definition: shapes.h:86
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
double radius
Definition: shapes.h:105
virtual ~StaticShape(void)
Definition: shapes.h:82
Cylinder(double r, double l)
Definition: shapes.h:118
double * normals
the normal to each triangle unit vector represented as (x,y,z)
Definition: shapes.h:200
StaticShape(void)
Definition: shapes.h:77
Shape * cloneShape(const Shape *shape)
Create a copy of a shape.
Definition: shapes.cpp:39


pr2_navigation_self_filter
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Jun 10 2019 14:28:54