38 #include <geometric_shapes/shapes.h>
40 #include <Eigen/Eigen>
43 using namespace Eigen;
48 if (!mesh.vertex_normals)
50 throw std::runtime_error(
"Vertex normals are not computed for input mesh. Call computeVertexNormals() before "
51 "passing as input to mesh_filter.");
54 mesh_label_ = mesh_label;
55 list_ = glGenLists(1);
56 glNewList(list_, GL_COMPILE);
57 glBegin(GL_TRIANGLES);
58 glColor4ubv(
reinterpret_cast<GLubyte*
>(&mesh_label_));
59 for (
unsigned t_idx = 0; t_idx < mesh.triangle_count; ++t_idx)
61 unsigned v1 = 3 * mesh.triangles[3 * t_idx];
62 unsigned v2 = 3 * mesh.triangles[3 * t_idx + 1];
63 unsigned v3 = 3 * mesh.triangles[3 * t_idx + 2];
65 glNormal3f(mesh.vertex_normals[v1], mesh.vertex_normals[v1 + 1], mesh.vertex_normals[v1 + 2]);
66 glVertex3f(mesh.vertices[v1], mesh.vertices[v1 + 1], mesh.vertices[v1 + 2]);
68 glNormal3f(mesh.vertex_normals[v2], mesh.vertex_normals[v2 + 1], mesh.vertex_normals[v2 + 2]);
69 glVertex3f(mesh.vertices[v2], mesh.vertices[v2 + 1], mesh.vertices[v2 + 2]);
71 glNormal3f(mesh.vertex_normals[v3], mesh.vertex_normals[v3 + 1], mesh.vertex_normals[v3 + 2]);
72 glVertex3f(mesh.vertices[v3], mesh.vertices[v3 + 1], mesh.vertices[v3 + 2]);
80 glDeleteLists(list_, 1);
85 glMatrixMode(GL_MODELVIEW);
87 if (!(transform.matrix().Flags & RowMajorBit))
89 glMultMatrixd(transform.matrix().data());
93 glMultTransposeMatrixd(transform.matrix().data());
void render(const Eigen::Isometry3d &transform) const
renders the mesh in current OpenGL frame buffer (context)
GLMesh(const shapes::Mesh &mesh, unsigned int mesh_label)
Constructs a GLMesh object for given mesh and label.