geolib2
import.cpp
Go to the documentation of this file.
1 #include "geolib/io/import.h"
2 
3 #ifdef ASSIMP_VERSION_3
4  #include <assimp/Importer.hpp>
5  #include <assimp/scene.h>
6 #else
7  #include <assimp/assimp.hpp>
8  #include <assimp/aiScene.h>
9 #endif
10 
11 #include <console_bridge/console.h>
12 
13 #include <geolib/Shape.h>
14 
15 #include <map>
16 #include <set>
17 #include <sstream>
18 #include <string>
19 
20 namespace geo {
21 
22 namespace io {
23 
24 // ----------------------------------------------------------------------------------------------------
25 
26 void constructMesh(const aiScene* scene, aiNode* node, const geo::Pose3D& parent_pose, double scale_x, double scale_y, double scale_z, bool transform, geo::Mesh* mesh)
27 {
28  const aiMatrix4x4& t = node->mTransformation;
29  geo::Pose3D p;
30  p.t = geo::Vector3(t.a4, t.b4, t.c4);
31  p.R = geo::Matrix3(t.a1, t.a2, t.a3, t.b1, t.b2, t.b3, t.c1, t.c2, t.c3);
32 
33  geo::Pose3D pose = parent_pose * p;
34 
35  for(unsigned int i = 0; i < node->mNumChildren; ++i)
36  {
37  constructMesh(scene, node->mChildren[i], pose, scale_x, scale_y, scale_z, transform, mesh);
38  }
39 
40  for(unsigned int i = 0; i < node->mNumMeshes; ++i)
41  {
42  aiMesh* m = scene->mMeshes[node->mMeshes[i]];
43 
45  std::vector<int> i_map(m->mNumVertices);
46 
47  for(unsigned int j = 0; j < m->mNumVertices; ++j) {
48  const aiVector3D& v = m->mVertices[j];
49 
50  int ix = 1000 * scale_x * v.x;
51  int iy = 1000 * scale_y * v.y;
52  int iz = 1000 * scale_z * v.z;
53 
54  bool match = false;
55  std::map<int, std::map<int, std::map<int, int> > >::iterator it1 = xyz_map.find(ix);
56  if (it1 != xyz_map.end()) {
57  std::map<int, std::map<int, int> >::iterator it2 = it1->second.find(iy);
58  if (it2 != it1->second.end()) {
59  std::map<int, int>::iterator it3 = it2->second.find(iz);
60  if (it3 != it2->second.end()) {
61  i_map[j] = it3->second;
62  match = true;
63  }
64  }
65  }
66 
67  if (!match) {
68  geo::Vector3 p(v.x, v.y, v.z);
69  if (transform)
70  p = pose * p;
71 
72  int ip = mesh->addPoint(scale_x * p.x, scale_y * p.y, scale_z * p.z);
73  xyz_map[ix][iy][iz] = ip;
74  i_map[j] = ip;
75  }
76  }
77 
79 
80  int num_triangles = 0;
81  for(unsigned int j = 0; j < m->mNumFaces; ++j) {
82  const aiFace& f = m->mFaces[j];
83  if (f.mNumIndices == 3) {
84  int ix = i_map[f.mIndices[0]];
85  int iy = i_map[f.mIndices[1]];
86  int iz = i_map[f.mIndices[2]];
87 
88  bool match = false;
89  std::map<int, std::map<int, std::set<int> > >::iterator it1 = triangle_map.find(ix);
90  if (it1 != triangle_map.end()) {
91  std::map<int, std::set<int> >::iterator it2 = it1->second.find(iy);
92  if (it2 != it1->second.end()) {
93  if (it2->second.find(iz) != it2->second.end()) {
94  match = true;
95  }
96  }
97  }
98 
99  if (!match) {
100  mesh->addTriangle(ix, iy, iz);
101  triangle_map[ix][iy].insert(iz);
102  ++num_triangles;
103  }
104  }
105  }
106  }
107 
108 }
109 
110 // ----------------------------------------------------------------------------------------------------
111 
112 ShapePtr readMeshFile(const std::string& filename, const geo::Vec3& scale)
113 {
114  Assimp::Importer I;
115  const aiScene* scene = I.ReadFile(filename, 0);
116 
117  if (!scene)
118  {
120  ss << "Assimp failed to load file: " << filename << std::endl;
121  const std::string& str = ss.str();
122  CONSOLE_BRIDGE_logError(str.c_str());
123  return ShapePtr();
124  }
125 
126  // TODO: get rid of this hack!!!
127  bool transform = true;
128  if (filename.substr(filename.size() - 3) == "3ds")
129  {
130  transform = false;
131  }
132 
133  ShapePtr shape(new Shape());
134 
135  Mesh mesh;
136 
137  if (filename.substr(filename.size() - 3) == "dae")
138  {
139  // compensate for rotation caused by "UP_AXIS". This is already applied by assimp, so don't need to do it again
140  // in constructMesh, therefore we need the compensation here. Rotation matrix of assimp also containts the
141  // scaling from "UNIT". We don't want to compensate for that, so we normalize the rotation matrix.
142  const aiMatrix4x4& t = scene->mRootNode->mTransformation;
143  geo::Pose3D p;
144  p.t = geo::Vector3(t.a4, t.b4, t.c4);
145  p.R = geo::Matrix3(t.a1, t.a2, t.a3, t.b1, t.b2, t.b3, t.c1, t.c2, t.c3).normalized();
146  constructMesh(scene, scene->mRootNode, p.inverse(), scale.x, scale.y, scale.z, transform, &mesh);
147  }
148  else
149  constructMesh(scene, scene->mRootNode, geo::Pose3D::identity(), scale.x, scale.y, scale.z, transform, &mesh);
150 
151  shape->setMesh(mesh);
152 
153  return shape;
154 }
155 
156 }
157 
158 }
Shape.h
geo::Vector3
Vec3 Vector3
Definition: datatypes.h:32
sstream
geo::ShapePtr
std::shared_ptr< Shape > ShapePtr
Definition: datatypes.h:12
std::string
std::shared_ptr
geo
Definition: Box.h:6
t
Timer t
geo::Transform3T::identity
static Transform3T identity()
Definition: math_types.h:778
std::vector
std::map::find
T find(T... args)
std::string::size
T size(T... args)
geo::Vec3T
Definition: math_types.h:13
std::stringstream
geo::Mat3T::normalized
Mat3T normalized()
Definition: math_types.h:587
geo::Transform3T
Definition: math_types.h:19
geo::Vec3T::y
T y
Definition: math_types.h:217
geo::Transform3T::inverse
Transform3T inverse() const
Definition: math_types.h:747
geo::Mesh::addPoint
unsigned int addPoint(double x, double y, double z)
Definition: Mesh.cpp:15
std::string::c_str
T c_str(T... args)
geo::io::readMeshFile
ShapePtr readMeshFile(const std::string &filename, const geo::Vec3 &scale)
Definition: import.cpp:112
geo::Transform3T::t
Vec3T< T > t
Definition: math_types.h:794
geo::Vector3
Definition: matrix.h:12
map
std::string::substr
T substr(T... args)
geo::io::constructMesh
void constructMesh(const aiScene *scene, aiNode *node, const geo::Pose3D &parent_pose, double scale_x, double scale_y, double scale_z, bool transform, geo::Mesh *mesh)
Definition: import.cpp:26
std::endl
T endl(T... args)
std::map::insert
T insert(T... args)
geo::Transform3T::R
Mat3T< T > R
Definition: math_types.h:793
geo::Mesh::addTriangle
void addTriangle(unsigned int i1, unsigned int i2, unsigned int i3)
Definition: Mesh.cpp:26
geo::Vec3T::z
T z
Definition: math_types.h:217
std::stringstream::str
T str(T... args)
std::map::end
T end(T... args)
geo::Matrix3
Mat3 Matrix3
Definition: datatypes.h:33
geo::Mesh
Definition: Mesh.h:25
set
geo::Vec3T::x
T x
Definition: math_types.h:217
geo::Shape
A geometric description of a shape.
Definition: Shape.h:19
import.h
string