46 #include <console_bridge/console.h>
49 #include <assimp/scene.h>
50 #include <assimp/Importer.hpp>
51 #include <assimp/postprocess.h>
53 #include <Eigen/Geometry>
55 #include <boost/math/constants/constants.hpp>
64 struct LocalVertexType
66 LocalVertexType() :
x(0.0),
y(0.0),
z(0.0)
70 LocalVertexType(
const Eigen::Vector3d& v) :
x(v.
x()),
y(v.
y()),
z(v.
z())
79 struct ltLocalVertexValue
81 bool operator()(
const LocalVertexType& p1,
const LocalVertexType& p2)
const
98 struct ltLocalVertexIndex
100 bool operator()(
const LocalVertexType& p1,
const LocalVertexType& p2)
const
102 return p1.index < p2.index;
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)
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();
119 std::copy(triangles.begin(), triangles.end(), mesh->triangles);
120 mesh->computeTriangleNormals();
121 mesh->computeVertexNormals();
128 if (source.size() < 3)
131 if (source.size() % 3 != 0)
133 "constructed triangles will not make sense.");
135 std::set<detail::LocalVertexType, detail::ltLocalVertexValue> vertices;
136 std::vector<unsigned int> triangles;
138 unsigned int n = source.size() / 3;
139 for (
unsigned int i = 0; i < n; ++i)
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())
147 vt1.index = vertices.size();
148 vertices.insert(vt1);
151 vt1.index = p1->index;
152 triangles.push_back(vt1.index);
154 detail::LocalVertexType vt2(source[++i3]);
155 std::set<detail::LocalVertexType, detail::ltLocalVertexValue>::iterator p2 = vertices.find(vt2);
156 if (p2 == vertices.end())
158 vt2.index = vertices.size();
159 vertices.insert(vt2);
162 vt2.index = p2->index;
163 triangles.push_back(vt2.index);
165 detail::LocalVertexType vt3(source[++i3]);
166 std::set<detail::LocalVertexType, detail::ltLocalVertexValue>::iterator p3 = vertices.find(vt3);
167 if (p3 == vertices.end())
169 vt3.index = vertices.size();
170 vertices.insert(vt3);
173 vt3.index = p3->index;
175 triangles.push_back(vt3.index);
179 std::vector<detail::LocalVertexType> vt;
180 vt.insert(vt.end(), vertices.begin(), vertices.end());
181 std::sort(vt.begin(), vt.end(), detail::ltLocalVertexIndex());
184 unsigned int nt = triangles.size() / 3;
186 Mesh* mesh =
new Mesh(vt.size(), nt);
187 for (
unsigned int i = 0; i < vt.size(); ++i)
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;
195 std::copy(triangles.begin(), triangles.end(), mesh->triangles);
196 mesh->computeTriangleNormals();
197 mesh->computeVertexNormals();
204 static const Eigen::Vector3d one(1.0, 1.0, 1.0);
208 Mesh*
createMeshFromBinary(
const char* buffer, std::size_t size,
const std::string& assimp_hint)
210 static const Eigen::Vector3d one(1.0, 1.0, 1.0);
215 const std::string& assimp_hint)
217 if (!buffer || size < 1)
219 CONSOLE_BRIDGE_logWarn(
"Cannot construct mesh from empty binary buffer");
225 std::size_t pos = assimp_hint.find_last_of(
'.');
226 if (pos != std::string::npos)
228 hint = assimp_hint.substr(pos + 1);
229 std::transform(hint.begin(), hint.end(), hint.begin(), ::tolower);
235 Assimp::Importer importer;
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);
246 const aiScene* scene = importer.ReadFileFromMemory(
reinterpret_cast<const void*
>(buffer), size,
247 aiProcess_Triangulate | aiProcess_JoinIdenticalVertices |
248 aiProcess_SortByPType | aiProcess_RemoveComponent,
258 scene->mRootNode->mTransformation = aiMatrix4x4();
262 importer.ApplyPostProcessing(aiProcess_OptimizeMeshes | aiProcess_OptimizeGraph);
273 res = retriever.
get(resource);
283 CONSOLE_BRIDGE_logWarn(
"Retrieved empty mesh for resource '%s'", resource.c_str());
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.");
299 void extractMeshData(
const aiScene* scene,
const aiNode* node,
const aiMatrix4x4& parent_transform,
301 std::vector<unsigned int>& triangles)
303 aiMatrix4x4
transform = parent_transform;
305 for (
unsigned int j = 0; j < node->mNumMeshes; ++j)
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)
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()));
314 for (
unsigned int i = 0; i < a->mNumFaces; ++i)
315 if (a->mFaces[i].mNumIndices == 3)
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]);
323 for (
unsigned int n = 0; n < node->mNumChildren; ++n)
324 extractMeshData(scene, node->mChildren[n],
transform, scale, vertices, triangles);
330 static const Eigen::Vector3d one(1.0, 1.0, 1.0);
334 Mesh*
createMeshFromAsset(
const aiScene* scene,
const Eigen::Vector3d& scale,
const std::string& resource_name)
336 if (!scene->HasMeshes())
338 CONSOLE_BRIDGE_logWarn(
"Assimp reports scene in %s has no meshes", resource_name.c_str());
342 std::vector<unsigned int> triangles;
343 extractMeshData(scene, scene->mRootNode, aiMatrix4x4(), scale, vertices, triangles);
344 if (vertices.empty())
346 CONSOLE_BRIDGE_logWarn(
"There are no vertices in the scene %s", resource_name.c_str());
349 if (triangles.empty())
351 CONSOLE_BRIDGE_logWarn(
"There are no triangles in the scene %s", resource_name.c_str());
375 double x = box.size[0] / 2.0;
376 double y = box.size[1] / 2.0;
377 double z = box.size[2] / 2.0;
380 Mesh* result =
new Mesh(8, 12);
381 result->vertices[0] = -
x;
382 result->vertices[1] = -
y;
383 result->vertices[2] = -
z;
385 result->vertices[3] =
x;
386 result->vertices[4] = -
y;
387 result->vertices[5] = -
z;
389 result->vertices[6] =
x;
390 result->vertices[7] = -
y;
391 result->vertices[8] =
z;
393 result->vertices[9] = -
x;
394 result->vertices[10] = -
y;
395 result->vertices[11] =
z;
397 result->vertices[12] = -
x;
398 result->vertices[13] =
y;
399 result->vertices[14] =
z;
401 result->vertices[15] = -
x;
402 result->vertices[16] =
y;
403 result->vertices[17] = -
z;
405 result->vertices[18] =
x;
406 result->vertices[19] =
y;
407 result->vertices[20] =
z;
409 result->vertices[21] =
x;
410 result->vertices[22] =
y;
411 result->vertices[23] = -
z;
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();
425 std::vector<unsigned int> triangles;
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);
432 const unsigned int ring = std::max<unsigned int>(6, 2.0 * r / 0.01);
437 phid = pi * 2.0 / seg;
440 double theta, thetad;
441 thetad = pi / (ring + 1);
444 for (
unsigned int i = 0; i < ring; ++i)
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),
451 vertices.push_back(Eigen::Vector3d(0.0, 0.0, r));
452 vertices.push_back(Eigen::Vector3d(0.0, 0.0, -r));
454 for (
unsigned int i = 0; i < ring - 1; ++i)
456 for (
unsigned int j = 0; j < seg; ++j)
458 unsigned int a, b, c,
d;
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);
472 for (
unsigned int j = 0; j < seg; ++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);
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);
494 std::vector<unsigned int> triangles;
497 static unsigned int tot_for_unit_cylinder = 100;
499 double r = cylinder.radius;
500 double h = cylinder.length;
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;
506 double circle_edge = phid *
r;
507 unsigned int h_num = ceil(std::abs(h) / circle_edge);
510 double hd = h / h_num;
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));
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));
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));
522 vertices.push_back(Eigen::Vector3d(0, 0, h / 2));
523 vertices.push_back(Eigen::Vector3d(0, 0, -h / 2));
525 for (
unsigned int i = 0; i < tot; ++i)
527 triangles.push_back((h_num + 1) * tot);
528 triangles.push_back(i);
529 triangles.push_back((i == tot - 1) ? 0 : (i + 1));
532 for (
unsigned int i = 0; i < tot; ++i)
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);
539 for (
unsigned int i = 0; i < h_num; ++i)
541 for (
unsigned int j = 0; j < tot; ++j)
545 b = (j == tot - 1) ? 0 : (j + 1);
547 d = (j == tot - 1) ? tot : (j + 1 + 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);
565 std::vector<unsigned int> triangles;
568 static unsigned int tot_for_unit_cone = 100;
570 double r = cone.radius;
571 double h = cone.length;
573 const double pi = boost::math::constants::pi<double>();
574 unsigned int tot = tot_for_unit_cone *
r;
575 double phid = pi * 2 / tot;
577 double circle_edge = phid *
r;
578 unsigned int h_num = ceil(h / circle_edge);
581 double hd = h / h_num;
583 for (
unsigned int i = 0; i < h_num - 1; ++i)
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));
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));
594 vertices.push_back(Eigen::Vector3d(0, 0, h / 2));
595 vertices.push_back(Eigen::Vector3d(0, 0, -h / 2));
597 for (
unsigned int i = 0; i < tot; ++i)
599 triangles.push_back(h_num * tot);
600 triangles.push_back(i);
601 triangles.push_back((i == tot - 1) ? 0 : (i + 1));
604 for (
unsigned int i = 0; i < tot; ++i)
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);
611 for (
unsigned int i = 0; i < h_num - 1; ++i)
612 for (
unsigned int j = 0; j < tot; ++j)
616 b = (j == tot - 1) ? 0 : (j + 1);
618 d = (j == tot - 1) ? tot : (j + 1 + 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);
633 inline void writeFloatToSTL(
char*& ptr,
const float data)
635 memcpy(ptr, &data,
sizeof(
float));
636 ptr +=
sizeof(float);
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)
650 unsigned int i3 = i * 3;
652 if (mesh->triangle_normals)
654 writeFloatToSTL(ptr, mesh->triangle_normals[i3]);
655 writeFloatToSTL(ptr, mesh->triangle_normals[i3 + 1]);
656 writeFloatToSTL(ptr, mesh->triangle_normals[i3 + 2]);
660 memset(ptr, 0,
sizeof(
float) * 3);
661 ptr +=
sizeof(float) * 3;
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]);