GLshape.cpp
Go to the documentation of this file.
00001 #include <iostream>
00002 #include <deque>
00003 #ifdef __APPLE__
00004 #include <OpenGL/glu.h>
00005 #else
00006 #include <GL/glu.h>
00007 #endif
00008 #include "GLutil.h"
00009 #include "GLlink.h"
00010 #include "GLshape.h"
00011 #include "GLtexture.h"
00012 
00013 GLshape::GLshape() : m_shininess(0.2), m_texture(NULL), m_requestCompile(false), m_shadingList(0), m_wireFrameList(0), m_highlight(false)
00014 {
00015     for (int i=0; i<16; i++) m_trans[i] = 0.0;
00016     m_trans[0] = m_trans[5] = m_trans[10] = m_trans[15] = 1.0;
00017     for (int i=0; i<4; i++) m_specular[i] = 0;
00018 }
00019 
00020 GLshape::~GLshape()
00021 {
00022     if (m_texture){
00023         if (m_texture->image.size()) glDeleteTextures(1, &m_textureId);
00024         delete m_texture;
00025     }
00026     if (m_shadingList) glDeleteLists(m_shadingList, 1);
00027     if (m_wireFrameList) glDeleteLists(m_wireFrameList, 1);
00028 }
00029 
00030 size_t GLshape::draw(int i_mode)
00031 {
00032     glPushMatrix();
00033     glMultMatrixd(m_trans);
00034     if (m_requestCompile){
00035         m_shadingList = doCompile(false);
00036         m_wireFrameList = doCompile(true);
00037         m_requestCompile = false;
00038     } 
00039     glCallList(i_mode == GLlink::DM_SOLID ? m_shadingList : m_wireFrameList);
00040     glPopMatrix();
00041     return m_triangles.size();
00042 }
00043 
00044 void GLshape::setVertices(unsigned int nvertices, const float *vertices)
00045 {
00046     m_vertices.resize(nvertices);
00047     for (size_t i=0; i<nvertices; i++){
00048         m_vertices[i] = Eigen::Vector3f(vertices[i*3  ], 
00049                                         vertices[i*3+1], 
00050                                         vertices[i*3+2]);
00051     }
00052 }
00053 
00054 void GLshape::setTriangles(unsigned int ntriangles, const int *vertexIndices)
00055 {
00056     m_triangles.resize(ntriangles);
00057     for (size_t i=0; i<ntriangles; i++){
00058         m_triangles[i] = Eigen::Vector3i(vertexIndices[i*3  ],
00059                                          vertexIndices[i*3+1],
00060                                          vertexIndices[i*3+2]);
00061     }
00062 }
00063 
00064 void GLshape::setNormals(unsigned int nnormal, const float *normals)
00065 {
00066     m_normals.resize(nnormal);
00067     for (size_t i=0; i<nnormal; i++){
00068         m_normals[i] = Eigen::Vector3f(normals[i*3  ],
00069                                        normals[i*3+1],
00070                                        normals[i*3+2]);
00071     }
00072 }
00073 
00074 void GLshape::setDiffuseColor(float r, float g, float b, float a)
00075 {
00076     m_diffuse[0] = r; m_diffuse[1] = g; m_diffuse[2] = b; m_diffuse[3] = a; 
00077 }
00078 
00079 void GLshape::setColors(unsigned int ncolors, const float *colors)
00080 {
00081     m_colors.resize(ncolors);
00082     for (size_t i=0; i<ncolors; i++){
00083         m_colors[i] = Eigen::Vector3f(colors[i*3  ], 
00084                                       colors[i*3+1], 
00085                                       colors[i*3+2]);
00086     }
00087 }
00088 
00089 void GLshape::normalPerVertex(bool flag)
00090 {
00091     m_normalPerVertex = flag;
00092 }
00093 
00094 void GLshape::solid(bool flag)
00095 {
00096     m_solid = flag;
00097 }
00098 
00099 void GLshape::setNormalIndices(unsigned int len, const int *normalIndices)
00100 {
00101     m_normalIndices.resize(len);
00102     for (size_t i=0; i<len; i++){
00103         m_normalIndices[i] = normalIndices[i];
00104     }
00105 }
00106 
00107 void GLshape::setTextureCoordinates(unsigned int ncoords, const float *coordinates)
00108 {
00109     m_textureCoordinates.resize(ncoords);
00110     for (size_t i=0; i<ncoords; i++){
00111         m_textureCoordinates[i] = Eigen::Vector2f(coordinates[i*2  ],
00112                                                   coordinates[i*2+1]);
00113     }
00114 }
00115 
00116 void GLshape::setTextureCoordIndices(unsigned int len, const int *coordIndices)
00117 {
00118     m_textureCoordIndices.resize(len);
00119     for (size_t i=0; i<len; i++){
00120         m_textureCoordIndices[i] = coordIndices[i];
00121     }
00122 }
00123 
00124 void GLshape::setTexture(GLtexture *texture)
00125 {
00126     m_texture = texture;
00127 }
00128 
00129 void GLshape::compile()
00130 {
00131     m_requestCompile = true;
00132 }
00133 
00134 int GLshape::doCompile(bool isWireFrameMode)
00135 {
00136     if (isWireFrameMode){
00137         if (m_wireFrameList) glDeleteLists(m_wireFrameList, 1);
00138     }else{
00139         if (m_shadingList) glDeleteLists(m_shadingList, 1);
00140     }
00141 
00142     //std::cout << "doCompile" << std::endl;
00143     int list = glGenLists(1);
00144     glNewList(list, GL_COMPILE);
00145 
00146     if (m_solid){
00147         glEnable(GL_CULL_FACE);
00148     }else{
00149         glDisable(GL_CULL_FACE);
00150     }
00151     double scale[3];
00152     for (int i=0; i<3; i++){
00153         scale[i] = sqrt(m_trans[i]*m_trans[i]
00154                         +m_trans[i+4]*m_trans[i+4]
00155                         +m_trans[i+8]*m_trans[i+8]);
00156     }
00157 
00158     bool drawTexture = false;
00159     if (!isWireFrameMode && m_texture && !m_highlight){
00160         drawTexture = true;
00161         glGenTextures(1, &m_textureId);
00162         glBindTexture(GL_TEXTURE_2D, m_textureId);
00163         
00164         if (m_texture->repeatS){
00165             glTexParameteri(GL_TEXTURE_2D, 
00166                             GL_TEXTURE_WRAP_S, GL_REPEAT);
00167         }else{
00168             glTexParameteri(GL_TEXTURE_2D, 
00169                             GL_TEXTURE_WRAP_S, GL_CLAMP);
00170         }
00171         if (m_texture->repeatT){
00172             glTexParameteri(GL_TEXTURE_2D,
00173                             GL_TEXTURE_WRAP_T, GL_REPEAT);
00174         }else{
00175             glTexParameteri(GL_TEXTURE_2D,
00176                             GL_TEXTURE_WRAP_T, GL_CLAMP);
00177         }
00178         int format;
00179         if (m_texture->numComponents == 3){
00180             format = GL_RGB;
00181         }else if (m_texture->numComponents == 4){
00182             format = GL_RGBA;
00183         }
00184         glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
00185         gluBuild2DMipmaps(GL_TEXTURE_2D, 3, 
00186                           m_texture->width, m_texture->height, 
00187                           format, GL_UNSIGNED_BYTE, 
00188                           &m_texture->image[0]);
00189         
00190         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, 
00191                         GL_LINEAR_MIPMAP_LINEAR);
00192         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, 
00193                         GL_LINEAR);
00194         glTexEnvi(GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_REPLACE);
00195         
00196         glEnable(GL_TEXTURE_2D);
00197     }
00198     
00199     if (!isWireFrameMode) glBegin(GL_TRIANGLES);
00200     if (m_highlight){
00201         float red[] = {1,0,0,1};
00202         glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, red);
00203     }else{
00204         glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, m_diffuse);
00205         //glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR,            m_specular);
00206         glMaterialf (GL_FRONT_AND_BACK, GL_SHININESS,           m_shininess);
00207     }
00208     for(size_t j=0; j < m_triangles.size(); ++j){
00209         if (isWireFrameMode) glBegin(GL_LINE_LOOP);
00210         if (!m_normalPerVertex){
00211             unsigned int p;
00212             if (m_normalIndices.size() == 0){
00213                 p = j;
00214             }else{
00215                 p = m_normalIndices[j];
00216             }
00217             if (p < m_normals.size()){
00218                 const Eigen::Vector3f &n = m_normals[p];
00219                 glNormal3f(scale[0]*n[0], scale[1]*n[1], scale[2]*n[2]);
00220             }
00221         }
00222         for(int k=0; k < 3; ++k){
00223             long vertexIndex = m_triangles[j][k];
00224             if (m_normalPerVertex){
00225                 int p;
00226                 if (m_normalIndices.size() == 0){
00227                     p = vertexIndex;
00228                 }else{
00229                     p = m_normalIndices[j*3+k];
00230                 }
00231                 const Eigen::Vector3f &n = m_normals[p];
00232                 glNormal3f(scale[0]*n[0], scale[1]*n[1], scale[2]*n[2]);
00233             }
00234             if (drawTexture){
00235                 int texCoordIndex = m_textureCoordIndices[j*3+k];
00236                 glTexCoord2d(m_textureCoordinates[texCoordIndex][0],
00237                              -m_textureCoordinates[texCoordIndex][1]);
00238             }
00239             glVertex3fv(m_vertices[vertexIndex].data());
00240         }
00241         if (isWireFrameMode) glEnd(); // GL_LINE_LOOP
00242     }
00243     if (!isWireFrameMode) glEnd(); // GL_TRIANGLES
00244     if (drawTexture) glDisable(GL_TEXTURE_2D);
00245 
00246     // point cloud
00247     if (!m_triangles.size()&&m_vertices.size()){
00248         glPointSize(3);
00249         glDisable(GL_LIGHTING);
00250         glBegin(GL_POINTS);
00251         for (size_t i=0; i<m_vertices.size(); i++){
00252             if (m_colors.size()>=m_vertices.size()) 
00253                 glColor3fv(m_colors[i].data());
00254             glVertex3fv(m_vertices[i].data());
00255         }
00256         glEnd();
00257         glEnable(GL_LIGHTING);
00258     }
00259     glEndList();
00260 
00261     return list;
00262 }
00263 
00264 void GLshape::setShininess(float s)
00265 {
00266     m_shininess = s;
00267 }
00268 
00269 void GLshape::setSpecularColor(float r, float g, float b)
00270 {
00271     m_specular[0] = r; m_specular[1] = g; m_specular[2] = b; 
00272 }
00273 
00274 
00275 void GLshape::highlight(bool flag)
00276 {
00277     if (m_highlight != flag) compile();
00278     m_highlight = flag;
00279 }
00280 
00281 void GLshape::divideLargeTriangles(double maxEdgeLen)
00282 {
00283     std::vector<Eigen::Vector3i> new_triangles;
00284     std::vector<int> new_normalIndices, new_textureCoordIndices;
00285     
00286     double scale[3];
00287     for (int i=0; i<3; i++){
00288         scale[i] = sqrt(m_trans[i]*m_trans[i]
00289                         +m_trans[i+4]*m_trans[i+4]
00290                         +m_trans[i+8]*m_trans[i+8]);
00291     }
00292     //std::cout << "normal per vertex:" << m_normalPerVertex << std::endl;
00293     for (size_t i=0; i<m_triangles.size(); i++){
00294         std::deque<Eigen::Vector3i> dq_triangles;
00295         dq_triangles.push_back(m_triangles[i]);
00296         std::deque<Eigen::Vector3i> dq_normals;
00297         Eigen::Vector3i n;
00298         if (m_normalPerVertex){
00299             for (int j=0; j<3; j++){
00300                 if (m_normalIndices.size() == 0){
00301                     n[j] = m_triangles[i][j];
00302                 }else{
00303                     n[j] = m_normalIndices[i*3+j];
00304                 }
00305             }
00306         }else{
00307             if (m_normalIndices.size() == 0){
00308                 n[0] = i;
00309             }else{
00310                 n[0] = m_normalIndices[i];
00311             }
00312         }
00313         dq_normals.push_back(n);
00314         std::deque<Eigen::Vector3i> dq_textureCoordIndices;
00315         if (m_texture){
00316             dq_textureCoordIndices.push_back(
00317                 Eigen::Vector3i(m_textureCoordIndices[i*3],
00318                                 m_textureCoordIndices[i*3+1],
00319                                 m_textureCoordIndices[i*3+2]));
00320         }
00321         while(dq_triangles.size()){
00322             Eigen::Vector3i tri = dq_triangles.front();
00323             dq_triangles.pop_front();
00324             Eigen::Vector3i n = dq_normals.front();
00325             dq_normals.pop_front();
00326             Eigen::Vector3i tc;
00327             if (m_texture){
00328                 tc = dq_textureCoordIndices.front();
00329                 dq_textureCoordIndices.pop_front();
00330             }
00331             //
00332             double l[3];
00333             for (int j=0; j<3; j++){
00334                 Eigen::Vector3f e = m_vertices[tri[j]] - m_vertices[tri[(j+1)%3]];
00335                 for (int k=0; k<3; k++) e[k] *= scale[k];
00336                 l[j] = e.norm();
00337             }
00338             int maxidx;
00339             if (l[0] > l[1]){
00340                 maxidx = l[0] > l[2] ? 0 : 2;
00341             }else{
00342                 maxidx = l[1] > l[2] ? 1 : 2;
00343             }
00344             if (l[maxidx] <= maxEdgeLen){
00345                 new_triangles.push_back(tri);
00346                 if (m_normalPerVertex){
00347                     for (int j=0; j<3; j++) new_normalIndices.push_back(n[j]);
00348                 }else{
00349                     new_normalIndices.push_back(n[0]);
00350                 }
00351                 for (int j=0; j<3; j++) new_textureCoordIndices.push_back(tc[j]);
00352             }else{
00353                 int vnew = m_vertices.size();
00354                 m_vertices.push_back(
00355                     (m_vertices[tri[maxidx]]+m_vertices[tri[(maxidx+1)%3]])/2);
00356                 dq_triangles.push_back(
00357                     Eigen::Vector3i(tri[maxidx], vnew, tri[(maxidx+2)%3]));
00358                 dq_triangles.push_back(
00359                     Eigen::Vector3i(vnew,tri[(maxidx+1)%3],tri[(maxidx+2)%3]));
00360                 if (m_normalPerVertex){
00361                     int nnew = m_normals.size();
00362                     m_normals.push_back(
00363                         (m_normals[n[maxidx]]+m_normals[n[(maxidx+1)%3]])/2);
00364                     dq_normals.push_back(
00365                         Eigen::Vector3i(n[maxidx], nnew, n[(maxidx+2)%3]));
00366                     dq_normals.push_back(
00367                         Eigen::Vector3i(nnew,n[(maxidx+1)%3],n[(maxidx+2)%3]));
00368                 }else{
00369                     dq_normals.push_back(n);
00370                     dq_normals.push_back(n);
00371                 }
00372                 if (m_texture){
00373                     int tcnew = m_textureCoordinates.size();
00374                     m_textureCoordinates.push_back(
00375                         (m_textureCoordinates[tc[maxidx]]
00376                          +m_textureCoordinates[tc[(maxidx+1)%3]])/2);
00377                     dq_textureCoordIndices.push_back(
00378                         Eigen::Vector3i(tc[maxidx], tcnew, tc[(maxidx+2)%3]));
00379                     dq_textureCoordIndices.push_back(
00380                         Eigen::Vector3i(tcnew, tc[(maxidx+1)%3], tc[(maxidx+2)%3]));
00381                 }
00382             }
00383         }
00384     }
00385             
00386     m_triangles = new_triangles;
00387     m_normalIndices = new_normalIndices;
00388     m_textureCoordIndices = new_textureCoordIndices;
00389 }
00390 
00391 void GLshape::computeAABB(const hrp::Vector3& i_p, const hrp::Matrix33& i_R,
00392                           hrp::Vector3& o_min, hrp::Vector3& o_max)
00393 {
00394     hrp::Vector3 relP = getPosition();
00395     hrp::Matrix33 relR;
00396     getRotation(relR);
00397     hrp::Vector3 p = i_p + i_R*relP;
00398     hrp::Matrix33 R = i_R*relR;
00399     hrp::Vector3 v;
00400     for (size_t i=0; i<m_vertices.size(); i++){
00401         v = R*hrp::Vector3(m_vertices[i][0],m_vertices[i][1],m_vertices[i][2]);
00402         if (i==0){
00403             o_min = v; o_max = v;
00404         }else{
00405             for (int j=0; j<3; j++){
00406                 if (o_min[j] > v[j]) o_min[j] = v[j];
00407                 if (o_max[j] < v[j]) o_max[j] = v[j];
00408             }
00409         }
00410     }
00411     o_min += p;
00412     o_max += p;
00413 }


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:17