shapes.cpp
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 
38 
40 {
41  shapes::Shape *result = NULL;
42  switch (shape->type)
43  {
44  case SPHERE:
45  result = new Sphere(static_cast<const Sphere*>(shape)->radius);
46  break;
47  case CYLINDER:
48  result = new Cylinder(static_cast<const Cylinder*>(shape)->radius, static_cast<const Cylinder*>(shape)->length);
49  break;
50  case BOX:
51  result = new Box(static_cast<const Box*>(shape)->size[0], static_cast<const Box*>(shape)->size[1], static_cast<const Box*>(shape)->size[2]);
52  break;
53  case MESH:
54  {
55  const Mesh *src = static_cast<const Mesh*>(shape);
56  Mesh *dest = new Mesh(src->vertexCount, src->triangleCount);
57  unsigned int n = 3 * src->vertexCount;
58  for (unsigned int i = 0 ; i < n ; ++i)
59  dest->vertices[i] = src->vertices[i];
60  n = 3 * src->triangleCount;
61  for (unsigned int i = 0 ; i < n ; ++i)
62  {
63  dest->triangles[i] = src->triangles[i];
64  dest->normals[i] = src->normals[i];
65  }
66  result = dest;
67  }
68  break;
69  default:
70  break;
71  }
72  return result;
73 }
74 
76 {
77  shapes::StaticShape *result = NULL;
78  switch (shape->type)
79  {
80  case PLANE:
81  result = new Plane(static_cast<const Plane*>(shape)->a, static_cast<const Plane*>(shape)->b,
82  static_cast<const Plane*>(shape)->c, static_cast<const Plane*>(shape)->d);
83  break;
84  default:
85  break;
86  }
87 
88  return result;
89 }
d
Definition of a cylinder.
Definition: shapes.h:109
ShapeType type
Definition: shapes.h:70
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
unsigned int triangleCount
the number of triangles formed with the vertices
Definition: shapes.h:192
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
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
Definition of a sphere.
Definition: shapes.h:90
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 * normals
the normal to each triangle unit vector represented as (x,y,z)
Definition: shapes.h:200
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