1 /*
2  * Copyright (c) 2011-2021, The DART development contributors
3  * All rights reserved.
4  *
5  * The list of contributors can be found at:
6  *   https://github.com/dartsim/dart/blob/master/LICENSE
7  *
8  * This file is provided under the following "BSD-style" License:
9  *   Redistribution and use in source and binary forms, with or
10  *   without modification, are permitted provided that the following
11  *   conditions are met:
12  *   * Redistributions of source code must retain the above copyright
13  *     notice, this list of conditions and the following disclaimer.
14  *   * Redistributions in binary form must reproduce the above
15  *     copyright notice, this list of conditions and the following
16  *     disclaimer in the documentation and/or other materials provided
17  *     with the distribution.
18  *   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19  *   CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20  *   INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21  *   MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  *   DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23  *   CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24  *   SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25  *   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26  *   USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  *   AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  *   LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  *   ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  *   POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #include <iostream>
34 #include <assimp/cimport.h>
35 
36 #include "dart/common/Console.hpp"
37 #include "dart/dynamics/BodyNode.hpp"
38 #include "dart/dynamics/BoxShape.hpp"
39 #include "dart/dynamics/CylinderShape.hpp"
40 #include "dart/dynamics/EllipsoidShape.hpp"
41 #include "dart/dynamics/LineSegmentShape.hpp"
42 #include "dart/dynamics/MeshShape.hpp"
43 #include "dart/dynamics/Shape.hpp"
44 #include "dart/dynamics/ShapeNode.hpp"
45 #include "dart/dynamics/Skeleton.hpp"
46 #include "dart/gui/LoadOpengl.hpp"
47 #include "dart/gui/OpenGLRenderInterface.hpp"
48 #include "dart/math/Icosphere.hpp"
49 
50 // Code taken from glut/lib/glut_shapes.c
51 static GLUquadricObj* quadObj;
52 
53 #define QUAD_OBJ_INIT                                                          \
54   {                                                                            \
55     if (!quadObj)                                                              \
56       initQuadObj();                                                           \
57   }
58 
initQuadObj(void)59 static void initQuadObj(void)
60 {
61   quadObj = gluNewQuadric();
62   if (!quadObj)
63     // DART modified error output
64     std::cerr << "OpenGL: Fatal Error in DART: out of memory." << std::endl;
65 }
66 // glut/lib/glut_shapes.c
67 
68 namespace dart {
69 namespace gui {
70 
initialize()71 void OpenGLRenderInterface::initialize()
72 {
73   glMatrixMode(GL_MODELVIEW);
74   glLoadIdentity();
75   glMatrixMode(GL_PROJECTION);
76   glLoadIdentity();
77   glCullFace(GL_BACK);
78   glDisable(GL_LIGHTING);
79   glEnable(GL_DEPTH_TEST);
80   // glLightModeli(GL_LIGHT_MODEL_TWO_SIDE, GL_TRUE);
81   glShadeModel(GL_SMOOTH);
82   clear(Eigen::Vector3d(1.0, 1.0, 1.0));
83 }
84 
destroy()85 void OpenGLRenderInterface::destroy()
86 {
87 }
88 
setViewport(int _x,int _y,int _width,int _height)89 void OpenGLRenderInterface::setViewport(int _x, int _y, int _width, int _height)
90 {
91   glViewport(_x, _y, _width, _height);
92   mViewportX = _x;
93   mViewportY = _y;
94   mViewportWidth = _width;
95   mViewportHeight = _height;
96 }
97 
getViewport(int & _x,int & _y,int & _width,int & _height) const98 void OpenGLRenderInterface::getViewport(
99     int& _x, int& _y, int& _width, int& _height) const
100 {
101   _x = mViewportX;
102   _y = mViewportY;
103   _width = mViewportWidth;
104   _height = mViewportHeight;
105 }
106 
clear(const Eigen::Vector3d & _color)107 void OpenGLRenderInterface::clear(const Eigen::Vector3d& _color)
108 {
109   glClearColor((GLfloat)_color[0], (GLfloat)_color[1], (GLfloat)_color[2], 1.0);
110   glClear(GL_COLOR_BUFFER_BIT);
111 }
112 
setMaterial(const Eigen::Vector3d &,const Eigen::Vector3d &,double)113 void OpenGLRenderInterface::setMaterial(
114     const Eigen::Vector3d& /*_diffuse*/,
115     const Eigen::Vector3d& /*_specular*/,
116     double /*_cosinePow*/)
117 {
118 }
119 
getMaterial(Eigen::Vector3d &,Eigen::Vector3d &,double &) const120 void OpenGLRenderInterface::getMaterial(
121     Eigen::Vector3d& /*_diffuse*/,
122     Eigen::Vector3d& /*_specular*/,
123     double& /*_cosinePow*/) const
124 {
125 }
126 
setDefaultMaterial()127 void OpenGLRenderInterface::setDefaultMaterial()
128 {
129 }
130 
pushMatrix()131 void OpenGLRenderInterface::pushMatrix()
132 {
133   glPushMatrix();
134 }
135 
popMatrix()136 void OpenGLRenderInterface::popMatrix()
137 {
138   glPopMatrix();
139 }
140 
pushName(int _id)141 void OpenGLRenderInterface::pushName(int _id)
142 {
143   glPushName(_id);
144 }
145 
popName()146 void OpenGLRenderInterface::popName()
147 {
148   glPopName();
149 }
150 
translate(const Eigen::Vector3d & _offset)151 void OpenGLRenderInterface::translate(const Eigen::Vector3d& _offset)
152 {
153   glTranslated(_offset[0], _offset[1], _offset[2]);
154 }
155 
rotate(const Eigen::Vector3d & _axis,double _rad)156 void OpenGLRenderInterface::rotate(const Eigen::Vector3d& _axis, double _rad)
157 {
158   glRotated(_rad, _axis[0], _axis[1], _axis[2]);
159 }
160 
transform(const Eigen::Isometry3d & _transform)161 void OpenGLRenderInterface::transform(const Eigen::Isometry3d& _transform)
162 {
163   glMultMatrixd(_transform.data());
164 }
165 
scale(const Eigen::Vector3d & _scale)166 void OpenGLRenderInterface::scale(const Eigen::Vector3d& _scale)
167 {
168   glScaled(_scale[0], _scale[1], _scale[2]);
169 }
170 
drawSphere(double radius,int slices,int stacks)171 void OpenGLRenderInterface::drawSphere(double radius, int slices, int stacks)
172 {
173   // Code taken from glut/lib/glut_shapes.c
174   QUAD_OBJ_INIT;
175   gluQuadricDrawStyle(quadObj, GLU_FILL);
176   gluQuadricNormals(quadObj, GLU_SMOOTH);
177   // gluQuadricTexture(quadObj, GL_TRUE);
178 
179   gluSphere(quadObj, radius, slices, stacks);
180 }
181 
drawOpenCylinderConnectingTwoSpheres(OpenGLRenderInterface * ri,const std::pair<double,Eigen::Vector3d> & sphere0,const std::pair<double,Eigen::Vector3d> & sphere1,int slices,int stacks)182 void drawOpenCylinderConnectingTwoSpheres(
183     OpenGLRenderInterface* ri,
184     const std::pair<double, Eigen::Vector3d>& sphere0,
185     const std::pair<double, Eigen::Vector3d>& sphere1,
186     int slices,
187     int stacks)
188 {
189   const auto& r0 = sphere0.first;
190   const auto& r1 = sphere1.first;
191   const Eigen::Vector3d& p0 = sphere0.second;
192   const Eigen::Vector3d& p1 = sphere1.second;
193 
194   const auto dist = (p0 - p1).norm();
195 
196   if (dist < std::numeric_limits<double>::epsilon())
197     return;
198 
199   const Eigen::Vector3d zAxis = (p1 - p0).normalized();
200 
201   const auto r0r1 = r0 - r1;
202   const auto theta = std::acos(r0r1 / dist);
203   const auto baseRadius = r0 * std::sin(theta);
204   const auto topRadius = r1 * std::sin(theta);
205   const Eigen::Vector3d baseCenter = p0 + r0 * std::cos(theta) * zAxis;
206   const Eigen::Vector3d topCenter = p1 + r1 * std::cos(theta) * zAxis;
207   const Eigen::Vector3d center = 0.5 * (baseCenter + topCenter);
208   const auto height = (topCenter - baseCenter).norm();
209   const Eigen::AngleAxisd aa(
210       Eigen::Quaterniond().setFromTwoVectors(Eigen::Vector3d::UnitZ(), zAxis));
211 
212   glPushMatrix();
213   {
214     glTranslated(center.x(), center.y(), center.z());
215     glRotated(
216         math::toDegree(aa.angle()),
217         aa.axis().x(),
218         aa.axis().y(),
219         aa.axis().z());
220 
221     ri->drawOpenCylinder(baseRadius, topRadius, height, slices, stacks);
222   }
223   glPopMatrix();
224 }
225 
drawMultiSphere(const std::vector<std::pair<double,Eigen::Vector3d>> & spheres,int slices,int stacks)226 void OpenGLRenderInterface::drawMultiSphere(
227     const std::vector<std::pair<double, Eigen::Vector3d>>& spheres,
228     int slices,
229     int stacks)
230 {
231   // Draw spheres
232   for (const auto& sphere : spheres)
233   {
234     glPushMatrix();
235     {
236       glTranslated(sphere.second.x(), sphere.second.y(), sphere.second.z());
237       drawSphere(sphere.first, slices, stacks);
238     }
239     glPopMatrix();
240   }
241 }
242 
drawMultiSphereConvexHull(const std::vector<std::pair<double,Eigen::Vector3d>> & spheres,std::size_t subdivisions)243 void OpenGLRenderInterface::drawMultiSphereConvexHull(
244     const std::vector<std::pair<double, Eigen::Vector3d>>& spheres,
245     std::size_t subdivisions)
246 {
247   // Create meshes of sphere and combine them into a single mesh
248   auto mesh = math::TriMeshf();
249   for (const auto& sphere : spheres)
250   {
251     const double& radius = sphere.first;
252     const Eigen::Vector3d& center = sphere.second;
253 
254     auto icosphere = math::Icospheref(radius, subdivisions);
255     icosphere.translate(center.cast<float>());
256 
257     mesh += icosphere;
258   }
259 
260   // Create a convex hull from the combined mesh
261   auto convexHull = mesh.generateConvexHull();
262   convexHull->computeVertexNormals();
263   const auto& meshVertices = convexHull->getVertices();
264   const auto& meshNormals = convexHull->getVertexNormals();
265   const auto& meshTriangles = convexHull->getTriangles();
266   assert(meshVertices.size() == meshNormals.size());
267 
268   // Draw the triangles of the convex hull
269   glBegin(GL_TRIANGLES);
270   for (const auto& triangle : meshTriangles)
271   {
272     for (auto i = 0u; i < 3; ++i)
273     {
274       const auto& normal = meshNormals[triangle[i]];
275       const auto& vertex = meshVertices[triangle[i]];
276       glNormal3fv(normal.data());
277       glVertex3fv(vertex.data());
278     }
279   }
280   glEnd();
281 }
282 
drawEllipsoid(const Eigen::Vector3d & _diameters)283 void OpenGLRenderInterface::drawEllipsoid(const Eigen::Vector3d& _diameters)
284 {
285   glScaled(_diameters(0), _diameters(1), _diameters(2));
286 
287   drawSphere(0.5);
288 }
289 
drawCube(const Eigen::Vector3d & _size)290 void OpenGLRenderInterface::drawCube(const Eigen::Vector3d& _size)
291 {
292   glScaled(_size(0), _size(1), _size(2));
293 
294   // Code taken from glut/lib/glut_shapes.c
295   static GLfloat n[6][3] = {{-1.0, 0.0, 0.0},
296                             {0.0, 1.0, 0.0},
297                             {1.0, 0.0, 0.0},
298                             {0.0, -1.0, 0.0},
299                             {0.0, 0.0, 1.0},
300                             {0.0, 0.0, -1.0}};
301   static GLint faces[6][4] = {{0, 1, 2, 3},
302                               {3, 2, 6, 7},
303                               {7, 6, 5, 4},
304                               {4, 5, 1, 0},
305                               {5, 6, 2, 1},
306                               {7, 4, 0, 3}};
307   GLfloat v[8][3];
308   GLint i;
309   GLfloat size = 1;
310 
311   v[0][0] = v[1][0] = v[2][0] = v[3][0] = -size / 2;
312   v[4][0] = v[5][0] = v[6][0] = v[7][0] = size / 2;
313   v[0][1] = v[1][1] = v[4][1] = v[5][1] = -size / 2;
314   v[2][1] = v[3][1] = v[6][1] = v[7][1] = size / 2;
315   v[0][2] = v[3][2] = v[4][2] = v[7][2] = -size / 2;
316   v[1][2] = v[2][2] = v[5][2] = v[6][2] = size / 2;
317 
318   for (i = 5; i >= 0; i--)
319   {
320     glBegin(GL_QUADS);
321     glNormal3fv(&n[i][0]);
322     glVertex3fv(&v[faces[i][0]][0]);
323     glVertex3fv(&v[faces[i][1]][0]);
324     glVertex3fv(&v[faces[i][2]][0]);
325     glVertex3fv(&v[faces[i][3]][0]);
326     glEnd();
327   }
328   // glut/lib/glut_shapes.c
329 }
330 
331 //==============================================================================
drawOpenCylinder(double baseRadius,double topRadius,double height,int slices,int stacks)332 void OpenGLRenderInterface::drawOpenCylinder(
333     double baseRadius, double topRadius, double height, int slices, int stacks)
334 {
335   glPushMatrix();
336 
337   // Graphics assumes Cylinder is centered at CoM
338   // gluCylinder places base at z = 0 and top at z = height
339   glTranslated(0.0, 0.0, -0.5 * height);
340 
341   // Code taken from glut/lib/glut_shapes.c
342   QUAD_OBJ_INIT;
343   gluQuadricDrawStyle(quadObj, GLU_FILL);
344   gluQuadricNormals(quadObj, GLU_SMOOTH);
345   // gluQuadricTexture(quadObj, GL_TRUE);
346 
347   // glut/lib/glut_shapes.c
348   gluCylinder(quadObj, baseRadius, topRadius, height, slices, stacks);
349 
350   glPopMatrix();
351 }
352 
353 //==============================================================================
drawCylinder(double radius,double height,int slices,int stacks)354 void OpenGLRenderInterface::drawCylinder(
355     double radius, double height, int slices, int stacks)
356 {
357   drawOpenCylinder(radius, radius, height, slices, stacks);
358 
359   glPushMatrix();
360 
361   glScaled(radius, radius, height);
362 
363   QUAD_OBJ_INIT;
364   gluQuadricDrawStyle(quadObj, GLU_FILL);
365   gluQuadricNormals(quadObj, GLU_SMOOTH);
366   // gluQuadricTexture(quadObj, GL_TRUE);
367 
368   glTranslated(0.0, 0.0, 0.5);
369   gluDisk(quadObj, 0, 1, slices, stacks);
370   glTranslated(0.0, 0.0, -1.0);
371   gluDisk(quadObj, 0, 1, slices, stacks);
372 
373   glPopMatrix();
374 }
375 
376 //==============================================================================
drawOpenDome(double radius,int slices,int stacks)377 static void drawOpenDome(double radius, int slices, int stacks)
378 {
379   // (2pi/Stacks)
380   const auto pi = dart::math::constants<double>::pi();
381   const auto drho = pi / stacks / 2.0;
382   const auto dtheta = 2.0 * pi / slices;
383 
384   const auto rho = drho;
385   const auto srho = std::sin(rho);
386   const auto crho = std::cos(rho);
387 
388   // Many sources of OpenGL sphere drawing code uses a triangle fan
389   // for the caps of the sphere. This however introduces texturing
390   // artifacts at the poles on some OpenGL implementations
391   glBegin(GL_TRIANGLE_FAN);
392   glNormal3d(0.0, 0.0, radius);
393   glVertex3d(0.0, 0.0, radius);
394   for (int j = 0; j <= slices; ++j)
395   {
396     const auto theta = (j == slices) ? 0.0 : j * dtheta;
397     const auto stheta = -std::sin(theta);
398     const auto ctheta = std::cos(theta);
399 
400     const auto x = srho * stheta;
401     const auto y = srho * ctheta;
402     const auto z = crho;
403 
404     glNormal3d(x, y, z);
405     glVertex3d(x * radius, y * radius, z * radius);
406   }
407   glEnd();
408 
409   for (int i = 1; i < stacks; ++i)
410   {
411     const auto rho = i * drho;
412     const auto srho = std::sin(rho);
413     const auto crho = std::cos(rho);
414     const auto srhodrho = std::sin(rho + drho);
415     const auto crhodrho = std::cos(rho + drho);
416 
417     // Many sources of OpenGL sphere drawing code uses a triangle fan
418     // for the caps of the sphere. This however introduces texturing
419     // artifacts at the poles on some OpenGL implementations
420     glBegin(GL_TRIANGLE_STRIP);
421 
422     for (int j = 0; j <= slices; ++j)
423     {
424       const auto theta = (j == slices) ? 0.0 : j * dtheta;
425       const auto stheta = -std::sin(theta);
426       const auto ctheta = std::cos(theta);
427 
428       auto x = srho * stheta;
429       auto y = srho * ctheta;
430       auto z = crho;
431 
432       glNormal3d(x, y, z);
433       glVertex3d(x * radius, y * radius, z * radius);
434 
435       x = srhodrho * stheta;
436       y = srhodrho * ctheta;
437       z = crhodrho;
438 
439       glNormal3d(x, y, z);
440       glVertex3d(x * radius, y * radius, z * radius);
441     }
442     glEnd();
443   }
444 }
445 
446 //==============================================================================
drawCapsule(double radius,double height)447 void OpenGLRenderInterface::drawCapsule(double radius, double height)
448 {
449   GLint slices = 16;
450   GLint stacks = 16;
451 
452   // Graphics assumes Cylinder is centered at CoM
453   // gluCylinder places base at z = 0 and top at z = height
454   glTranslated(0.0, 0.0, -0.5 * height);
455 
456   // Code taken from glut/lib/glut_shapes.c
457   QUAD_OBJ_INIT;
458   gluQuadricDrawStyle(quadObj, GLU_FILL);
459   gluQuadricNormals(quadObj, GLU_SMOOTH);
460 
461   gluCylinder(
462       quadObj,
463       radius,
464       radius,
465       height,
466       slices,
467       stacks); // glut/lib/glut_shapes.c
468 
469   // Upper hemisphere
470   glTranslated(0.0, 0.0, height);
471   drawOpenDome(radius, slices, stacks);
472 
473   // Lower hemisphere
474   glTranslated(0.0, 0.0, -height);
475   glRotated(180.0, 0.0, 1.0, 0.0);
476   drawOpenDome(radius, slices, stacks);
477 }
478 
479 //==============================================================================
drawCone(double radius,double height)480 void OpenGLRenderInterface::drawCone(double radius, double height)
481 {
482   GLint slices = 16;
483   GLint stacks = 16;
484 
485   // Graphics assumes Cylinder is centered at CoM
486   // gluCylinder places base at z = 0 and top at z = height
487   glTranslated(0.0, 0.0, -0.5 * height);
488 
489   // Code taken from glut/lib/glut_shapes.c
490   QUAD_OBJ_INIT;
491   gluQuadricDrawStyle(quadObj, GLU_FILL);
492   gluQuadricNormals(quadObj, GLU_SMOOTH);
493 
494   gluCylinder(
495       quadObj, radius, 0.0, height, slices, stacks); // glut/lib/glut_shapes.c
496   gluDisk(quadObj, 0, radius, slices, stacks);
497 }
498 
499 //==============================================================================
computeNormal(const Eigen::Vector3d & v1,const Eigen::Vector3d & v2,const Eigen::Vector3d & v3)500 Eigen::Vector3d computeNormal(
501     const Eigen::Vector3d& v1,
502     const Eigen::Vector3d& v2,
503     const Eigen::Vector3d& v3)
504 {
505   return (v1 - v2).cross(v2 - v3).normalized();
506 }
507 
508 //==============================================================================
drawPyramid(double baseWidth,double baseDepth,double height)509 void OpenGLRenderInterface::drawPyramid(
510     double baseWidth, double baseDepth, double height)
511 {
512   const double w = baseWidth;
513   const double d = baseDepth;
514   const double h = height;
515 
516   const double hTop = h / 2;
517   const double hBottom = -hTop;
518   const double left = -w / 2;
519   const double right = w / 2;
520   const double front = -d / 2;
521   const double back = d / 2;
522 
523   std::vector<Eigen::Vector3d> points(5);
524   std::vector<Eigen::Vector3i> faces(6);
525 
526   points[0] << 0, 0, hTop;
527   points[1] << right, back, hBottom;
528   points[2] << left, back, hBottom;
529   points[3] << left, front, hBottom;
530   points[4] << right, front, hBottom;
531 
532   faces[0] << 0, 1, 2;
533   faces[1] << 0, 2, 3;
534   faces[2] << 0, 3, 4;
535   faces[3] << 0, 4, 1;
536   faces[4] << 1, 3, 2;
537   faces[5] << 1, 4, 3;
538 
539   glBegin(GL_TRIANGLES);
540   for (const auto& face : faces)
541   {
542     const auto& p1 = points[static_cast<size_t>(face[0])];
543     const auto& p2 = points[static_cast<size_t>(face[1])];
544     const auto& p3 = points[static_cast<size_t>(face[2])];
545     const Eigen::Vector3d n = computeNormal(p1, p2, p3);
546 
547     glNormal3dv(n.data());
548     glVertex3dv(p1.data());
549     glVertex3dv(p2.data());
550     glVertex3dv(p3.data());
551   }
552   glEnd();
553 }
554 
color4_to_float4(const aiColor4D * c,float f[4])555 void OpenGLRenderInterface::color4_to_float4(const aiColor4D* c, float f[4])
556 {
557   f[0] = c->r;
558   f[1] = c->g;
559   f[2] = c->b;
560   f[3] = c->a;
561 }
562 
set_float4(float f[4],float a,float b,float c,float d)563 void OpenGLRenderInterface::set_float4(
564     float f[4], float a, float b, float c, float d)
565 {
566   f[0] = a;
567   f[1] = b;
568   f[2] = c;
569   f[3] = d;
570 }
571 
572 // This function is taken from the examples coming with assimp
applyMaterial(const struct aiMaterial * mtl)573 void OpenGLRenderInterface::applyMaterial(const struct aiMaterial* mtl)
574 {
575   float c[4];
576 
577   GLenum fill_mode;
578   int ret1;
579   aiColor4D diffuse;
580   aiColor4D specular;
581   aiColor4D ambient;
582   aiColor4D emission;
583   float shininess, strength;
584   int two_sided;
585   int wireframe;
586   unsigned int max;
587 
588   set_float4(c, 0.8f, 0.8f, 0.8f, 1.0f);
589   if (AI_SUCCESS == aiGetMaterialColor(mtl, AI_MATKEY_COLOR_DIFFUSE, &diffuse))
590     color4_to_float4(&diffuse, c);
591   glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, c);
592 
593   set_float4(c, 0.0f, 0.0f, 0.0f, 1.0f);
594   if (AI_SUCCESS
595       == aiGetMaterialColor(mtl, AI_MATKEY_COLOR_SPECULAR, &specular))
596     color4_to_float4(&specular, c);
597   glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, c);
598 
599   set_float4(c, 0.2f, 0.2f, 0.2f, 1.0f);
600   if (AI_SUCCESS == aiGetMaterialColor(mtl, AI_MATKEY_COLOR_AMBIENT, &ambient))
601     color4_to_float4(&ambient, c);
602   glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, c);
603 
604   set_float4(c, 0.0f, 0.0f, 0.0f, 1.0f);
605   if (AI_SUCCESS
606       == aiGetMaterialColor(mtl, AI_MATKEY_COLOR_EMISSIVE, &emission))
607     color4_to_float4(&emission, c);
608   glMaterialfv(GL_FRONT_AND_BACK, GL_EMISSION, c);
609 
610   max = 1;
611   ret1 = aiGetMaterialFloatArray(mtl, AI_MATKEY_SHININESS, &shininess, &max);
612   if (ret1 == AI_SUCCESS)
613   {
614     max = 1;
615     const int ret2 = aiGetMaterialFloatArray(
616         mtl, AI_MATKEY_SHININESS_STRENGTH, &strength, &max);
617     if (ret2 == AI_SUCCESS)
618       glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, shininess * strength);
619     else
620       glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, shininess);
621   }
622   else
623   {
624     glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, 0.0f);
625     set_float4(c, 0.0f, 0.0f, 0.0f, 0.0f);
626     glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, c);
627   }
628 
629   max = 1;
630   if (AI_SUCCESS
631       == aiGetMaterialIntegerArray(
632              mtl, AI_MATKEY_ENABLE_WIREFRAME, &wireframe, &max))
633     fill_mode = wireframe ? GL_LINE : GL_FILL;
634   else
635     fill_mode = GL_FILL;
636   glPolygonMode(GL_FRONT_AND_BACK, fill_mode);
637 
638   max = 1;
639   if ((AI_SUCCESS
640        == aiGetMaterialIntegerArray(mtl, AI_MATKEY_TWOSIDED, &two_sided, &max))
641       && two_sided)
642     glEnable(GL_CULL_FACE);
643   else
644     glDisable(GL_CULL_FACE);
645 }
646 
647 // This function is taken from the examples coming with assimp
recursiveRender(const struct aiScene * sc,const struct aiNode * nd)648 void OpenGLRenderInterface::recursiveRender(
649     const struct aiScene* sc, const struct aiNode* nd)
650 {
651   unsigned int i;
652   unsigned int n = 0, t;
653   aiMatrix4x4 m = nd->mTransformation;
654 
655   // update transform
656   aiTransposeMatrix4(&m);
657   glPushMatrix();
658   glMultMatrixf((float*)&m);
659 
660   // draw all meshes assigned to this node
661   for (; n < nd->mNumMeshes; ++n)
662   {
663     const struct aiMesh* mesh = sc->mMeshes[nd->mMeshes[n]];
664 
665     glPushAttrib(GL_POLYGON_BIT | GL_LIGHTING_BIT); // for applyMaterial()
666     if (mesh->mMaterialIndex
667         != (unsigned int)(-1)) // -1 is being used by us to indicate no material
668       applyMaterial(sc->mMaterials[mesh->mMaterialIndex]);
669 
670     if (mesh->mNormals == nullptr)
671     {
672       glDisable(GL_LIGHTING);
673     }
674     else
675     {
676       glEnable(GL_LIGHTING);
677     }
678 
679     for (t = 0; t < mesh->mNumFaces; ++t)
680     {
681       const struct aiFace* face = &mesh->mFaces[t];
682       GLenum face_mode;
683 
684       switch (face->mNumIndices)
685       {
686         case 1:
687           face_mode = GL_POINTS;
688           break;
689         case 2:
690           face_mode = GL_LINES;
691           break;
692         case 3:
693           face_mode = GL_TRIANGLES;
694           break;
695         default:
696           face_mode = GL_POLYGON;
697           break;
698       }
699 
700       glBegin(face_mode);
701 
702       for (i = 0; i < face->mNumIndices; i++)
703       {
704         int index = face->mIndices[i];
705         if (mesh->mColors[0] != nullptr)
706           glColor4fv((GLfloat*)&mesh->mColors[0][index]);
707         if (mesh->mNormals != nullptr)
708           glNormal3fv(&mesh->mNormals[index].x);
709         glVertex3fv(&mesh->mVertices[index].x);
710       }
711 
712       glEnd();
713     }
714 
715     glPopAttrib(); // for applyMaterial()
716   }
717 
718   // draw all children
719   for (n = 0; n < nd->mNumChildren; ++n)
720   {
721     recursiveRender(sc, nd->mChildren[n]);
722   }
723 
724   glPopMatrix();
725 }
726 
727 //==============================================================================
drawMesh(const Eigen::Vector3d & scale,const aiScene * mesh)728 void OpenGLRenderInterface::drawMesh(
729     const Eigen::Vector3d& scale, const aiScene* mesh)
730 {
731   if (!mesh)
732     return;
733 
734   glPushMatrix();
735 
736   glScaled(scale[0], scale[1], scale[2]);
737   recursiveRender(mesh, mesh->mRootNode);
738 
739   glPopMatrix();
740 }
741 
742 //==============================================================================
drawSoftMesh(const aiMesh * mesh)743 void OpenGLRenderInterface::drawSoftMesh(const aiMesh* mesh)
744 {
745   glEnable(GL_LIGHTING);
746   glEnable(GL_AUTO_NORMAL);
747   glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
748 
749   for (auto i = 0u; i < mesh->mNumFaces; ++i)
750   {
751     glBegin(GL_TRIANGLES);
752 
753     const auto& face = &mesh->mFaces[i];
754     assert(3u == face->mNumIndices);
755 
756     for (auto j = 0u; j < 3; ++j)
757     {
758       auto index = face->mIndices[j];
759       glNormal3fv(&mesh->mVertices[index].x);
760       glVertex3fv(&mesh->mVertices[index].x);
761     }
762 
763     glEnd();
764   }
765 }
766 
drawList(GLuint index)767 void OpenGLRenderInterface::drawList(GLuint index)
768 {
769   glCallList(index);
770 }
771 
drawLineSegments(const std::vector<Eigen::Vector3d> & _vertices,const common::aligned_vector<Eigen::Vector2i> & _connections)772 void OpenGLRenderInterface::drawLineSegments(
773     const std::vector<Eigen::Vector3d>& _vertices,
774     const common::aligned_vector<Eigen::Vector2i>& _connections)
775 {
776   glBegin(GL_LINES);
777   for (const Eigen::Vector2i& c : _connections)
778   {
779     const Eigen::Vector3d& v1 = _vertices[c[0]];
780     const Eigen::Vector3d& v2 = _vertices[c[1]];
781     glVertex3f(v1[0], v1[1], v1[2]);
782     glVertex3f(v2[0], v2[1], v2[2]);
783   }
784   glEnd();
785 }
786 
787 //==============================================================================
compileList(dynamics::Skeleton * _skel)788 void OpenGLRenderInterface::compileList(dynamics::Skeleton* _skel)
789 {
790   if (_skel == 0)
791     return;
792 
793   for (std::size_t i = 0; i < _skel->getNumBodyNodes(); i++)
794   {
795     compileList(_skel->getBodyNode(i));
796   }
797 }
798 
799 //==============================================================================
compileList(dynamics::BodyNode * node)800 void OpenGLRenderInterface::compileList(dynamics::BodyNode* node)
801 {
802   if (node == 0)
803     return;
804 
805   for (auto childFrame : node->getChildFrames())
806   {
807     auto shapeFrame = dynamic_cast<dynamics::ShapeFrame*>(childFrame);
808     if (shapeFrame)
809       compileList(shapeFrame->getShape().get());
810   }
811 
812   for (auto i = 0u; i < node->getNumNodes<dynamics::ShapeNode>(); ++i)
813   {
814     auto shapeNode = node->getNode<dynamics::ShapeNode>(i);
815     compileList(shapeNode->getShape().get());
816   }
817 }
818 
819 //==============================================================================
compileList(dynamics::Shape * shape)820 void OpenGLRenderInterface::compileList(dynamics::Shape* shape)
821 {
822   if (!shape)
823     return;
824 
825   if (shape->getType() == dynamics::MeshShape::getStaticType())
826   {
827     assert(dynamic_cast<dynamics::MeshShape*>(shape));
828 
829     auto* mesh = static_cast<dynamics::MeshShape*>(shape);
830     mesh->setDisplayList(compileList(mesh->getScale(), mesh->getMesh()));
831   }
832   else
833   {
834     dtwarn << "[OpenGLRenderInterface::compileList] Attempting to compile "
835            << "OpenGL list for an unsupported shape type [" << shape->getType()
836            << "].\n";
837   }
838 }
839 
compileList(const Eigen::Vector3d & _scale,const aiScene * _mesh)840 GLuint OpenGLRenderInterface::compileList(
841     const Eigen::Vector3d& _scale, const aiScene* _mesh)
842 {
843   if (!_mesh)
844     return 0;
845 
846   // Generate one list
847   GLuint index = glGenLists(1);
848   // Compile list
849   glNewList(index, GL_COMPILE);
850   drawMesh(_scale, _mesh);
851   glEndList();
852 
853   return index;
854 }
855 
setPenColor(const Eigen::Vector4d & _col)856 void OpenGLRenderInterface::setPenColor(const Eigen::Vector4d& _col)
857 {
858   glColor4d(_col[0], _col[1], _col[2], _col[3]);
859 }
860 
setPenColor(const Eigen::Vector3d & _col)861 void OpenGLRenderInterface::setPenColor(const Eigen::Vector3d& _col)
862 {
863   glColor4d(_col[0], _col[1], _col[2], 1.0);
864 }
865 
setLineWidth(float _width)866 void OpenGLRenderInterface::setLineWidth(float _width)
867 {
868   glLineWidth(_width);
869 }
870 
readFrameBuffer(DecoBufferType,DecoColorChannel,void *)871 void OpenGLRenderInterface::readFrameBuffer(
872     DecoBufferType /*_buffType*/, DecoColorChannel /*_ch*/, void* /*_pixels*/)
873 {
874 }
875 
saveToImage(const char *,DecoBufferType)876 void OpenGLRenderInterface::saveToImage(
877     const char* /*_filename*/, DecoBufferType /*_buffType*/)
878 {
879 }
880 
881 } // namespace gui
882 } // namespace dart
883