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  void scaleAndPadd(double scale, double padd) override;
118  Sphere* clone() const override;
119  void print(std::ostream& out = std::cout) const override;
120 
122  double radius;
123 };
124 
127 class Cylinder : public Shape
128 {
129 public:
130  using Shape::padd;
131  using Shape::scale;
132 
133  Cylinder();
134 
136  Cylinder(double r, double l);
137 
139  static const std::string STRING_NAME;
140 
146  void scale(double scaleRadius, double scaleLength);
147 
153  void padd(double paddRadius, double paddLength);
154 
162  void scaleAndPadd(double scaleRadius, double scaleLength, double paddRadius, double paddLength);
163 
164  void scaleAndPadd(double scale, double padd) override;
165  Cylinder* clone() const override;
166  void print(std::ostream& out = std::cout) const override;
167 
169  double length;
170 
172  double radius;
173 };
174 
178 class Cone : public Shape
179 {
180 public:
181  using Shape::padd;
182  using Shape::scale;
183 
184  Cone();
185  Cone(double r, double l);
186 
188  static const std::string STRING_NAME;
189 
195  void scale(double scaleRadius, double scaleLength);
196 
202  void padd(double paddRadius, double paddLength);
203 
211  void scaleAndPadd(double scaleRadius, double scaleLength, double paddRadius, double paddLength);
212 
213  void scaleAndPadd(double scale, double padd) override;
214  Cone* clone() const override;
215  void print(std::ostream& out = std::cout) const override;
216 
218  double length;
219 
221  double radius;
222 };
223 
226 class Box : public Shape
227 {
228 public:
229  using Shape::padd;
230  using Shape::scale;
231 
232  Box();
233  Box(double x, double y, double z);
234 
236  static const std::string STRING_NAME;
237 
244  void scale(double scaleX, double scaleY, double scaleZ);
245 
252  void padd(double paddX, double paddY, double paddZ);
253 
263  void scaleAndPadd(double scaleX, double scaleY, double scaleZ, double paddX, double paddY, double paddZ);
264 
265  void scaleAndPadd(double scale, double padd) override;
266  Box* clone() const override;
267  void print(std::ostream& out = std::cout) const override;
268 
270  double size[3];
271 };
272 
281 class Mesh : public Shape
282 {
283 public:
284  using Shape::padd;
285  using Shape::scale;
286 
287  Mesh();
288  Mesh(unsigned int v_count, unsigned int t_count);
289  ~Mesh() override;
290 
292  static const std::string STRING_NAME;
293 
300  void scale(double scaleX, double scaleY, double scaleZ);
301 
311  void padd(double paddX, double paddY, double paddZ);
312 
325  void scaleAndPadd(double scaleX, double scaleY, double scaleZ, double paddX, double paddY, double paddZ);
326 
327  void scaleAndPadd(double scale, double padd) override;
328  Mesh* clone() const override;
329  void print(std::ostream& out = std::cout) const override;
330 
332  void computeTriangleNormals();
333 
337  void computeVertexNormals();
338 
340  void mergeVertices(double threshold);
341 
343  unsigned int vertex_count;
344 
347  double* vertices;
348 
350  unsigned int triangle_count;
351 
354  unsigned int* triangles;
355 
359 
362  double* vertex_normals;
363 };
364 
366 class Plane : public Shape
367 {
368 public:
369  Plane();
370  Plane(double pa, double pb, double pc, double pd);
371 
373  static const std::string STRING_NAME;
374 
375  Plane* clone() const override;
376  void print(std::ostream& out = std::cout) const override;
377  void scaleAndPadd(double scale, double padd) override;
378  bool isFixed() const override;
379 
381  double a, b, c, d;
382 };
383 
385 class OcTree : public Shape
386 {
387 public:
388  OcTree();
389  OcTree(const std::shared_ptr<const octomap::OcTree>& t);
390 
392  static const std::string STRING_NAME;
393 
394  OcTree* clone() const override;
395  void print(std::ostream& out = std::cout) const override;
396  void scaleAndPadd(double scale, double padd) override;
397  bool isFixed() const override;
398 
399  std::shared_ptr<const octomap::OcTree> octree;
400 };
401 
403 typedef std::shared_ptr<Shape> ShapePtr;
404 
406 typedef std::shared_ptr<const Shape> ShapeConstPtr;
407 } // namespace shapes
408 
409 #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:172
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:218
ShapeType type
The type of the shape.
Definition: shapes.h:102
double radius
The radius of the cone.
Definition: shapes.h:221
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:139
double d
Definition: shapes.h:381
double length
The length of the cylinder.
Definition: shapes.h:169
unsigned int * triangles
The vertex indices for each triangle triangle k has vertices at index (3k, 3k+1, 3k+2) = (v1...
Definition: shapes.h:354
std::shared_ptr< Shape > ShapePtr
Shared pointer to a Shape.
Definition: shapes.h:403
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:366
double * vertex_normals
The normal to each vertex; unit vector represented as (x,y,z); If missing from the mesh...
Definition: shapes.h:362
Representation of an octomap::OcTree as a Shape.
Definition: shapes.h:385
std::shared_ptr< const octomap::OcTree > octree
Definition: shapes.h:399
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:178
unsigned int vertex_count
The number of available vertices.
Definition: shapes.h:343
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:350
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:347
double * triangle_normals
The normal to each triangle; unit vector represented as (x,y,z); If missing from the mesh...
Definition: shapes.h:358
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:373
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:392
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. Padding is not applied to vertices plainly coordinate-wise, but instead the padding value is added to the length of the direction vector between centroid and each vertex.
Definition: shapes.h:281
Definition of a box Aligned with the XYZ axes.
Definition: shapes.h:226
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:292
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:236
double x
r
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:188
std::shared_ptr< const Shape > ShapeConstPtr
Shared pointer to a const Shape.
Definition: shapes.h:406


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Fri Apr 14 2023 02:14:40