shapes.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, 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 
39 #include <octomap/octomap.h>
41 
42 namespace shapes
43 {
44 const std::string Sphere::STRING_NAME = "sphere";
45 const std::string Box::STRING_NAME = "box";
46 const std::string Cylinder::STRING_NAME = "cylinder";
47 const std::string Cone::STRING_NAME = "cone";
48 const std::string Mesh::STRING_NAME = "mesh";
49 const std::string Plane::STRING_NAME = "plane";
50 const std::string OcTree::STRING_NAME = "octree";
51 
52 std::ostream& operator<<(std::ostream& ss, ShapeType type)
53 {
54  switch (type)
55  {
56  case UNKNOWN_SHAPE:
57  ss << "unknown";
58  break;
59  case SPHERE:
60  ss << Sphere::STRING_NAME;
61  break;
62  case CYLINDER:
64  break;
65  case CONE:
66  ss << Cone::STRING_NAME;
67  break;
68  case BOX:
69  ss << Box::STRING_NAME;
70  break;
71  case PLANE:
72  ss << Plane::STRING_NAME;
73  break;
74  case MESH:
75  ss << Mesh::STRING_NAME;
76  break;
77  case OCTREE:
78  ss << OcTree::STRING_NAME;
79  break;
80  default:
81  ss << "impossible";
82  break;
83  }
84  return ss;
85 }
86 
88 {
90 }
91 
93 {
94 }
95 
97 {
98  type = SPHERE;
99  radius = 0.0;
100 }
101 
102 Sphere::Sphere(double r) : Shape()
103 {
104  type = SPHERE;
105  radius = r;
106 }
107 
109 {
110  type = CYLINDER;
111  length = radius = 0.0;
112 }
113 
114 Cylinder::Cylinder(double r, double l) : Shape()
115 {
116  type = CYLINDER;
117  length = l;
118  radius = r;
119 }
120 
122 {
123  type = CONE;
124  length = radius = 0.0;
125 }
126 
127 Cone::Cone(double r, double l) : Shape()
128 {
129  type = CONE;
130  length = l;
131  radius = r;
132 }
133 
135 {
136  type = BOX;
137  size[0] = size[1] = size[2] = 0.0;
138 }
139 
140 Box::Box(double x, double y, double z) : Shape()
141 {
142  type = BOX;
143  size[0] = x;
144  size[1] = y;
145  size[2] = z;
146 }
147 
149 {
150  type = MESH;
151  vertex_count = 0;
152  vertices = NULL;
153  triangle_count = 0;
154  triangles = NULL;
155  triangle_normals = NULL;
156  vertex_normals = NULL;
157 }
158 
159 Mesh::Mesh(unsigned int v_count, unsigned int t_count) : Shape()
160 {
161  type = MESH;
162  vertex_count = v_count;
163  vertices = new double[v_count * 3];
164  triangle_count = t_count;
165  triangles = new unsigned int[t_count * 3];
166  triangle_normals = new double[t_count * 3];
167  vertex_normals = new double[v_count * 3];
168 }
169 
171 {
172  if (vertices)
173  delete[] vertices;
174  if (triangles)
175  delete[] triangles;
176  if (triangle_normals)
177  delete[] triangle_normals;
178  if (vertex_normals)
179  delete[] vertex_normals;
180 }
181 
183 {
184  type = PLANE;
185  a = b = c = d = 0.0;
186 }
187 
188 Plane::Plane(double pa, double pb, double pc, double pd) : Shape()
189 {
190  type = PLANE;
191  a = pa;
192  b = pb;
193  c = pc;
194  d = pd;
195 }
196 
198 {
199  type = OCTREE;
200 }
201 
202 OcTree::OcTree(const std::shared_ptr<const octomap::OcTree>& t) : octree(t)
203 {
204  type = OCTREE;
205 }
206 
208 {
209  return new Sphere(radius);
210 }
211 
213 {
214  return new Cylinder(radius, length);
215 }
216 
218 {
219  return new Cone(radius, length);
220 }
221 
223 {
224  return new Box(size[0], size[1], size[2]);
225 }
226 
228 {
229  Mesh* dest = new Mesh(vertex_count, triangle_count);
230  unsigned int n = 3 * vertex_count;
231  for (unsigned int i = 0; i < n; ++i)
232  dest->vertices[i] = vertices[i];
233  if (vertex_normals)
234  for (unsigned int i = 0; i < n; ++i)
235  dest->vertex_normals[i] = vertex_normals[i];
236  else
237  {
238  delete[] dest->vertex_normals;
239  dest->vertex_normals = NULL;
240  }
241  n = 3 * triangle_count;
242  for (unsigned int i = 0; i < n; ++i)
243  dest->triangles[i] = triangles[i];
244  if (triangle_normals)
245  for (unsigned int i = 0; i < n; ++i)
246  dest->triangle_normals[i] = triangle_normals[i];
247  else
248  {
249  delete[] dest->triangle_normals;
250  dest->triangle_normals = NULL;
251  }
252  return dest;
253 }
254 
256 {
257  return new Plane(a, b, c, d);
258 }
259 
261 {
262  return new OcTree(octree);
263 }
264 
265 void OcTree::scaleAndPadd(double scale, double padd)
266 {
267  CONSOLE_BRIDGE_logWarn("OcTrees cannot be scaled or padded");
268 }
269 
270 void Plane::scaleAndPadd(double scale, double padding)
271 {
272  CONSOLE_BRIDGE_logWarn("Planes cannot be scaled or padded");
273 }
274 
275 void Shape::scale(double scale)
276 {
277  scaleAndPadd(scale, 0.0);
278 }
279 
280 void Shape::padd(double padding)
281 {
282  scaleAndPadd(1.0, padding);
283 }
284 
285 void Sphere::scaleAndPadd(double scale, double padding)
286 {
287  radius = radius * scale + padding;
288 }
289 
290 void Cylinder::scaleAndPadd(double scale, double padding)
291 {
292  radius = radius * scale + padding;
293  length = length * scale + 2.0 * padding;
294 }
295 
296 void Cone::scaleAndPadd(double scale, double padding)
297 {
298  radius = radius * scale + padding;
299  length = length * scale + 2.0 * padding;
300 }
301 
302 void Box::scaleAndPadd(double scale, double padding)
303 {
304  double p2 = padding * 2.0;
305  size[0] = size[0] * scale + p2;
306  size[1] = size[1] * scale + p2;
307  size[2] = size[2] * scale + p2;
308 }
309 
310 void Mesh::scaleAndPadd(double scale, double padding)
311 {
312  // find the center of the mesh
313  double sx = 0.0, sy = 0.0, sz = 0.0;
314  for (unsigned int i = 0; i < vertex_count; ++i)
315  {
316  unsigned int i3 = i * 3;
317  sx += vertices[i3];
318  sy += vertices[i3 + 1];
319  sz += vertices[i3 + 2];
320  }
321  sx /= (double)vertex_count;
322  sy /= (double)vertex_count;
323  sz /= (double)vertex_count;
324 
325  // scale the mesh
326  for (unsigned int i = 0; i < vertex_count; ++i)
327  {
328  unsigned int i3 = i * 3;
329 
330  // vector from center to the vertex
331  double dx = vertices[i3] - sx;
332  double dy = vertices[i3 + 1] - sy;
333  double dz = vertices[i3 + 2] - sz;
334 
335  // length of vector
336  double norm = sqrt(dx * dx + dy * dy + dz * dz);
337  if (norm > 1e-6)
338  {
339  double fact = scale + padding / norm;
340  vertices[i3] = sx + dx * fact;
341  vertices[i3 + 1] = sy + dy * fact;
342  vertices[i3 + 2] = sz + dz * fact;
343  }
344  else
345  {
346  double ndx = ((dx > 0) ? dx + padding : dx - padding);
347  double ndy = ((dy > 0) ? dy + padding : dy - padding);
348  double ndz = ((dz > 0) ? dz + padding : dz - padding);
349  vertices[i3] = sx + ndx;
350  vertices[i3 + 1] = sy + ndy;
351  vertices[i3 + 2] = sz + ndz;
352  }
353  }
354 }
355 
356 void Shape::print(std::ostream& out) const
357 {
358  out << this << std::endl;
359 }
360 
361 void Sphere::print(std::ostream& out) const
362 {
363  out << "Sphere[radius=" << radius << "]" << std::endl;
364 }
365 
366 void Cylinder::print(std::ostream& out) const
367 {
368  out << "Cylinder[radius=" << radius << ", length=" << length << "]" << std::endl;
369 }
370 
371 void Cone::print(std::ostream& out) const
372 {
373  out << "Cone[radius=" << radius << ", length=" << length << "]" << std::endl;
374 }
375 
376 void Box::print(std::ostream& out) const
377 {
378  out << "Box[x=length=" << size[0] << ", y=width=" << size[1] << "z=height=" << size[2] << "]" << std::endl;
379 }
380 
381 void Mesh::print(std::ostream& out) const
382 {
383  out << "Mesh[vertices=" << vertex_count << ", triangles=" << triangle_count << "]" << std::endl;
384 }
385 
386 void Plane::print(std::ostream& out) const
387 {
388  out << "Plane[a=" << a << ", b=" << b << ", c=" << c << ", d=" << d << "]" << std::endl;
389 }
390 
391 void OcTree::print(std::ostream& out) const
392 {
393  if (octree)
394  {
395  double minx, miny, minz, maxx, maxy, maxz;
396  octree->getMetricMin(minx, miny, minz);
397  octree->getMetricMax(maxx, maxy, maxz);
398  out << "OcTree[depth = " << octree->getTreeDepth() << ", resolution = " << octree->getResolution()
399  << " inside box (minx=" << minx << ", miny=" << miny << ", minz=" << minz << ", maxx=" << maxx
400  << ", maxy=" << maxy << ", maxz=" << maxz << ")]" << std::endl;
401  }
402  else
403  out << "OcTree[NULL]" << std::endl;
404 }
405 
406 bool Shape::isFixed() const
407 {
408  return false;
409 }
410 
411 bool OcTree::isFixed() const
412 {
413  return true;
414 }
415 
416 bool Plane::isFixed() const
417 {
418  return true;
419 }
420 
422 {
423  if (triangle_count && !triangle_normals)
424  triangle_normals = new double[triangle_count * 3];
425 
426  // compute normals
427  for (unsigned int i = 0; i < triangle_count; ++i)
428  {
429  unsigned int i3 = i * 3;
430  Eigen::Vector3d s1(vertices[triangles[i3] * 3] - vertices[triangles[i3 + 1] * 3],
431  vertices[triangles[i3] * 3 + 1] - vertices[triangles[i3 + 1] * 3 + 1],
432  vertices[triangles[i3] * 3 + 2] - vertices[triangles[i3 + 1] * 3 + 2]);
433  Eigen::Vector3d s2(vertices[triangles[i3 + 1] * 3] - vertices[triangles[i3 + 2] * 3],
434  vertices[triangles[i3 + 1] * 3 + 1] - vertices[triangles[i3 + 2] * 3 + 1],
435  vertices[triangles[i3 + 1] * 3 + 2] - vertices[triangles[i3 + 2] * 3 + 2]);
436  Eigen::Vector3d normal = s1.cross(s2);
437  normal.normalize();
438  triangle_normals[i3] = normal.x();
439  triangle_normals[i3 + 1] = normal.y();
440  triangle_normals[i3 + 2] = normal.z();
441  }
442 }
443 
445 {
446  if (!triangle_normals)
447  computeTriangleNormals();
448  if (vertex_count && !vertex_normals)
449  vertex_normals = new double[vertex_count * 3];
450  EigenSTL::vector_Vector3d avg_normals(vertex_count, Eigen::Vector3d(0, 0, 0));
451 
452  for (unsigned int tIdx = 0; tIdx < triangle_count; ++tIdx)
453  {
454  unsigned int tIdx3 = 3 * tIdx;
455  unsigned int tIdx3_1 = tIdx3 + 1;
456  unsigned int tIdx3_2 = tIdx3 + 2;
457 
458  unsigned int v1 = triangles[tIdx3];
459  unsigned int v2 = triangles[tIdx3_1];
460  unsigned int v3 = triangles[tIdx3_2];
461 
462  avg_normals[v1][0] += triangle_normals[tIdx3];
463  avg_normals[v1][1] += triangle_normals[tIdx3_1];
464  avg_normals[v1][2] += triangle_normals[tIdx3_2];
465 
466  avg_normals[v2][0] += triangle_normals[tIdx3];
467  avg_normals[v2][1] += triangle_normals[tIdx3_1];
468  avg_normals[v2][2] += triangle_normals[tIdx3_2];
469 
470  avg_normals[v3][0] += triangle_normals[tIdx3];
471  avg_normals[v3][1] += triangle_normals[tIdx3_1];
472  avg_normals[v3][2] += triangle_normals[tIdx3_2];
473  }
474  for (std::size_t i = 0; i < avg_normals.size(); ++i)
475  {
476  if (avg_normals[i].squaredNorm() > 0.0)
477  avg_normals[i].normalize();
478  unsigned int i3 = i * 3;
479  vertex_normals[i3] = avg_normals[i][0];
480  vertex_normals[i3 + 1] = avg_normals[i][1];
481  vertex_normals[i3 + 2] = avg_normals[i][2];
482  }
483 }
484 
485 void Mesh::mergeVertices(double threshold)
486 {
487  const double thresholdSQR = threshold * threshold;
488 
489  std::vector<unsigned int> vertex_map(vertex_count);
490  EigenSTL::vector_Vector3d orig_vertices(vertex_count);
491  EigenSTL::vector_Vector3d compressed_vertices;
492 
493  for (unsigned int vIdx = 0; vIdx < vertex_count; ++vIdx)
494  {
495  orig_vertices[vIdx][0] = vertices[3 * vIdx];
496  orig_vertices[vIdx][1] = vertices[3 * vIdx + 1];
497  orig_vertices[vIdx][2] = vertices[3 * vIdx + 2];
498  vertex_map[vIdx] = vIdx;
499  }
500 
501  for (unsigned int vIdx1 = 0; vIdx1 < vertex_count; ++vIdx1)
502  {
503  if (vertex_map[vIdx1] != vIdx1)
504  continue;
505 
506  vertex_map[vIdx1] = compressed_vertices.size();
507  compressed_vertices.push_back(orig_vertices[vIdx1]);
508 
509  for (unsigned int vIdx2 = vIdx1 + 1; vIdx2 < vertex_count; ++vIdx2)
510  {
511  double distanceSQR = (orig_vertices[vIdx1] - orig_vertices[vIdx2]).squaredNorm();
512  if (distanceSQR <= thresholdSQR)
513  vertex_map[vIdx2] = vertex_map[vIdx1];
514  }
515  }
516 
517  if (compressed_vertices.size() == orig_vertices.size())
518  return;
519 
520  // redirect triangles to new vertices!
521  for (unsigned int tIdx = 0; tIdx < triangle_count; ++tIdx)
522  {
523  unsigned int i3 = 3 * tIdx;
524  triangles[i3] = vertex_map[triangles[i3]];
525  triangles[i3 + 1] = vertex_map[triangles[i3 + 1]];
526  triangles[i3 + 2] = vertex_map[triangles[i3 + 2]];
527  }
528 
529  vertex_count = compressed_vertices.size();
530  delete[] vertices;
531  vertices = new double[vertex_count * 3];
532 
533  for (unsigned int vIdx = 0; vIdx < vertex_count; ++vIdx)
534  {
535  unsigned int i3 = 3 * vIdx;
536  vertices[i3] = compressed_vertices[vIdx][0];
537  vertices[i3 + 1] = compressed_vertices[vIdx][1];
538  vertices[i3 + 2] = compressed_vertices[vIdx][2];
539  }
540 
541  if (triangle_normals)
542  computeTriangleNormals();
543  if (vertex_normals)
544  computeVertexNormals();
545 }
546 
547 } /* namespace shapes */
#define CONSOLE_BRIDGE_logWarn(fmt,...)
d
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
virtual void print(std::ostream &out=std::cout) const
Print information about this shape.
Definition: shapes.cpp:376
void scale(double scale)
Scale this shape by a factor.
Definition: shapes.cpp:275
void mergeVertices(double threshold)
Merge vertices that are very close to each other, up to a threshold.
Definition: shapes.cpp:485
virtual Shape * clone() const
Create a copy of this shape.
Definition: shapes.cpp:255
virtual bool isFixed() const
Return a flag indicating whether this shape can be scaled and/or padded.
Definition: shapes.cpp:411
Definition of a cylinder Length is along z axis. Origin is at center of mass.
Definition: shapes.h:127
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
virtual void print(std::ostream &out=std::cout) const
Print information about this shape.
Definition: shapes.cpp:386
virtual Shape * clone() const
Create a copy of this shape.
Definition: shapes.cpp:227
double length
The length (height) of the cone.
Definition: shapes.h:166
double size[3]
x, y, z dimensions of the box (axis-aligned)
Definition: shapes.h:188
double b
Definition: shapes.h:260
ShapeType type
The type of the shape.
Definition: shapes.h:102
virtual Shape * clone() const
Create a copy of this shape.
Definition: shapes.cpp:222
static double distanceSQR(const Eigen::Vector3d &p, const Eigen::Vector3d &origin, const Eigen::Vector3d &dir)
Compute the square of the distance between a ray and a point Note: this requires &#39;dir&#39; to be normaliz...
Definition: bodies.cpp:78
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
virtual void print(std::ostream &out=std::cout) const
Print information about this shape.
Definition: shapes.cpp:381
double length
The length of the cylinder.
Definition: shapes.h:143
virtual ~Mesh()
Definition: shapes.cpp:170
double c
Definition: shapes.h:260
virtual void scaleAndPadd(double scale, double padd)
Scale and padd this shape.
Definition: shapes.cpp:310
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
virtual void print(std::ostream &out=std::cout) const
Print information about this shape.
Definition: shapes.cpp:391
virtual void scaleAndPadd(double scale, double padd)
Scale and padd this shape.
Definition: shapes.cpp:285
double y
Definition of a plane with equation ax + by + cz + d = 0.
Definition: shapes.h:245
double a
The plane equation is ax + by + cz + d = 0.
Definition: shapes.h:260
double * vertex_normals
The normal to each vertex; unit vector represented as (x,y,z); If missing from the mesh...
Definition: shapes.h:241
std::ostream & operator<<(std::ostream &ss, ShapeType type)
Definition: shapes.cpp:52
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
virtual void scaleAndPadd(double scale, double padd)
Scale and padd this shape.
Definition: shapes.cpp:290
void padd(double padding)
Add padding to this shape.
Definition: shapes.cpp:280
A basic definition of a shape. Shapes are considered centered at origin.
Definition: shapes.h:77
unsigned int triangle_count
The number of triangles formed with the vertices.
Definition: shapes.h:229
virtual void print(std::ostream &out=std::cout) const
Print information about this shape.
Definition: shapes.cpp:371
virtual bool isFixed() const
Return a flag indicating whether this shape can be scaled and/or padded.
Definition: shapes.cpp:406
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
virtual void scaleAndPadd(double scale, double padd)
Scale and padd this shape.
Definition: shapes.cpp:265
double * triangle_normals
The normal to each triangle; unit vector represented as (x,y,z); If missing from the mesh...
Definition: shapes.h:237
virtual void print(std::ostream &out=std::cout) const
Print information about this shape.
Definition: shapes.cpp:361
void computeVertexNormals()
Compute vertex normals by averaging from adjacent triangle normals.
Definition: shapes.cpp:444
virtual void scaleAndPadd(double scale, double padd)
Scale and padd this shape.
Definition: shapes.cpp:302
virtual Shape * clone() const
Create a copy of this shape.
Definition: shapes.cpp:217
Definition of a sphere.
Definition: shapes.h:106
virtual ~Shape()
Definition: shapes.cpp:92
virtual void print(std::ostream &out=std::cout) const
Print information about this shape.
Definition: shapes.cpp:366
void computeTriangleNormals()
Compute the normals of each triangle from its vertices via cross product.
Definition: shapes.cpp:421
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
virtual bool isFixed() const
Return a flag indicating whether this shape can be scaled and/or padded.
Definition: shapes.cpp:416
virtual Shape * clone() const
Create a copy of this shape.
Definition: shapes.cpp:212
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
virtual void scaleAndPadd(double scale, double padd)
Scale and padd this shape.
Definition: shapes.cpp:270
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:115
virtual void print(std::ostream &out=std::cout) const
Print information about this shape.
Definition: shapes.cpp:356
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:181
double x
virtual Shape * clone() const
Create a copy of this shape.
Definition: shapes.cpp:260
virtual Shape * clone() const
Create a copy of this shape.
Definition: shapes.cpp:207
virtual void scaleAndPadd(double scale, double padd)
Scale and padd this shape.
Definition: shapes.cpp:296
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:159


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