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 
35 /* Author: Ioan Sucan */
36 
37 #ifndef GEOMETRIC_SHAPES_SHAPES_
38 #define GEOMETRIC_SHAPES_SHAPES_
39 
40 #if __cplusplus <= 199711L
41 #error This header requires at least C++11
42 #endif
43 
44 #include <cstdlib>
45 #include <vector>
46 #include <iostream>
47 #include <memory>
48 #include <string>
49 
50 namespace octomap
51 {
52 class OcTree;
53 }
54 
58 namespace shapes
59 {
62 {
67  BOX,
71 };
72 
73 /* convert above enum to printable */
74 std::ostream& operator<<(std::ostream& ss, ShapeType type);
75 
77 class Shape
78 {
79 public:
80  Shape();
81  virtual ~Shape();
82 
84  virtual Shape* clone() const = 0;
85 
87  virtual void print(std::ostream& out = std::cout) const;
88 
90  void scale(double scale);
91 
93  void padd(double padding);
94 
96  virtual void scaleAndPadd(double scale, double padd) = 0;
97 
99  virtual bool isFixed() const;
100 
103 };
104 
106 class Sphere : public Shape
107 {
108 public:
109  Sphere();
110 
112  Sphere(double r);
113 
115  static const std::string STRING_NAME;
116 
117  virtual void scaleAndPadd(double scale, double padd);
118  virtual Shape* clone() const;
119  virtual void print(std::ostream& out = std::cout) const;
120 
122  double radius;
123 };
124 
127 class Cylinder : public Shape
128 {
129 public:
130  Cylinder();
131 
133  Cylinder(double r, double l);
134 
136  static const std::string STRING_NAME;
137 
138  virtual void scaleAndPadd(double scale, double padd);
139  virtual Shape* clone() const;
140  virtual void print(std::ostream& out = std::cout) const;
141 
143  double length;
144 
146  double radius;
147 };
148 
152 class Cone : public Shape
153 {
154 public:
155  Cone();
156  Cone(double r, double l);
157 
159  static const std::string STRING_NAME;
160 
161  virtual void scaleAndPadd(double scale, double padd);
162  virtual Shape* clone() const;
163  virtual void print(std::ostream& out = std::cout) const;
164 
166  double length;
167 
169  double radius;
170 };
171 
174 class Box : public Shape
175 {
176 public:
177  Box();
178  Box(double x, double y, double z);
179 
181  static const std::string STRING_NAME;
182 
183  virtual void scaleAndPadd(double scale, double padd);
184  virtual Shape* clone() const;
185  virtual void print(std::ostream& out = std::cout) const;
186 
188  double size[3];
189 };
190 
196 class Mesh : public Shape
197 {
198 public:
199  Mesh();
200  Mesh(unsigned int v_count, unsigned int t_count);
201  virtual ~Mesh();
202 
204  static const std::string STRING_NAME;
205 
206  virtual void scaleAndPadd(double scale, double padd);
207  virtual Shape* clone() const;
208  virtual void print(std::ostream& out = std::cout) const;
209 
211  void computeTriangleNormals();
212 
216  void computeVertexNormals();
217 
219  void mergeVertices(double threshold);
220 
222  unsigned int vertex_count;
223 
226  double* vertices;
227 
229  unsigned int triangle_count;
230 
233  unsigned int* triangles;
234 
238 
241  double* vertex_normals;
242 };
243 
245 class Plane : public Shape
246 {
247 public:
248  Plane();
249  Plane(double pa, double pb, double pc, double pd);
250 
252  static const std::string STRING_NAME;
253 
254  virtual Shape* clone() const;
255  virtual void print(std::ostream& out = std::cout) const;
256  virtual void scaleAndPadd(double scale, double padd);
257  virtual bool isFixed() const;
258 
260  double a, b, c, d;
261 };
262 
264 class OcTree : public Shape
265 {
266 public:
267  OcTree();
268  OcTree(const std::shared_ptr<const octomap::OcTree>& t);
269 
271  static const std::string STRING_NAME;
272 
273  virtual Shape* clone() const;
274  virtual void print(std::ostream& out = std::cout) const;
275  virtual void scaleAndPadd(double scale, double padd);
276  virtual bool isFixed() const;
277 
278  std::shared_ptr<const octomap::OcTree> octree;
279 };
280 
282 typedef std::shared_ptr<Shape> ShapePtr;
283 
285 typedef std::shared_ptr<const Shape> ShapeConstPtr;
286 }
287 
288 #endif
Definition of various shapes. No properties such as position are included. These are simply the descr...
double radius
The radius of the cylinder.
Definition: shapes.h:146
Definition of a cylinder Length is along z axis. Origin is at center of mass.
Definition: shapes.h:127
double length
The length (height) of the cone.
Definition: shapes.h:166
ShapeType type
The type of the shape.
Definition: shapes.h:102
double radius
The radius of the cone.
Definition: shapes.h:169
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:136
double d
Definition: shapes.h:260
double length
The length of the cylinder.
Definition: shapes.h:143
unsigned int * triangles
The vertex indices for each triangle triangle k has vertices at index (3k, 3k+1, 3k+2) = (v1...
Definition: shapes.h:233
std::shared_ptr< Shape > ShapePtr
Shared pointer to a Shape.
Definition: shapes.h:282
ROSCONSOLE_DECL void print(FilterBase *filter, void *logger, Level level, const char *file, int line, const char *function, const char *fmt,...) ROSCONSOLE_PRINTF_ATTRIBUTE(7
double y
Definition of a plane with equation ax + by + cz + d = 0.
Definition: shapes.h:245
double * vertex_normals
The normal to each vertex; unit vector represented as (x,y,z); If missing from the mesh...
Definition: shapes.h:241
Representation of an octomap::OcTree as a Shape.
Definition: shapes.h:264
std::shared_ptr< const octomap::OcTree > octree
Definition: shapes.h:278
Definition of a cone Tip is on positive z axis. Center of base is on negative z axis. Origin is halway between tip and center of base.
Definition: shapes.h:152
unsigned int vertex_count
The number of available vertices.
Definition: shapes.h:222
A basic definition of a shape. Shapes are considered centered at origin.
Definition: shapes.h:77
std::ostream & operator<<(std::ostream &out, ColorOcTreeNode::Color const &c)
unsigned int triangle_count
The number of triangles formed with the vertices.
Definition: shapes.h:229
double z
ShapeType
A list of known shape types.
Definition: shapes.h:61
double * vertices
The position for each vertex vertex k has values at index (3k, 3k+1, 3k+2) = (x,y,z)
Definition: shapes.h:226
double * triangle_normals
The normal to each triangle; unit vector represented as (x,y,z); If missing from the mesh...
Definition: shapes.h:237
Definition of a sphere.
Definition: shapes.h:106
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:252
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:271
Definition of a triangle mesh By convention the "center" of the shape is at the origin. For a mesh this implies that the AABB of the mesh is centered at the origin. Some methods may not work with arbitrary meshes whose AABB is not centered at the origin.
Definition: shapes.h:196
Definition of a box Aligned with the XYZ axes.
Definition: shapes.h:174
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:204
double radius
The radius of the sphere.
Definition: shapes.h:122
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:115
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:181
double x
r
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:159
std::shared_ptr< const Shape > ShapeConstPtr
Shared pointer to a const Shape.
Definition: shapes.h:285


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Mon Jun 10 2019 13:22:04