MRPT  1.9.9
CAssimpModel.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 // This file contains portions of code from Assimp's example:
11 // "Sample_SimpleOpenGL.c"
12 
13 #include "opengl-precomp.h" // Precompiled header
14 
16 
17 #if MRPT_HAS_ASSIMP
18 #if defined(MRPT_ASSIMP_VERSION_MAJOR) && MRPT_ASSIMP_VERSION_MAJOR < 3
19 #include <aiPostProcess.h>
20 #include <aiScene.h>
21 #include <assimp.h>
22 #else
23 #include <assimp/cimport.h>
24 #include <assimp/postprocess.h>
25 #include <assimp/scene.h>
26 #include <assimp/DefaultLogger.hpp>
27 #include <assimp/LogStream.hpp>
28 #endif
29 #endif
30 
32 #include <mrpt/system/filesystem.h>
33 
34 using namespace mrpt;
35 using namespace mrpt::opengl;
36 using namespace mrpt::math;
37 using namespace std;
38 using mrpt::img::CImage;
39 
41 
43 {
44  std::vector<mrpt::math::TPoint3Df>* lines_vbd = nullptr;
45  std::vector<mrpt::img::TColor>* lines_cbd = nullptr;
46  std::vector<mrpt::math::TPoint3Df>* pts_vbd = nullptr;
47  std::vector<mrpt::img::TColor>* pts_cbd = nullptr;
48  std::vector<mrpt::opengl::TTriangle>* tris = nullptr;
49 };
50 
51 #if MRPT_HAS_OPENGL_GLUT && MRPT_HAS_ASSIMP
52 // Note: Look at older git versions to see pre-OpenGL3 version with more texture
53 // supports, etc. load_textures(), etc.
54 static void recursive_render(
55  const aiScene* sc, const aiNode* nd, const mrpt::poses::CPose3D& transf,
56  RenderElements& re);
57 
58 // Just return the diffuse color:
59 static mrpt::img::TColor apply_material(const aiMaterial* mtl);
60 static void get_bounding_box(
61  const aiScene* sc, aiVector3D* min, aiVector3D* max);
62 static void get_bounding_box_for_node(
63  const aiScene* sc, const aiNode* nd, aiVector3D* min, aiVector3D* max,
64  aiMatrix4x4* trafo);
65 #endif // MRPT_HAS_OPENGL_GLUT && MRPT_HAS_ASSIMP
66 
67 void CAssimpModel::render(const RenderContext& rc) const
68 {
69  switch (rc.shader_id)
70  {
73  break;
76  break;
79  break;
80  };
81 }
83 {
84  // Process all elements at once:
85  const_cast<CAssimpModel&>(*this).onUpdateBuffers_all();
86 
90 }
91 
92 // special case for assimp: update all buffers within one run over the scene
93 // structure.
95 {
98  lines_vbd.clear();
99  lines_cbd.clear();
100 
103  pts_vbd.clear();
104  pts_cbd.clear();
105 
107  tris.clear();
108 
109  if (!m_assimp_scene->scene) return; // No scene
110 
111  RenderElements re;
112  re.lines_vbd = &lines_vbd;
113  re.lines_cbd = &lines_cbd;
114  re.pts_vbd = &pts_vbd;
115  re.pts_cbd = &pts_cbd;
116  re.tris = &tris;
117 
118 #if MRPT_HAS_OPENGL_GLUT && MRPT_HAS_ASSIMP
119  auto* scene = reinterpret_cast<aiScene*>(m_assimp_scene->scene);
120 
121  const auto transf = mrpt::poses::CPose3D();
122 
123  recursive_render(scene, scene->mRootNode, transf, re);
124 #endif
125 }
126 
127 // These 3: already done in onUpdateBuffers_all()
131 
132 uint8_t CAssimpModel::serializeGetVersion() const { return 0; }
134 {
135  writeToStreamRender(out);
136 
137  const bool empty = m_assimp_scene->scene != nullptr;
138  out << empty;
139 
140  if (!empty)
141  {
142 #if MRPT_HAS_OPENGL_GLUT && MRPT_HAS_ASSIMP
143  // aiScene *scene = (aiScene *) m_assimp_scene->scene;
144  THROW_EXCEPTION("MRPT can't serialize Assimp objects yet!");
145 #else
146  THROW_EXCEPTION("MRPT compiled without OpenGL and/or Assimp");
147 #endif
148  }
149 }
150 
152  mrpt::serialization::CArchive& in, uint8_t version)
153 {
154  THROW_EXCEPTION("MRPT can't serialize Assimp objects yet!");
155 
156  switch (version)
157  {
158  case 0:
159  {
160  readFromStreamRender(in);
161 
162  clear();
163  }
164  break;
165  default:
167  };
169 }
170 
171 CAssimpModel::CAssimpModel() : m_bbox_min(0, 0, 0), m_bbox_max(0, 0, 0)
172 {
173  m_assimp_scene = std::make_shared<TImplAssimp>();
174 }
175 
177 /*---------------------------------------------------------------
178  clear
179  ---------------------------------------------------------------*/
181 {
183  m_assimp_scene = std::make_shared<TImplAssimp>();
184  m_modelPath.clear();
185  // m_textures_loaded = false;
186 
187 #if MRPT_HAS_OPENGL_GLUT
188 #if 0
189  if (!m_textureIds.empty())
190  {
191  glDeleteTextures(m_textureIds.size(), &m_textureIds[0]);
192  m_textureIds.clear();
193  }
194  m_textureIdMap.clear();
195 #endif
196 #endif
197 }
198 
199 void CAssimpModel::loadScene(const std::string& filepath)
200 {
201 #if MRPT_HAS_OPENGL_GLUT && MRPT_HAS_ASSIMP
202  clear();
204 
205  // we are taking one of the postprocessing presets to avoid
206  // spelling out 20+ single postprocessing flags here.
207  m_assimp_scene->scene = (void*)aiImportFile(
208  filepath.c_str(), aiProcessPreset_TargetRealtime_MaxQuality);
209  m_modelPath = filepath;
210 
211  if (m_assimp_scene->scene)
212  {
213  aiVector3D scene_min, scene_max;
214  auto* scene = (aiScene*)m_assimp_scene->scene;
215  get_bounding_box(scene, &scene_min, &scene_max);
216  m_bbox_min.x = scene_min.x;
217  m_bbox_min.y = scene_min.y;
218  m_bbox_min.z = scene_min.z;
219  m_bbox_max.x = scene_max.x;
220  m_bbox_max.y = scene_max.y;
221  m_bbox_max.z = scene_max.z;
222  }
223 
224 #else
225  THROW_EXCEPTION("MRPT compiled without OpenGL and/or Assimp");
226 #endif
227 }
228 
231 {
232  bb_min = m_bbox_min;
233  bb_max = m_bbox_max;
234 
235  // Convert to coordinates of my parent:
238 }
239 
242 {
243 #if MRPT_HAS_OPENGL_GLUT && MRPT_HAS_ASSIMP
244  if (scene)
245  {
246  // cleanup - calling 'aiReleaseImport' is important, as the library
247  // keeps internal resources until the scene is freed again. Not
248  // doing so can cause severe resource leaking.
249  aiReleaseImport((aiScene*)scene);
250  scene = nullptr;
251  }
252 #endif
253 }
254 
255 bool CAssimpModel::traceRay(const mrpt::poses::CPose3D& o, double& dist) const
256 {
257  // TODO
258  return false;
259 }
260 
261 #if MRPT_HAS_OPENGL_GLUT && MRPT_HAS_ASSIMP
262 
263 static void get_bounding_box_for_node(
264  const aiScene* scene, const aiNode* nd, aiVector3D* min, aiVector3D* max,
265  aiMatrix4x4* trafo)
266 {
267  aiMatrix4x4 prev;
268  unsigned int n = 0, t;
269 
270  prev = *trafo;
271  aiMultiplyMatrix4(trafo, &nd->mTransformation);
272 
273  for (; n < nd->mNumMeshes; ++n)
274  {
275  const aiMesh* mesh = scene->mMeshes[nd->mMeshes[n]];
276  for (t = 0; t < mesh->mNumVertices; ++t)
277  {
278  aiVector3D tmp = mesh->mVertices[t];
279  aiTransformVecByMatrix4(&tmp, trafo);
280 
281  min->x = std::min(min->x, tmp.x);
282  min->y = std::min(min->y, tmp.y);
283  min->z = std::min(min->z, tmp.z);
284 
285  max->x = std::max(max->x, tmp.x);
286  max->y = std::max(max->y, tmp.y);
287  max->z = std::max(max->z, tmp.z);
288  }
289  }
290 
291  for (n = 0; n < nd->mNumChildren; ++n)
292  {
293  get_bounding_box_for_node(scene, nd->mChildren[n], min, max, trafo);
294  }
295  *trafo = prev;
296 }
297 
298 static void get_bounding_box(
299  const aiScene* scene, aiVector3D* min, aiVector3D* max)
300 {
301  aiMatrix4x4 trafo;
302  aiIdentityMatrix4(&trafo);
303 
304  min->x = min->y = min->z = 1e10f;
305  max->x = max->y = max->z = -1e10f;
306  get_bounding_box_for_node(scene, scene->mRootNode, min, max, &trafo);
307 }
308 
309 static mrpt::img::TColor color4_to_TColor(const aiColor4D& c)
310 {
311  return mrpt::img::TColorf(c.r, c.g, c.b, c.a).asTColor();
312 }
313 
314 static mrpt::img::TColor apply_material(const aiMaterial* mtl)
315 {
316  aiColor4D diffuse;
317  if (AI_SUCCESS ==
318  aiGetMaterialColor(mtl, AI_MATKEY_COLOR_DIFFUSE, &diffuse))
319  {
320  return color4_to_TColor(diffuse);
321  }
322  else
323  {
324  // Default color:
325  return {0xa0, 0xa0, 0xa0, 0xff};
326  }
327 }
328 
329 static mrpt::math::CMatrixDouble44 aiMatrix_to_mrpt(const aiMatrix4x4& m)
330 {
332  M(0, 0) = m.a1;
333  M(0, 1) = m.a2;
334  M(0, 2) = m.a3;
335  M(0, 3) = m.a4;
336 
337  M(1, 0) = m.b1;
338  M(1, 1) = m.b2;
339  M(1, 2) = m.b3;
340  M(1, 3) = m.b4;
341 
342  M(2, 0) = m.c1;
343  M(2, 1) = m.c2;
344  M(2, 2) = m.c3;
345  M(2, 3) = m.c4;
346 
347  M(3, 0) = m.d1;
348  M(3, 1) = m.d2;
349  M(3, 2) = m.d3;
350  M(3, 3) = m.d4;
351  return M;
352 }
353 
354 static mrpt::math::TPoint3Df to_mrpt(const aiVector3D& v)
355 {
356  return {v.x, v.y, v.z};
357 }
358 
359 static void recursive_render(
360  const aiScene* sc, const aiNode* nd, const mrpt::poses::CPose3D& transf,
361  RenderElements& re)
362 {
363  aiMatrix4x4 m = nd->mTransformation;
364 
365  // update transform
366  const auto nodeTransf = mrpt::poses::CPose3D(aiMatrix_to_mrpt(m));
367  const mrpt::poses::CPose3D curTf = transf + nodeTransf;
368 
369  // draw all meshes assigned to this node
370  for (unsigned int n = 0; n < nd->mNumMeshes; ++n)
371  {
372  const struct aiMesh* mesh = sc->mMeshes[nd->mMeshes[n]];
373 
374  mrpt::img::TColor color =
375  apply_material(sc->mMaterials[mesh->mMaterialIndex]);
376 
377  for (unsigned int t = 0; t < mesh->mNumFaces; ++t)
378  {
379  const struct aiFace* face = &mesh->mFaces[t];
380 
381  switch (face->mNumIndices)
382  {
383  case 1:
384  // GL_POINTS ================
385  for (unsigned int i = 0; i < face->mNumIndices; i++)
386  {
387  // get group index for current index
388  int vertexIndex = face->mIndices[i];
389  if (mesh->mColors[0] != nullptr)
390  color =
391  color4_to_TColor(mesh->mColors[0][vertexIndex]);
392 
393  re.pts_vbd->emplace_back(curTf.composePoint(
394  to_mrpt(mesh->mVertices[vertexIndex])));
395  re.pts_cbd->emplace_back(color);
396  }
397  break;
398 
399  case 2:
400  // GL_LINES ================
401  for (unsigned int i = 0; i < face->mNumIndices; i++)
402  {
403  // get group index for current index
404  int vertexIndex = face->mIndices[i];
405  if (mesh->mColors[0] != nullptr)
406  color =
407  color4_to_TColor(mesh->mColors[0][vertexIndex]);
408 
409  re.lines_vbd->emplace_back(curTf.composePoint(
410  to_mrpt(mesh->mVertices[vertexIndex])));
411  re.lines_cbd->emplace_back(color);
412  }
413  break;
414 
415  case 3:
416  {
417  // GL_TRIANGLES ================
418  const unsigned int nTri = face->mNumIndices / 3;
419  ASSERT_EQUAL_(face->mNumIndices % 3, 0);
420 
421  for (unsigned int iTri = 0; iTri < nTri; iTri++)
422  {
424  for (unsigned int v = 0; v < 3; v++)
425  {
426  unsigned int i = iTri * 3 + v;
427  // get group index for current index
428  int vertexIndex = face->mIndices[i];
429  if (mesh->mColors[0] != nullptr)
430  color = color4_to_TColor(
431  mesh->mColors[0][vertexIndex]);
432 
433  tri.r(v) = color.R;
434  tri.g(v) = color.G;
435  tri.b(v) = color.B;
436  tri.a(v) = color.A;
437 
438  // texture_coordinates_set=0
439  if (mesh->HasTextureCoords(0))
440  {
441  tri.vertices[v].uv.x =
442  mesh->mTextureCoords[0][vertexIndex].x;
443  tri.vertices[v].uv.y =
444  mesh->mTextureCoords[0][vertexIndex].y;
445  }
446 
447  if (mesh->mNormals)
448  tri.vertices[v].normal = curTf.rotateVector(
449  to_mrpt(mesh->mNormals[vertexIndex]));
450 
451  auto pt = curTf.composePoint(
452  to_mrpt(mesh->mVertices[vertexIndex]));
453  tri.x(v) = pt.x;
454  tri.y(v) = pt.y;
455  tri.z(v) = pt.z;
456  }
457 
458  re.tris->emplace_back(std::move(tri));
459  }
460  }
461  break;
462  default:
463  // GL_POLYGON ================
464  THROW_EXCEPTION("ASSIMP polygons not implemented yet.");
465  break;
466  }
467  }
468  }
469 
470  // draw all children
471  for (unsigned int n = 0; n < nd->mNumChildren; ++n)
472  recursive_render(sc, nd->mChildren[n], curTf, re);
473 }
474 
475 #endif // MRPT_HAS_OPENGL_GLUT && MRPT_HAS_ASSIMP
A compile-time fixed-size numeric matrix container.
Definition: CMatrixFixed.h:33
const uint8_t & b(size_t i) const
Definition: TTriangle.h:95
std::vector< mrpt::math::TPoint3Df > m_vertex_buffer_data
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
void serializeFrom(mrpt::serialization::CArchive &in, uint8_t serial_version) override
Pure virtual method for reading (deserializing) from an abstract archive.
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
To be added to all CSerializable-classes implementation files.
void onUpdateBuffers_Triangles() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
const uint8_t & r(size_t i) const
Definition: TTriangle.h:93
void notifyChange() const
Call to enable calling renderUpdateBuffers() before the next render() rendering iteration.
const float & x(size_t i) const
Definition: TTriangle.h:90
std::vector< mrpt::img::TColor > * lines_cbd
std::vector< mrpt::math::TPoint3Df > * pts_vbd
A triangle (float coordinates) with RGBA colors (u8) and UV (texture coordinates) for each vertex...
Definition: TTriangle.h:35
The base class of 3D objects that can be directly rendered through OpenGL.
Definition: CRenderizable.h:48
void onUpdateBuffers_Points() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
const uint8_t & g(size_t i) const
Definition: TTriangle.h:94
STL namespace.
uint8_t B
Definition: TColor.h:51
uint8_t G
Definition: TColor.h:51
void loadScene(const std::string &file_name)
Loads a scene from a file in any supported file.
mrpt::math::TPoint3D m_bbox_min
Bounding box.
Definition: CAssimpModel.h:113
mrpt::poses::CPose3D m_pose
6D pose wrt the parent coordinate reference.
Definition: CRenderizable.h:62
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.
bool traceRay(const mrpt::poses::CPose3D &o, double &dist) const override
Simulation of ray-trace, given a pose.
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.
Context for calls to render()
mrpt::math::TVector3D rotateVector(const mrpt::math::TVector3D &local) const
Rotates a vector (i.e.
Definition: CPose3D.cpp:460
std::vector< mrpt::math::TPoint3Df > m_vertex_buffer_data
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
Definition: exceptions.h:97
const uint8_t & a(size_t i) const
Definition: TTriangle.h:96
std::vector< mrpt::img::TColor > m_color_buffer_data
std::array< Vertex, 3 > vertices
Definition: TTriangle.h:88
void onUpdateBuffers_Wireframe() override
Must be implemented in derived classes to update the geometric entities to be drawn in "m_*_buffer" f...
mrpt::img::CImage CImage
Definition: utils/CImage.h:5
This base provides a set of functions for maths stuff.
mrpt::math::TPoint3D m_bbox_max
Definition: CAssimpModel.h:113
void getBoundingBox(mrpt::math::TPoint3D &bb_min, mrpt::math::TPoint3D &bb_max) const override
Evaluates the bounding box of this object (including possible children) in the coordinate frame of th...
void clear()
Empty the object.
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
Definition: exceptions.h:137
std::vector< mrpt::math::TPoint3Df > * lines_vbd
static constexpr shader_id_t WIREFRAME
uint8_t serializeGetVersion() const override
Must return the current versioning number of the object.
virtual ~CAssimpModel() override
uint8_t R
Definition: TColor.h:51
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.
bool empty() const
Definition: ts_hash_map.h:191
static constexpr shader_id_t TRIANGLES
std::vector< mrpt::img::TColor > * pts_cbd
T x
X,Y,Z coordinates.
Definition: TPoint3D.h:29
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
std::vector< mrpt::img::TColor > m_color_buffer_data
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::vector< mrpt::opengl::TTriangle > * tris
const float & y(size_t i) const
Definition: TTriangle.h:91
Virtual base class for "archives": classes abstracting I/O streams.
Definition: CArchive.h:54
std::vector< mrpt::opengl::TTriangle > m_triangles
List of triangles.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
mrpt::vision::TStereoCalibResults out
const float & z(size_t i) const
Definition: TTriangle.h:92
An RGBA color - floats in the range [0,1].
Definition: TColor.h:88
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:13
const auto bb_max
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
void serializeTo(mrpt::serialization::CArchive &out) const override
Pure virtual method for writing (serializing) to an abstract archive.
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
const auto bb_min
TColor asTColor() const
Returns the 0-255 integer version of this color: RGBA_u8.
Definition: TColor.h:101
A RGB color - 8bit.
Definition: TColor.h:25
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:183
This class can load & render 3D models in a number of different formats (requires the library assimp)...
Definition: CAssimpModel.h:41
static constexpr shader_id_t POINTS
uint8_t A
Definition: TColor.h:51
std::shared_ptr< TImplAssimp > m_assimp_scene
Definition: CAssimpModel.h:110
void render(const RenderContext &rc) const override
Implements the rendering of 3D objects in each class derived from CRenderizable.
void renderUpdateBuffers() const override
Called whenever m_outdatedBuffers is true: used to re-generate OpenGL vertex buffers, etc.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020