shape_operations.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 
35 /* Author: Ioan Sucan */
36 
38 
39 #include <cstdio>
40 #include <cmath>
41 #include <algorithm>
42 #include <set>
43 #include <float.h>
44 
45 #include <console_bridge/console.h>
46 
47 #include <Eigen/Geometry>
48 
52 
53 namespace shapes
54 {
55 Shape* constructShapeFromMsg(const shape_msgs::Plane& shape_msg)
56 {
57  return new Plane(shape_msg.coef[0], shape_msg.coef[1], shape_msg.coef[2], shape_msg.coef[3]);
58 }
59 
60 Shape* constructShapeFromMsg(const shape_msgs::Mesh& shape_msg)
61 {
62  if (shape_msg.triangles.empty() || shape_msg.vertices.empty())
63  {
64  CONSOLE_BRIDGE_logWarn("Mesh definition is empty");
65  return nullptr;
66  }
67  else
68  {
69  EigenSTL::vector_Vector3d vertices(shape_msg.vertices.size());
70  std::vector<unsigned int> triangles(shape_msg.triangles.size() * 3);
71  for (unsigned int i = 0; i < shape_msg.vertices.size(); ++i)
72  vertices[i] = Eigen::Vector3d(shape_msg.vertices[i].x, shape_msg.vertices[i].y, shape_msg.vertices[i].z);
73  for (unsigned int i = 0; i < shape_msg.triangles.size(); ++i)
74  {
75  unsigned int i3 = i * 3;
76  triangles[i3++] = shape_msg.triangles[i].vertex_indices[0];
77  triangles[i3++] = shape_msg.triangles[i].vertex_indices[1];
78  triangles[i3] = shape_msg.triangles[i].vertex_indices[2];
79  }
80  return createMeshFromVertices(vertices, triangles);
81  }
82 }
83 
84 Shape* constructShapeFromMsg(const shape_msgs::SolidPrimitive& shape_msg)
85 {
86  Shape* shape = nullptr;
87  if (shape_msg.type == shape_msgs::SolidPrimitive::SPHERE)
88  {
89  if (shape_msg.dimensions.size() >= geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::SPHERE>())
90  shape = new Sphere(shape_msg.dimensions[shape_msgs::SolidPrimitive::SPHERE_RADIUS]);
91  }
92  else if (shape_msg.type == shape_msgs::SolidPrimitive::BOX)
93  {
94  if (shape_msg.dimensions.size() >= geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>())
95  shape = new Box(shape_msg.dimensions[shape_msgs::SolidPrimitive::BOX_X],
96  shape_msg.dimensions[shape_msgs::SolidPrimitive::BOX_Y],
97  shape_msg.dimensions[shape_msgs::SolidPrimitive::BOX_Z]);
98  }
99  else if (shape_msg.type == shape_msgs::SolidPrimitive::CYLINDER)
100  {
101  if (shape_msg.dimensions.size() >= geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::CYLINDER>())
102  shape = new Cylinder(shape_msg.dimensions[shape_msgs::SolidPrimitive::CYLINDER_RADIUS],
103  shape_msg.dimensions[shape_msgs::SolidPrimitive::CYLINDER_HEIGHT]);
104  }
105  else if (shape_msg.type == shape_msgs::SolidPrimitive::CONE)
106  {
107  if (shape_msg.dimensions.size() >= geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::CONE>())
108  shape = new Cone(shape_msg.dimensions[shape_msgs::SolidPrimitive::CONE_RADIUS],
109  shape_msg.dimensions[shape_msgs::SolidPrimitive::CONE_HEIGHT]);
110  }
111  if (shape == nullptr)
112  CONSOLE_BRIDGE_logError("Unable to construct shape corresponding to shape_msg of type %d", (int)shape_msg.type);
113 
114  return shape;
115 }
116 
117 namespace
118 {
119 class ShapeVisitorAlloc : public boost::static_visitor<Shape*>
120 {
121 public:
122  Shape* operator()(const shape_msgs::Plane& shape_msg) const
123  {
124  return constructShapeFromMsg(shape_msg);
125  }
126 
127  Shape* operator()(const shape_msgs::Mesh& shape_msg) const
128  {
129  return constructShapeFromMsg(shape_msg);
130  }
131 
132  Shape* operator()(const shape_msgs::SolidPrimitive& shape_msg) const
133  {
134  return constructShapeFromMsg(shape_msg);
135  }
136 };
137 } // namespace
138 
139 Shape* constructShapeFromMsg(const ShapeMsg& shape_msg)
140 {
141  return boost::apply_visitor(ShapeVisitorAlloc(), shape_msg);
142 }
143 
144 namespace
145 {
146 class ShapeVisitorMarker : public boost::static_visitor<void>
147 {
148 public:
149  ShapeVisitorMarker(visualization_msgs::Marker* marker, bool use_mesh_triangle_list)
150  : boost::static_visitor<void>(), use_mesh_triangle_list_(use_mesh_triangle_list), marker_(marker)
151  {
152  }
153 
154  void operator()(const shape_msgs::Plane& /* shape_msg */) const
155  {
156  throw std::runtime_error("No visual markers can be constructed for planes");
157  }
158 
159  void operator()(const shape_msgs::Mesh& shape_msg) const
160  {
162  }
163 
164  void operator()(const shape_msgs::SolidPrimitive& shape_msg) const
165  {
167  }
168 
169 private:
171  visualization_msgs::Marker* marker_;
172 };
173 } // namespace
174 
175 bool constructMarkerFromShape(const Shape* shape, visualization_msgs::Marker& marker, bool use_mesh_triangle_list)
176 {
177  ShapeMsg shape_msg;
178  if (constructMsgFromShape(shape, shape_msg))
179  {
180  bool ok = false;
181  try
182  {
183  boost::apply_visitor(ShapeVisitorMarker(&marker, use_mesh_triangle_list), shape_msg);
184  ok = true;
185  }
186  catch (std::runtime_error& ex)
187  {
188  CONSOLE_BRIDGE_logError("%s", ex.what());
189  }
190  if (ok)
191  return true;
192  }
193  return false;
194 }
195 
196 namespace
197 {
198 class ShapeVisitorComputeExtents : public boost::static_visitor<Eigen::Vector3d>
199 {
200 public:
201  Eigen::Vector3d operator()(const shape_msgs::Plane& /* shape_msg */) const
202  {
203  Eigen::Vector3d e(0.0, 0.0, 0.0);
204  return e;
205  }
206 
207  Eigen::Vector3d operator()(const shape_msgs::Mesh& shape_msg) const
208  {
209  double x_extent, y_extent, z_extent;
210  geometric_shapes::getShapeExtents(shape_msg, x_extent, y_extent, z_extent);
211  Eigen::Vector3d e(x_extent, y_extent, z_extent);
212  return e;
213  }
214 
215  Eigen::Vector3d operator()(const shape_msgs::SolidPrimitive& shape_msg) const
216  {
217  double x_extent, y_extent, z_extent;
218  geometric_shapes::getShapeExtents(shape_msg, x_extent, y_extent, z_extent);
219  Eigen::Vector3d e(x_extent, y_extent, z_extent);
220  return e;
221  }
222 };
223 } // namespace
224 
225 Eigen::Vector3d computeShapeExtents(const ShapeMsg& shape_msg)
226 {
227  return boost::apply_visitor(ShapeVisitorComputeExtents(), shape_msg);
228 }
229 
230 Eigen::Vector3d computeShapeExtents(const Shape* shape)
231 {
232  if (shape->type == SPHERE)
233  {
234  double d = static_cast<const Sphere*>(shape)->radius * 2.0;
235  return Eigen::Vector3d(d, d, d);
236  }
237  else if (shape->type == BOX)
238  {
239  const double* sz = static_cast<const Box*>(shape)->size;
240  return Eigen::Vector3d(sz[0], sz[1], sz[2]);
241  }
242  else if (shape->type == CYLINDER)
243  {
244  double d = static_cast<const Cylinder*>(shape)->radius * 2.0;
245  return Eigen::Vector3d(d, d, static_cast<const Cylinder*>(shape)->length);
246  }
247  else if (shape->type == CONE)
248  {
249  double d = static_cast<const Cone*>(shape)->radius * 2.0;
250  return Eigen::Vector3d(d, d, static_cast<const Cone*>(shape)->length);
251  }
252  else if (shape->type == MESH)
253  {
254  const Mesh* mesh = static_cast<const Mesh*>(shape);
255  if (mesh->vertex_count > 1)
256  {
257  std::vector<double> vmin(3, std::numeric_limits<double>::max());
258  std::vector<double> vmax(3, -std::numeric_limits<double>::max());
259  for (unsigned int i = 0; i < mesh->vertex_count; ++i)
260  {
261  unsigned int i3 = i * 3;
262  for (unsigned int k = 0; k < 3; ++k)
263  {
264  unsigned int i3k = i3 + k;
265  if (mesh->vertices[i3k] > vmax[k])
266  vmax[k] = mesh->vertices[i3k];
267  if (mesh->vertices[i3k] < vmin[k])
268  vmin[k] = mesh->vertices[i3k];
269  }
270  }
271  return Eigen::Vector3d(vmax[0] - vmin[0], vmax[1] - vmin[1], vmax[2] - vmin[2]);
272  }
273  else
274  return Eigen::Vector3d(0.0, 0.0, 0.0);
275  }
276  else
277  return Eigen::Vector3d(0.0, 0.0, 0.0);
278 }
279 
280 void computeShapeBoundingSphere(const Shape* shape, Eigen::Vector3d& center, double& radius)
281 {
282  center.x() = 0.0;
283  center.y() = 0.0;
284  center.z() = 0.0;
285  radius = 0.0;
286 
287  if (shape->type == SPHERE)
288  {
289  radius = static_cast<const Sphere*>(shape)->radius;
290  }
291  else if (shape->type == BOX)
292  {
293  const double* sz = static_cast<const Box*>(shape)->size;
294  double half_width = sz[0] * 0.5;
295  double half_height = sz[1] * 0.5;
296  double half_depth = sz[2] * 0.5;
297  radius = std::sqrt(half_width * half_width + half_height * half_height + half_depth * half_depth);
298  }
299  else if (shape->type == CYLINDER)
300  {
301  double cyl_radius = static_cast<const Cylinder*>(shape)->radius;
302  double half_len = static_cast<const Cylinder*>(shape)->length * 0.5;
303  radius = std::sqrt(cyl_radius * cyl_radius + half_len * half_len);
304  }
305  else if (shape->type == CONE)
306  {
307  double cone_radius = static_cast<const Cone*>(shape)->radius;
308  double cone_height = static_cast<const Cone*>(shape)->length;
309 
310  if (cone_height > cone_radius)
311  {
312  // center of sphere is intersection of perpendicular bisectors:
313  double z = (cone_height - (cone_radius * cone_radius / cone_height)) * 0.5;
314  center.z() = z - (cone_height * 0.5);
315  radius = cone_height - z;
316  }
317  else
318  {
319  // short cone. Bounding sphere touches base only.
320  center.z() = -(cone_height * 0.5);
321  radius = cone_radius;
322  }
323  }
324  else if (shape->type == MESH)
325  {
326  const Mesh* mesh = static_cast<const Mesh*>(shape);
327  if (mesh->vertex_count > 1)
328  {
329  double mx = std::numeric_limits<double>::max();
330  Eigen::Vector3d min(mx, mx, mx);
331  Eigen::Vector3d max(-mx, -mx, -mx);
332  unsigned int cnt = mesh->vertex_count * 3;
333  for (unsigned int i = 0; i < cnt; i += 3)
334  {
335  Eigen::Vector3d v(mesh->vertices[i + 0], mesh->vertices[i + 1], mesh->vertices[i + 2]);
336  min = min.cwiseMin(v);
337  max = max.cwiseMax(v);
338  }
339 
340  center = (min + max) * 0.5;
341  radius = (max - min).norm() * 0.5;
342  }
343  }
344 }
345 
346 bool constructMsgFromShape(const Shape* shape, ShapeMsg& shape_msg)
347 {
348  if (shape->type == SPHERE)
349  {
350  shape_msgs::SolidPrimitive s;
352  s.dimensions.resize(geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::SPHERE>());
353  s.dimensions[shape_msgs::SolidPrimitive::SPHERE_RADIUS] = static_cast<const Sphere*>(shape)->radius;
354  shape_msg = s;
355  }
356  else if (shape->type == BOX)
357  {
358  shape_msgs::SolidPrimitive s;
360  const double* sz = static_cast<const Box*>(shape)->size;
361  s.dimensions.resize(geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>());
362  s.dimensions[shape_msgs::SolidPrimitive::BOX_X] = sz[0];
363  s.dimensions[shape_msgs::SolidPrimitive::BOX_Y] = sz[1];
364  s.dimensions[shape_msgs::SolidPrimitive::BOX_Z] = sz[2];
365  shape_msg = s;
366  }
367  else if (shape->type == CYLINDER)
368  {
369  shape_msgs::SolidPrimitive s;
371  s.dimensions.resize(geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::CYLINDER>());
372  s.dimensions[shape_msgs::SolidPrimitive::CYLINDER_RADIUS] = static_cast<const Cylinder*>(shape)->radius;
373  s.dimensions[shape_msgs::SolidPrimitive::CYLINDER_HEIGHT] = static_cast<const Cylinder*>(shape)->length;
374  shape_msg = s;
375  }
376  else if (shape->type == CONE)
377  {
378  shape_msgs::SolidPrimitive s;
380  s.dimensions.resize(geometric_shapes::solidPrimitiveDimCount<shape_msgs::SolidPrimitive::CONE>());
381  s.dimensions[shape_msgs::SolidPrimitive::CONE_RADIUS] = static_cast<const Cone*>(shape)->radius;
382  s.dimensions[shape_msgs::SolidPrimitive::CONE_HEIGHT] = static_cast<const Cone*>(shape)->length;
383  shape_msg = s;
384  }
385  else if (shape->type == PLANE)
386  {
387  shape_msgs::Plane s;
388  const Plane* p = static_cast<const Plane*>(shape);
389  s.coef[0] = p->a;
390  s.coef[1] = p->b;
391  s.coef[2] = p->c;
392  s.coef[3] = p->d;
393  shape_msg = s;
394  }
395  else if (shape->type == MESH)
396  {
397  shape_msgs::Mesh s;
398  const Mesh* mesh = static_cast<const Mesh*>(shape);
399  s.vertices.resize(mesh->vertex_count);
400  s.triangles.resize(mesh->triangle_count);
401 
402  for (unsigned int i = 0; i < mesh->vertex_count; ++i)
403  {
404  unsigned int i3 = i * 3;
405  s.vertices[i].x = mesh->vertices[i3];
406  s.vertices[i].y = mesh->vertices[i3 + 1];
407  s.vertices[i].z = mesh->vertices[i3 + 2];
408  }
409 
410  for (unsigned int i = 0; i < s.triangles.size(); ++i)
411  {
412  unsigned int i3 = i * 3;
413  s.triangles[i].vertex_indices[0] = mesh->triangles[i3];
414  s.triangles[i].vertex_indices[1] = mesh->triangles[i3 + 1];
415  s.triangles[i].vertex_indices[2] = mesh->triangles[i3 + 2];
416  }
417  shape_msg = s;
418  }
419  else
420  {
421  CONSOLE_BRIDGE_logError("Unable to construct shape message for shape of type %d", (int)shape->type);
422  return false;
423  }
424 
425  return true;
426 }
427 
428 void saveAsText(const Shape* shape, std::ostream& out)
429 {
430  if (shape->type == SPHERE)
431  {
432  out << Sphere::STRING_NAME << std::endl;
433  out << static_cast<const Sphere*>(shape)->radius << std::endl;
434  }
435  else if (shape->type == BOX)
436  {
437  out << Box::STRING_NAME << std::endl;
438  const double* sz = static_cast<const Box*>(shape)->size;
439  out << sz[0] << " " << sz[1] << " " << sz[2] << std::endl;
440  }
441  else if (shape->type == CYLINDER)
442  {
443  out << Cylinder::STRING_NAME << std::endl;
444  out << static_cast<const Cylinder*>(shape)->radius << " " << static_cast<const Cylinder*>(shape)->length
445  << std::endl;
446  }
447  else if (shape->type == CONE)
448  {
449  out << Cone::STRING_NAME << std::endl;
450  out << static_cast<const Cone*>(shape)->radius << " " << static_cast<const Cone*>(shape)->length << std::endl;
451  }
452  else if (shape->type == PLANE)
453  {
454  out << Plane::STRING_NAME << std::endl;
455  const Plane* p = static_cast<const Plane*>(shape);
456  out << p->a << " " << p->b << " " << p->c << " " << p->d << std::endl;
457  }
458  else if (shape->type == MESH)
459  {
460  out << Mesh::STRING_NAME << std::endl;
461  const Mesh* mesh = static_cast<const Mesh*>(shape);
462  out << mesh->vertex_count << " " << mesh->triangle_count << std::endl;
463 
464  for (unsigned int i = 0; i < mesh->vertex_count; ++i)
465  {
466  unsigned int i3 = i * 3;
467  out << mesh->vertices[i3] << " " << mesh->vertices[i3 + 1] << " " << mesh->vertices[i3 + 2] << std::endl;
468  }
469 
470  for (unsigned int i = 0; i < mesh->triangle_count; ++i)
471  {
472  unsigned int i3 = i * 3;
473  out << mesh->triangles[i3] << " " << mesh->triangles[i3 + 1] << " " << mesh->triangles[i3 + 2] << std::endl;
474  }
475  }
476  else
477  {
478  CONSOLE_BRIDGE_logError("Unable to save shape of type %d", (int)shape->type);
479  }
480 }
481 
482 Shape* constructShapeFromText(std::istream& in)
483 {
484  Shape* result = nullptr;
485  if (in.good() && !in.eof())
486  {
487  std::string type;
488  in >> type;
489  if (in.good() && !in.eof())
490  {
491  if (type == Sphere::STRING_NAME)
492  {
493  double radius;
494  in >> radius;
495  result = new Sphere(radius);
496  }
497  else if (type == Box::STRING_NAME)
498  {
499  double x, y, z;
500  in >> x >> y >> z;
501  result = new Box(x, y, z);
502  }
503  else if (type == Cylinder::STRING_NAME)
504  {
505  double r, l;
506  in >> r >> l;
507  result = new Cylinder(r, l);
508  }
509  else if (type == Cone::STRING_NAME)
510  {
511  double r, l;
512  in >> r >> l;
513  result = new Cone(r, l);
514  }
515  else if (type == Plane::STRING_NAME)
516  {
517  double a, b, c, d;
518  in >> a >> b >> c >> d;
519  result = new Plane(a, b, c, d);
520  }
521  else if (type == Mesh::STRING_NAME)
522  {
523  unsigned int v, t;
524  in >> v >> t;
525  Mesh* m = new Mesh(v, t);
526  result = m;
527  for (unsigned int i = 0; i < m->vertex_count; ++i)
528  {
529  unsigned int i3 = i * 3;
530  in >> m->vertices[i3] >> m->vertices[i3 + 1] >> m->vertices[i3 + 2];
531  }
532  for (unsigned int i = 0; i < m->triangle_count; ++i)
533  {
534  unsigned int i3 = i * 3;
535  in >> m->triangles[i3] >> m->triangles[i3 + 1] >> m->triangles[i3 + 2];
536  }
537  m->computeTriangleNormals();
538  m->computeVertexNormals();
539  }
540  else
541  CONSOLE_BRIDGE_logError("Unknown shape type: '%s'", type.c_str());
542  }
543  }
544  return result;
545 }
546 
547 const std::string& shapeStringName(const Shape* shape)
548 {
549  static const std::string unknown = "unknown";
550  if (shape)
551  switch (shape->type)
552  {
553  case SPHERE:
554  return Sphere::STRING_NAME;
555  case CYLINDER:
556  return Cylinder::STRING_NAME;
557  case CONE:
558  return Cone::STRING_NAME;
559  case BOX:
560  return Box::STRING_NAME;
561  case PLANE:
562  return Plane::STRING_NAME;
563  case MESH:
564  return Mesh::STRING_NAME;
565  case OCTREE:
566  return OcTree::STRING_NAME;
567  default:
568  return unknown;
569  }
570  else
571  {
572  static const std::string empty;
573  return empty;
574  }
575 }
576 } // namespace shapes
geometric_shapes::constructMarkerFromShape
void constructMarkerFromShape(const shape_msgs::Mesh &shape_msg, visualization_msgs::Marker &marker, bool use_mesh_triangle_list=true)
Convert a shape_msgs::Mesh shape_msg to a visualization_msgs::Marker marker.
Definition: shape_to_marker.cpp:98
shapes::ShapeMsg
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
Type that can hold any of the desired shape message types.
Definition: shape_messages.h:84
shapes
Definition of various shapes. No properties such as position are included. These are simply the descr...
Definition: mesh_operations.h:47
shapes::computeShapeExtents
Eigen::Vector3d computeShapeExtents(const ShapeMsg &shape_msg)
Compute the extents of a shape.
Definition: shape_operations.cpp:257
shapes::Mesh::triangles
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
shapes::PLANE
@ PLANE
Definition: shapes.h:68
shape_to_marker.h
shape_extents.h
CONSOLE_BRIDGE_logError
#define CONSOLE_BRIDGE_logError(fmt,...)
shapes::Mesh::triangle_count
unsigned int triangle_count
The number of triangles formed with the vertices.
Definition: shapes.h:350
boost
shapes::SPHERE
@ SPHERE
Definition: shapes.h:64
shapes::Shape
A basic definition of a shape. Shapes are considered centered at origin.
Definition: shapes.h:77
shapes::Mesh
Definition of a triangle mesh By convention the "center" of the shape is at the origin....
Definition: shapes.h:281
shapes::Sphere::STRING_NAME
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:115
shapes::MESH
@ MESH
Definition: shapes.h:69
marker_
visualization_msgs::Marker * marker_
Definition: shape_operations.cpp:203
geometric_shapes::getShapeExtents
void getShapeExtents(const shape_msgs::SolidPrimitive &shape_msg, double &x_extent, double &y_extent, double &z_extent)
Get the dimensions of an axis-aligned bounding box for the shape described by shape_msg.
Definition: shape_extents.cpp:39
shapes::CONE
@ CONE
Definition: shapes.h:66
shapes::OcTree::STRING_NAME
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:392
shapes::Box
Definition of a box Aligned with the XYZ axes.
Definition: shapes.h:226
solid_primitive_dims.h
shapes::Sphere
Definition of a sphere.
Definition: shapes.h:106
shapes::Cylinder::STRING_NAME
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:139
shapes::Mesh::vertex_count
unsigned int vertex_count
The number of available vertices.
Definition: shapes.h:343
y
double y
Definition: mesh_operations.cpp:202
shapes::createMeshFromVertices
Mesh * createMeshFromVertices(const EigenSTL::vector_Vector3d &vertices, const std::vector< unsigned int > &triangles)
Load a mesh from a set of vertices.
Definition: mesh_operations.cpp:140
EigenSTL::vector_Vector3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
d
d
shapes::constructMarkerFromShape
bool constructMarkerFromShape(const Shape *shape, visualization_msgs::Marker &mk, bool use_mesh_triangle_list=false)
Construct the marker that corresponds to the shape. Return false on failure.
Definition: shape_operations.cpp:207
shapes::constructShapeFromMsg
Shape * constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
Construct the shape that corresponds to the message. Return NULL on failure.
Definition: shape_operations.cpp:116
shapes::Box::STRING_NAME
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:236
shapes::Mesh::vertices
double * vertices
The position for each vertex vertex k has values at index (3k, 3k+1, 3k+2) = (x,y,...
Definition: shapes.h:347
shapes::shapeStringName
const std::string & shapeStringName(const Shape *shape)
Get the string name of the shape.
Definition: shape_operations.cpp:579
r
S r
shapes::OCTREE
@ OCTREE
Definition: shapes.h:70
shapes::constructMsgFromShape
bool constructMsgFromShape(const Shape *shape, ShapeMsg &shape_msg)
Construct the message that corresponds to the shape. Return false on failure.
Definition: shape_operations.cpp:378
shapes::saveAsText
void saveAsText(const Shape *shape, std::ostream &out)
Save all the information about this shape as plain text.
Definition: shape_operations.cpp:460
use_mesh_triangle_list_
bool use_mesh_triangle_list_
Definition: shape_operations.cpp:202
shape_operations.h
shapes::Plane::STRING_NAME
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:373
shapes::CYLINDER
@ CYLINDER
Definition: shapes.h:65
x
double x
Definition: mesh_operations.cpp:202
shapes::computeShapeBoundingSphere
void computeShapeBoundingSphere(const Shape *shape, Eigen::Vector3d &center, double &radius)
Compute a sphere bounding a shape.
Definition: shape_operations.cpp:312
shapes::Cone
Definition of a cone Tip is on positive z axis. Center of base is on negative z axis....
Definition: shapes.h:178
shapes::Cone::STRING_NAME
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:188
shapes::Mesh::STRING_NAME
static const std::string STRING_NAME
The type of the shape, as a string.
Definition: shapes.h:292
z
double z
Definition: mesh_operations.cpp:202
shapes::BOX
@ BOX
Definition: shapes.h:67
shapes::constructShapeFromText
Shape * constructShapeFromText(std::istream &in)
Construct a shape from plain text description.
Definition: shape_operations.cpp:514


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Sun Oct 1 2023 02:40:16