mesh_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 
39 
40 #include <cstdio>
41 #include <cmath>
42 #include <algorithm>
43 #include <set>
44 #include <float.h>
45 
46 #include <console_bridge/console.h>
48 
49 #include <assimp/scene.h>
50 #include <assimp/Importer.hpp>
51 #include <assimp/postprocess.h>
52 
53 #include <Eigen/Geometry>
54 
55 #include <boost/math/constants/constants.hpp>
56 
57 namespace shapes
58 {
59 namespace detail
60 {
61 namespace
62 {
64 struct LocalVertexType
65 {
66  LocalVertexType() : x(0.0), y(0.0), z(0.0)
67  {
68  }
69 
70  LocalVertexType(const Eigen::Vector3d& v) : x(v.x()), y(v.y()), z(v.z())
71  {
72  }
73 
74  double x, y, z;
75  unsigned int index;
76 };
77 
79 struct ltLocalVertexValue
80 {
81  bool operator()(const LocalVertexType& p1, const LocalVertexType& p2) const
82  {
83  if (p1.x < p2.x)
84  return true;
85  if (p1.x > p2.x)
86  return false;
87  if (p1.y < p2.y)
88  return true;
89  if (p1.y > p2.y)
90  return false;
91  if (p1.z < p2.z)
92  return true;
93  return false;
94  }
95 };
96 
98 struct ltLocalVertexIndex
99 {
100  bool operator()(const LocalVertexType& p1, const LocalVertexType& p2) const
101  {
102  return p1.index < p2.index;
103  }
104 };
105 } // namespace
106 } // namespace detail
107 
108 Mesh* createMeshFromVertices(const EigenSTL::vector_Vector3d& vertices, const std::vector<unsigned int>& triangles)
109 {
110  unsigned int nt = triangles.size() / 3;
111  Mesh* mesh = new Mesh(vertices.size(), nt);
112  for (unsigned int i = 0; i < vertices.size(); ++i)
113  {
114  mesh->vertices[3 * i] = vertices[i].x();
115  mesh->vertices[3 * i + 1] = vertices[i].y();
116  mesh->vertices[3 * i + 2] = vertices[i].z();
117  }
118 
119  std::copy(triangles.begin(), triangles.end(), mesh->triangles);
120  mesh->computeTriangleNormals();
121  mesh->computeVertexNormals();
122 
123  return mesh;
124 }
125 
127 {
128  if (source.size() < 3)
129  return nullptr;
130 
131  if (source.size() % 3 != 0)
132  CONSOLE_BRIDGE_logError("The number of vertices to construct a mesh from is not divisible by 3. Probably "
133  "constructed triangles will not make sense.");
134 
135  std::set<detail::LocalVertexType, detail::ltLocalVertexValue> vertices;
136  std::vector<unsigned int> triangles;
137 
138  unsigned int n = source.size() / 3;
139  for (unsigned int i = 0; i < n; ++i)
140  {
141  // check if we have new vertices
142  unsigned int i3 = i * 3;
143  detail::LocalVertexType vt1(source[i3]);
144  std::set<detail::LocalVertexType, detail::ltLocalVertexValue>::iterator p1 = vertices.find(vt1);
145  if (p1 == vertices.end())
146  {
147  vt1.index = vertices.size();
148  vertices.insert(vt1);
149  }
150  else
151  vt1.index = p1->index;
152  triangles.push_back(vt1.index);
153 
154  detail::LocalVertexType vt2(source[++i3]);
155  std::set<detail::LocalVertexType, detail::ltLocalVertexValue>::iterator p2 = vertices.find(vt2);
156  if (p2 == vertices.end())
157  {
158  vt2.index = vertices.size();
159  vertices.insert(vt2);
160  }
161  else
162  vt2.index = p2->index;
163  triangles.push_back(vt2.index);
164 
165  detail::LocalVertexType vt3(source[++i3]);
166  std::set<detail::LocalVertexType, detail::ltLocalVertexValue>::iterator p3 = vertices.find(vt3);
167  if (p3 == vertices.end())
168  {
169  vt3.index = vertices.size();
170  vertices.insert(vt3);
171  }
172  else
173  vt3.index = p3->index;
174 
175  triangles.push_back(vt3.index);
176  }
177 
178  // sort our vertices
179  std::vector<detail::LocalVertexType> vt;
180  vt.insert(vt.end(), vertices.begin(), vertices.end());
181  std::sort(vt.begin(), vt.end(), detail::ltLocalVertexIndex());
182 
183  // copy the data to a mesh structure
184  unsigned int nt = triangles.size() / 3;
185 
186  Mesh* mesh = new Mesh(vt.size(), nt);
187  for (unsigned int i = 0; i < vt.size(); ++i)
188  {
189  unsigned int i3 = i * 3;
190  mesh->vertices[i3] = vt[i].x;
191  mesh->vertices[i3 + 1] = vt[i].y;
192  mesh->vertices[i3 + 2] = vt[i].z;
193  }
194 
195  std::copy(triangles.begin(), triangles.end(), mesh->triangles);
196  mesh->computeTriangleNormals();
197  mesh->computeVertexNormals();
198 
199  return mesh;
200 }
201 
202 Mesh* createMeshFromResource(const std::string& resource)
203 {
204  static const Eigen::Vector3d one(1.0, 1.0, 1.0);
205  return createMeshFromResource(resource, one);
206 }
207 
208 Mesh* createMeshFromBinary(const char* buffer, std::size_t size, const std::string& assimp_hint)
209 {
210  static const Eigen::Vector3d one(1.0, 1.0, 1.0);
211  return createMeshFromBinary(buffer, size, one, assimp_hint);
212 }
213 
214 Mesh* createMeshFromBinary(const char* buffer, std::size_t size, const Eigen::Vector3d& scale,
215  const std::string& assimp_hint)
216 {
217  if (!buffer || size < 1)
218  {
219  CONSOLE_BRIDGE_logWarn("Cannot construct mesh from empty binary buffer");
220  return nullptr;
221  }
222 
223  // try to get a file extension
224  std::string hint;
225  std::size_t pos = assimp_hint.find_last_of('.');
226  if (pos != std::string::npos)
227  {
228  hint = assimp_hint.substr(pos + 1);
229  std::transform(hint.begin(), hint.end(), hint.begin(), ::tolower);
230  }
231  if (hint.empty())
232  hint = assimp_hint; // send entire file name as hint if no extension was found
233 
234  // Create an instance of the Importer class
235  Assimp::Importer importer;
236 
237  // Issue #38 fix: as part of the post-processing, we remove all other components in file but
238  // the meshes, as anyway the resulting shapes:Mesh object just receives vertices and triangles.
239  importer.SetPropertyInteger(AI_CONFIG_PP_RVC_FLAGS, aiComponent_NORMALS | aiComponent_TANGENTS_AND_BITANGENTS |
240  aiComponent_COLORS | aiComponent_TEXCOORDS |
241  aiComponent_BONEWEIGHTS | aiComponent_ANIMATIONS |
242  aiComponent_TEXTURES | aiComponent_LIGHTS |
243  aiComponent_CAMERAS | aiComponent_MATERIALS);
244 
245  // And have it read the given file with some post-processing
246  const aiScene* scene = importer.ReadFileFromMemory(reinterpret_cast<const void*>(buffer), size,
247  aiProcess_Triangulate | aiProcess_JoinIdenticalVertices |
248  aiProcess_SortByPType | aiProcess_RemoveComponent,
249  hint.c_str());
250  if (!scene)
251  return nullptr;
252 
253  // Assimp enforces Y_UP convention by rotating models with different conventions.
254  // However, that behaviour is confusing and doesn't match the ROS convention
255  // where the Z axis is pointing up.
256  // Hopefully this doesn't undo legit use of the root node transformation...
257  // Note that this is also what RViz does internally.
258  scene->mRootNode->mTransformation = aiMatrix4x4();
259 
260  // These post processing steps flatten the root node transformation into child nodes,
261  // so they must be delayed until after clearing the root node transform above.
262  importer.ApplyPostProcessing(aiProcess_OptimizeMeshes | aiProcess_OptimizeGraph);
263 
264  return createMeshFromAsset(scene, scale, hint);
265 }
266 
267 Mesh* createMeshFromResource(const std::string& resource, const Eigen::Vector3d& scale)
268 {
271  try
272  {
273  res = retriever.get(resource);
274  }
276  {
277  CONSOLE_BRIDGE_logError("%s", e.what());
278  return nullptr;
279  }
280 
281  if (res.size == 0)
282  {
283  CONSOLE_BRIDGE_logWarn("Retrieved empty mesh for resource '%s'", resource.c_str());
284  return nullptr;
285  }
286 
287  Mesh* m = createMeshFromBinary(reinterpret_cast<const char*>(res.data.get()), res.size, scale, resource);
288  if (!m)
289  {
290  CONSOLE_BRIDGE_logWarn("Assimp reports no scene in %s.", resource.c_str());
291  CONSOLE_BRIDGE_logWarn("This could be because of a resource filename that is too long for the Assimp library, a "
292  "known bug. As a workaround shorten the filename/path.");
293  }
294  return m;
295 }
296 
297 namespace
298 {
299 void extractMeshData(const aiScene* scene, const aiNode* node, const aiMatrix4x4& parent_transform,
300  const Eigen::Vector3d& scale, EigenSTL::vector_Vector3d& vertices,
301  std::vector<unsigned int>& triangles)
302 {
303  aiMatrix4x4 transform = parent_transform;
304  transform *= node->mTransformation;
305  for (unsigned int j = 0; j < node->mNumMeshes; ++j)
306  {
307  const aiMesh* a = scene->mMeshes[node->mMeshes[j]];
308  unsigned int offset = vertices.size();
309  for (unsigned int i = 0; i < a->mNumVertices; ++i)
310  {
311  aiVector3D v = transform * a->mVertices[i];
312  vertices.push_back(Eigen::Vector3d(v.x * scale.x(), v.y * scale.y(), v.z * scale.z()));
313  }
314  for (unsigned int i = 0; i < a->mNumFaces; ++i)
315  if (a->mFaces[i].mNumIndices == 3)
316  {
317  triangles.push_back(offset + a->mFaces[i].mIndices[0]);
318  triangles.push_back(offset + a->mFaces[i].mIndices[1]);
319  triangles.push_back(offset + a->mFaces[i].mIndices[2]);
320  }
321  }
322 
323  for (unsigned int n = 0; n < node->mNumChildren; ++n)
324  extractMeshData(scene, node->mChildren[n], transform, scale, vertices, triangles);
325 }
326 } // namespace
327 
328 Mesh* createMeshFromAsset(const aiScene* scene, const std::string& resource_name)
329 {
330  static const Eigen::Vector3d one(1.0, 1.0, 1.0);
331  return createMeshFromAsset(scene, one, resource_name);
332 }
333 
334 Mesh* createMeshFromAsset(const aiScene* scene, const Eigen::Vector3d& scale, const std::string& resource_name)
335 {
336  if (!scene->HasMeshes())
337  {
338  CONSOLE_BRIDGE_logWarn("Assimp reports scene in %s has no meshes", resource_name.c_str());
339  return nullptr;
340  }
341  EigenSTL::vector_Vector3d vertices;
342  std::vector<unsigned int> triangles;
343  extractMeshData(scene, scene->mRootNode, aiMatrix4x4(), scale, vertices, triangles);
344  if (vertices.empty())
345  {
346  CONSOLE_BRIDGE_logWarn("There are no vertices in the scene %s", resource_name.c_str());
347  return nullptr;
348  }
349  if (triangles.empty())
350  {
351  CONSOLE_BRIDGE_logWarn("There are no triangles in the scene %s", resource_name.c_str());
352  return nullptr;
353  }
354 
355  return createMeshFromVertices(vertices, triangles);
356 }
357 
358 Mesh* createMeshFromShape(const Shape* shape)
359 {
360  if (shape->type == shapes::SPHERE)
361  return shapes::createMeshFromShape(static_cast<const shapes::Sphere&>(*shape));
362  else if (shape->type == shapes::BOX)
363  return shapes::createMeshFromShape(static_cast<const shapes::Box&>(*shape));
364  else if (shape->type == shapes::CYLINDER)
365  return shapes::createMeshFromShape(static_cast<const shapes::Cylinder&>(*shape));
366  else if (shape->type == shapes::CONE)
367  return shapes::createMeshFromShape(static_cast<const shapes::Cone&>(*shape));
368  else
369  CONSOLE_BRIDGE_logError("Conversion of shape of type '%s' to a mesh is not known", shapeStringName(shape).c_str());
370  return nullptr;
371 }
372 
373 Mesh* createMeshFromShape(const Box& box)
374 {
375  double x = box.size[0] / 2.0;
376  double y = box.size[1] / 2.0;
377  double z = box.size[2] / 2.0;
378 
379  // define vertices of box mesh
380  Mesh* result = new Mesh(8, 12);
381  result->vertices[0] = -x;
382  result->vertices[1] = -y;
383  result->vertices[2] = -z;
384 
385  result->vertices[3] = x;
386  result->vertices[4] = -y;
387  result->vertices[5] = -z;
388 
389  result->vertices[6] = x;
390  result->vertices[7] = -y;
391  result->vertices[8] = z;
392 
393  result->vertices[9] = -x;
394  result->vertices[10] = -y;
395  result->vertices[11] = z;
396 
397  result->vertices[12] = -x;
398  result->vertices[13] = y;
399  result->vertices[14] = z;
400 
401  result->vertices[15] = -x;
402  result->vertices[16] = y;
403  result->vertices[17] = -z;
404 
405  result->vertices[18] = x;
406  result->vertices[19] = y;
407  result->vertices[20] = z;
408 
409  result->vertices[21] = x;
410  result->vertices[22] = y;
411  result->vertices[23] = -z;
412 
413  static const unsigned int tri[] = { 0, 1, 2, 2, 3, 0, 4, 3, 2, 2, 6, 4, 7, 6, 2, 2, 1, 7,
414  3, 4, 5, 5, 0, 3, 0, 5, 7, 7, 1, 0, 7, 5, 4, 4, 6, 7 };
415  memcpy(result->triangles, tri, sizeof(unsigned int) * 36);
416  result->computeTriangleNormals();
417  result->computeVertexNormals();
418  return result;
419 }
420 
421 Mesh* createMeshFromShape(const Sphere& sphere)
422 {
423  // this code is adapted from FCL
424  EigenSTL::vector_Vector3d vertices;
425  std::vector<unsigned int> triangles;
426 
427  const double r = sphere.radius;
428  const double pi = boost::math::constants::pi<double>();
429  const unsigned int seg = std::max<unsigned int>(6, 0.5 + 2.0 * pi * r / 0.01); // split the sphere longitudinally up
430  // to a resolution of 1 cm at the
431  // ecuator, or a minimum of 6 segments
432  const unsigned int ring = std::max<unsigned int>(6, 2.0 * r / 0.01); // split the sphere into rings along latitude,
433  // up to a height of at most 1 cm, or a minimum
434  // of 6 rings
435 
436  double phi, phid;
437  phid = pi * 2.0 / seg;
438  phi = 0.0;
439 
440  double theta, thetad;
441  thetad = pi / (ring + 1);
442  theta = 0;
443 
444  for (unsigned int i = 0; i < ring; ++i)
445  {
446  double theta_ = theta + thetad * (i + 1);
447  for (unsigned int j = 0; j < seg; ++j)
448  vertices.push_back(Eigen::Vector3d(r * sin(theta_) * cos(phi + j * phid), r * sin(theta_) * sin(phi + j * phid),
449  r * cos(theta_)));
450  }
451  vertices.push_back(Eigen::Vector3d(0.0, 0.0, r));
452  vertices.push_back(Eigen::Vector3d(0.0, 0.0, -r));
453 
454  for (unsigned int i = 0; i < ring - 1; ++i)
455  {
456  for (unsigned int j = 0; j < seg; ++j)
457  {
458  unsigned int a, b, c, d;
459  a = i * seg + j;
460  b = (j == seg - 1) ? (i * seg) : (i * seg + j + 1);
461  c = (i + 1) * seg + j;
462  d = (j == seg - 1) ? ((i + 1) * seg) : ((i + 1) * seg + j + 1);
463  triangles.push_back(a);
464  triangles.push_back(c);
465  triangles.push_back(b);
466  triangles.push_back(b);
467  triangles.push_back(c);
468  triangles.push_back(d);
469  }
470  }
471 
472  for (unsigned int j = 0; j < seg; ++j)
473  {
474  unsigned int a, b;
475  a = j;
476  b = (j == seg - 1) ? 0 : (j + 1);
477  triangles.push_back(ring * seg);
478  triangles.push_back(a);
479  triangles.push_back(b);
480 
481  a = (ring - 1) * seg + j;
482  b = (j == seg - 1) ? (ring - 1) * seg : ((ring - 1) * seg + j + 1);
483  triangles.push_back(a);
484  triangles.push_back(ring * seg + 1);
485  triangles.push_back(b);
486  }
487  return createMeshFromVertices(vertices, triangles);
488 }
489 
490 Mesh* createMeshFromShape(const Cylinder& cylinder)
491 {
492  // this code is adapted from FCL
493  EigenSTL::vector_Vector3d vertices;
494  std::vector<unsigned int> triangles;
495 
496  // magic number defining how many triangles to construct for the unit cylinder; perhaps this should be a param
497  static unsigned int tot_for_unit_cylinder = 100;
498 
499  double r = cylinder.radius;
500  double h = cylinder.length;
501 
502  const double pi = boost::math::constants::pi<double>();
503  unsigned int tot = std::max<unsigned int>(6, ceil(tot_for_unit_cylinder * r));
504  double phid = pi * 2 / tot;
505 
506  double circle_edge = phid * r;
507  unsigned int h_num = ceil(std::abs(h) / circle_edge);
508 
509  double phi = 0;
510  double hd = h / h_num;
511 
512  for (unsigned int i = 0; i < tot; ++i)
513  vertices.push_back(Eigen::Vector3d(r * cos(phi + phid * i), r * sin(phi + phid * i), h / 2));
514 
515  for (unsigned int i = 0; i < h_num - 1; ++i)
516  for (unsigned int j = 0; j < tot; ++j)
517  vertices.push_back(Eigen::Vector3d(r * cos(phi + phid * j), r * sin(phi + phid * j), h / 2 - (i + 1) * hd));
518 
519  for (unsigned int i = 0; i < tot; ++i)
520  vertices.push_back(Eigen::Vector3d(r * cos(phi + phid * i), r * sin(phi + phid * i), -h / 2));
521 
522  vertices.push_back(Eigen::Vector3d(0, 0, h / 2));
523  vertices.push_back(Eigen::Vector3d(0, 0, -h / 2));
524 
525  for (unsigned int i = 0; i < tot; ++i)
526  {
527  triangles.push_back((h_num + 1) * tot);
528  triangles.push_back(i);
529  triangles.push_back((i == tot - 1) ? 0 : (i + 1));
530  }
531 
532  for (unsigned int i = 0; i < tot; ++i)
533  {
534  triangles.push_back((h_num + 1) * tot + 1);
535  triangles.push_back(h_num * tot + ((i == tot - 1) ? 0 : (i + 1)));
536  triangles.push_back(h_num * tot + i);
537  }
538 
539  for (unsigned int i = 0; i < h_num; ++i)
540  {
541  for (unsigned int j = 0; j < tot; ++j)
542  {
543  int a, b, c, d;
544  a = j;
545  b = (j == tot - 1) ? 0 : (j + 1);
546  c = j + tot;
547  d = (j == tot - 1) ? tot : (j + 1 + tot);
548 
549  int start = i * tot;
550  triangles.push_back(start + b);
551  triangles.push_back(start + a);
552  triangles.push_back(start + c);
553  triangles.push_back(start + b);
554  triangles.push_back(start + c);
555  triangles.push_back(start + d);
556  }
557  }
558  return createMeshFromVertices(vertices, triangles);
559 }
560 
561 Mesh* createMeshFromShape(const Cone& cone)
562 {
563  // this code is adapted from FCL
564  EigenSTL::vector_Vector3d vertices;
565  std::vector<unsigned int> triangles;
566 
567  // magic number defining how many triangles to construct for the unit cylinder; perhaps this should be a param
568  static unsigned int tot_for_unit_cone = 100;
569 
570  double r = cone.radius;
571  double h = cone.length;
572 
573  const double pi = boost::math::constants::pi<double>();
574  unsigned int tot = tot_for_unit_cone * r;
575  double phid = pi * 2 / tot;
576 
577  double circle_edge = phid * r;
578  unsigned int h_num = ceil(h / circle_edge);
579 
580  double phi = 0;
581  double hd = h / h_num;
582 
583  for (unsigned int i = 0; i < h_num - 1; ++i)
584  {
585  double h_i = h / 2 - (i + 1) * hd;
586  double rh = r * (0.5 - h_i / h);
587  for (unsigned int j = 0; j < tot; ++j)
588  vertices.push_back(Eigen::Vector3d(rh * cos(phi + phid * j), rh * sin(phi + phid * j), h_i));
589  }
590 
591  for (unsigned int i = 0; i < tot; ++i)
592  vertices.push_back(Eigen::Vector3d(r * cos(phi + phid * i), r * sin(phi + phid * i), -h / 2));
593 
594  vertices.push_back(Eigen::Vector3d(0, 0, h / 2));
595  vertices.push_back(Eigen::Vector3d(0, 0, -h / 2));
596 
597  for (unsigned int i = 0; i < tot; ++i)
598  {
599  triangles.push_back(h_num * tot);
600  triangles.push_back(i);
601  triangles.push_back((i == tot - 1) ? 0 : (i + 1));
602  }
603 
604  for (unsigned int i = 0; i < tot; ++i)
605  {
606  triangles.push_back(h_num * tot + 1);
607  triangles.push_back((h_num - 1) * tot + ((i == tot - 1) ? 0 : (i + 1)));
608  triangles.push_back((h_num - 1) * tot + i);
609  }
610 
611  for (unsigned int i = 0; i < h_num - 1; ++i)
612  for (unsigned int j = 0; j < tot; ++j)
613  {
614  int a, b, c, d;
615  a = j;
616  b = (j == tot - 1) ? 0 : (j + 1);
617  c = j + tot;
618  d = (j == tot - 1) ? tot : (j + 1 + tot);
619 
620  int start = i * tot;
621  triangles.push_back(start + b);
622  triangles.push_back(start + a);
623  triangles.push_back(start + c);
624  triangles.push_back(start + b);
625  triangles.push_back(start + c);
626  triangles.push_back(start + d);
627  }
628  return createMeshFromVertices(vertices, triangles);
629 }
630 
631 namespace
632 {
633 inline void writeFloatToSTL(char*& ptr, const float data)
634 {
635  memcpy(ptr, &data, sizeof(float));
636  ptr += sizeof(float);
637 }
638 } // namespace
639 
640 void writeSTLBinary(const Mesh* mesh, std::vector<char>& buffer)
641 {
642  buffer.resize(84 + mesh->triangle_count * 50);
643  memset(&buffer[0], 0, 80);
644  char* ptr = &buffer[80];
645  uint32_t nt = mesh->triangle_count;
646  memcpy(ptr, &nt, sizeof(uint32_t));
647  ptr += sizeof(uint32_t);
648  for (unsigned int i = 0; i < mesh->triangle_count; ++i)
649  {
650  unsigned int i3 = i * 3;
651 
652  if (mesh->triangle_normals)
653  {
654  writeFloatToSTL(ptr, mesh->triangle_normals[i3]);
655  writeFloatToSTL(ptr, mesh->triangle_normals[i3 + 1]);
656  writeFloatToSTL(ptr, mesh->triangle_normals[i3 + 2]);
657  }
658  else
659  {
660  memset(ptr, 0, sizeof(float) * 3);
661  ptr += sizeof(float) * 3;
662  }
663 
664  unsigned int index = mesh->triangles[i3] * 3;
665  writeFloatToSTL(ptr, mesh->vertices[index]);
666  writeFloatToSTL(ptr, mesh->vertices[index + 1]);
667  writeFloatToSTL(ptr, mesh->vertices[index + 2]);
668  index = mesh->triangles[i3 + 1] * 3;
669  writeFloatToSTL(ptr, mesh->vertices[index]);
670  writeFloatToSTL(ptr, mesh->vertices[index + 1]);
671  writeFloatToSTL(ptr, mesh->vertices[index + 2]);
672  index = mesh->triangles[i3 + 2] * 3;
673  writeFloatToSTL(ptr, mesh->vertices[index]);
674  writeFloatToSTL(ptr, mesh->vertices[index + 1]);
675  writeFloatToSTL(ptr, mesh->vertices[index + 2]);
676  memset(ptr, 0, 2);
677  ptr += 2;
678  }
679 }
680 } // namespace shapes
resource_retriever::MemoryResource::size
uint32_t size
shapes
Definition of various shapes. No properties such as position are included. These are simply the descr...
Definition: mesh_operations.h:47
mesh_operations.h
resource_retriever::MemoryResource
CONSOLE_BRIDGE_logError
#define CONSOLE_BRIDGE_logError(fmt,...)
shapes::Cylinder
Definition of a cylinder Length is along z axis. Origin is at center of mass.
Definition: shapes.h:127
shapes::SPHERE
@ SPHERE
Definition: shapes.h:64
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
resource_retriever::MemoryResource::data
boost::shared_array< uint8_t > data
shapes::CONE
@ CONE
Definition: shapes.h:66
shapes::Box
Definition of a box Aligned with the XYZ axes.
Definition: shapes.h:226
shapes::Sphere
Definition of a sphere.
Definition: shapes.h:106
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
resource_retriever::Retriever::get
MemoryResource get(const std::string &url)
d
d
shapes::createMeshFromResource
Mesh * createMeshFromResource(const std::string &resource)
Load a mesh from a resource that contains a mesh that can be loaded by assimp.
Definition: mesh_operations.cpp:234
resource_retriever::Retriever
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::writeSTLBinary
void writeSTLBinary(const Mesh *mesh, std::vector< char > &buffer)
Write the mesh to a buffer in STL format.
Definition: mesh_operations.cpp:672
shapes::createMeshFromBinary
Mesh * createMeshFromBinary(const char *buffer, std::size_t size, const std::string &assimp_hint=std::string())
Load a mesh from a binary stream that contains a mesh that can be loaded by assimp.
Definition: mesh_operations.cpp:240
shape_operations.h
retriever.h
shapes::CYLINDER
@ CYLINDER
Definition: shapes.h:65
index
unsigned int index
Definition: mesh_operations.cpp:203
x
double x
Definition: mesh_operations.cpp:202
resource_retriever::Exception
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::createMeshFromAsset
Mesh * createMeshFromAsset(const aiScene *scene, const Eigen::Vector3d &scale, const std::string &assimp_hint=std::string())
Load a mesh from an assimp datastructure.
Definition: mesh_operations.cpp:366
z
double z
Definition: mesh_operations.cpp:202
shapes::BOX
@ BOX
Definition: shapes.h:67
shapes::createMeshFromShape
Mesh * createMeshFromShape(const Shape *shape)
Construct a mesh from a primitive shape that is NOT already a mesh. This call allocates a new object.
Definition: mesh_operations.cpp:390


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