45 #include <console_bridge/console.h>
47 #include <Eigen/Geometry>
57 return new Plane(shape_msg.coef[0], shape_msg.coef[1], shape_msg.coef[2], shape_msg.coef[3]);
62 if (shape_msg.triangles.empty() || shape_msg.vertices.empty())
64 CONSOLE_BRIDGE_logWarn(
"Mesh definition is empty");
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)
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];
86 Shape* shape =
nullptr;
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]);
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]);
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]);
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]);
111 if (shape ==
nullptr)
112 CONSOLE_BRIDGE_logError(
"Unable to construct shape corresponding to shape_msg of type %d", (
int)shape_msg.type);
119 class ShapeVisitorAlloc :
public boost::static_visitor<Shape*>
122 Shape* operator()(
const shape_msgs::Plane& shape_msg)
const
127 Shape* operator()(
const shape_msgs::Mesh& shape_msg)
const
132 Shape* operator()(
const shape_msgs::SolidPrimitive& shape_msg)
const
141 return boost::apply_visitor(ShapeVisitorAlloc(), shape_msg);
146 class ShapeVisitorMarker :
public boost::static_visitor<void>
149 ShapeVisitorMarker(visualization_msgs::Marker* marker,
bool use_mesh_triangle_list)
154 void operator()(
const shape_msgs::Plane& )
const
156 throw std::runtime_error(
"No visual markers can be constructed for planes");
159 void operator()(
const shape_msgs::Mesh& shape_msg)
const
164 void operator()(
const shape_msgs::SolidPrimitive& shape_msg)
const
183 boost::apply_visitor(ShapeVisitorMarker(&marker, use_mesh_triangle_list), shape_msg);
186 catch (std::runtime_error& ex)
198 class ShapeVisitorComputeExtents :
public boost::static_visitor<Eigen::Vector3d>
201 Eigen::Vector3d operator()(
const shape_msgs::Plane& )
const
203 Eigen::Vector3d e(0.0, 0.0, 0.0);
207 Eigen::Vector3d operator()(
const shape_msgs::Mesh& shape_msg)
const
209 double x_extent, y_extent, z_extent;
211 Eigen::Vector3d e(x_extent, y_extent, z_extent);
215 Eigen::Vector3d operator()(
const shape_msgs::SolidPrimitive& shape_msg)
const
217 double x_extent, y_extent, z_extent;
219 Eigen::Vector3d e(x_extent, y_extent, z_extent);
227 return boost::apply_visitor(ShapeVisitorComputeExtents(), shape_msg);
232 if (shape->type ==
SPHERE)
234 double d =
static_cast<const Sphere*
>(shape)->radius * 2.0;
235 return Eigen::Vector3d(d, d, d);
237 else if (shape->type ==
BOX)
239 const double* sz =
static_cast<const Box*
>(shape)->size;
240 return Eigen::Vector3d(sz[0], sz[1], sz[2]);
244 double d =
static_cast<const Cylinder*
>(shape)->radius * 2.0;
245 return Eigen::Vector3d(d, d,
static_cast<const Cylinder*
>(shape)->length);
247 else if (shape->type ==
CONE)
249 double d =
static_cast<const Cone*
>(shape)->radius * 2.0;
250 return Eigen::Vector3d(d, d,
static_cast<const Cone*
>(shape)->length);
252 else if (shape->type ==
MESH)
254 const Mesh* mesh =
static_cast<const Mesh*
>(shape);
255 if (mesh->vertex_count > 1)
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)
261 unsigned int i3 = i * 3;
262 for (
unsigned int k = 0; k < 3; ++k)
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];
271 return Eigen::Vector3d(vmax[0] - vmin[0], vmax[1] - vmin[1], vmax[2] - vmin[2]);
274 return Eigen::Vector3d(0.0, 0.0, 0.0);
277 return Eigen::Vector3d(0.0, 0.0, 0.0);
287 if (shape->type ==
SPHERE)
289 radius =
static_cast<const Sphere*
>(shape)->radius;
291 else if (shape->type ==
BOX)
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);
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);
305 else if (shape->type ==
CONE)
307 double cone_radius =
static_cast<const Cone*
>(shape)->radius;
308 double cone_height =
static_cast<const Cone*
>(shape)->length;
310 if (cone_height > cone_radius)
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;
320 center.z() = -(cone_height * 0.5);
321 radius = cone_radius;
324 else if (shape->type ==
MESH)
326 const Mesh* mesh =
static_cast<const Mesh*
>(shape);
327 if (mesh->vertex_count > 1)
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)
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);
340 center = (min + max) * 0.5;
341 radius = (max - min).norm() * 0.5;
348 if (shape->type ==
SPHERE)
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;
356 else if (shape->type ==
BOX)
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];
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;
376 else if (shape->type ==
CONE)
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;
385 else if (shape->type ==
PLANE)
388 const Plane* p =
static_cast<const Plane*
>(shape);
395 else if (shape->type ==
MESH)
398 const Mesh* mesh =
static_cast<const Mesh*
>(shape);
399 s.vertices.resize(mesh->vertex_count);
400 s.triangles.resize(mesh->triangle_count);
402 for (
unsigned int i = 0; i < mesh->vertex_count; ++i)
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];
410 for (
unsigned int i = 0; i < s.triangles.size(); ++i)
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];
428 void saveAsText(
const Shape* shape, std::ostream& out)
430 if (shape->type ==
SPHERE)
433 out << static_cast<const Sphere*>(shape)->radius << std::endl;
435 else if (shape->type ==
BOX)
438 const double* sz =
static_cast<const Box*
>(shape)->size;
439 out << sz[0] <<
" " << sz[1] <<
" " << sz[2] << std::endl;
444 out << static_cast<const Cylinder*>(shape)->radius <<
" " <<
static_cast<const Cylinder*
>(shape)->length
447 else if (shape->type ==
CONE)
450 out << static_cast<const Cone*>(shape)->radius <<
" " <<
static_cast<const Cone*
>(shape)->length << std::endl;
452 else if (shape->type ==
PLANE)
455 const Plane* p =
static_cast<const Plane*
>(shape);
456 out << p->a <<
" " << p->b <<
" " << p->c <<
" " << p->d << std::endl;
458 else if (shape->type ==
MESH)
461 const Mesh* mesh =
static_cast<const Mesh*
>(shape);
466 unsigned int i3 = i * 3;
472 unsigned int i3 = i * 3;
484 Shape* result =
nullptr;
485 if (in.good() && !in.eof())
489 if (in.good() && !in.eof())
495 result =
new Sphere(radius);
501 result =
new Box(
x,
y,
z);
507 result =
new Cylinder(r, l);
513 result =
new Cone(r, l);
518 in >> a >> b >> c >>
d;
519 result =
new Plane(a, b, c,
d);
525 Mesh* m =
new Mesh(v, t);
527 for (
unsigned int i = 0; i < m->vertex_count; ++i)
529 unsigned int i3 = i * 3;
530 in >> m->vertices[i3] >> m->vertices[i3 + 1] >> m->vertices[i3 + 2];
532 for (
unsigned int i = 0; i < m->triangle_count; ++i)
534 unsigned int i3 = i * 3;
535 in >> m->triangles[i3] >> m->triangles[i3 + 1] >> m->triangles[i3 + 2];
537 m->computeTriangleNormals();
538 m->computeVertexNormals();
549 static const std::string unknown =
"unknown";
572 static const std::string empty;