graph_drawable.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <sstream>
00029 
00030 #include "graph_drawable.h"
00031 #include "rtabmap/utilite/ULogger.h"
00032 #include "util.h"
00033 
00034 #include <GLES2/gl2.h>
00035 
00036 GraphDrawable::GraphDrawable(
00037                 GLuint shaderProgram,
00038                 const std::map<int, rtabmap::Transform> & poses,
00039                 const std::multimap<int, rtabmap::Link> & links) :
00040                 vertex_buffers_(0),
00041                 pose_(1.0f),
00042                 visible_(true),
00043                 lineWidth_(3.0f),
00044                 shader_program_(shaderProgram)
00045 {
00046         UASSERT(!poses.empty());
00047 
00048         glGenBuffers(1, &vertex_buffers_);
00049 
00050         if(vertex_buffers_)
00051         {
00052                 LOGI("Creating vertex buffer %d", vertex_buffers_);
00053                 std::vector<float> vertices = std::vector<float>(poses.size()*3);
00054                 int i=0;
00055                 std::map<int, int> idsToIndices;
00056                 for(std::map<int, rtabmap::Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
00057                 {
00058                         vertices[i*3] = iter->second.x();
00059                         vertices[i*3+1] = iter->second.y();
00060                         vertices[i*3+2] = iter->second.z();
00061                         idsToIndices.insert(std::make_pair(iter->first, i));
00062                         ++i;
00063                 }
00064 
00065                 glBindBuffer(GL_ARRAY_BUFFER, vertex_buffers_);
00066                 glBufferData(GL_ARRAY_BUFFER, sizeof(GLfloat) * (int)vertices.size(), (const void *)vertices.data(), GL_STATIC_DRAW);
00067                 glBindBuffer(GL_ARRAY_BUFFER, 0);
00068 
00069                 GLint error = glGetError();
00070                 if(error != GL_NO_ERROR)
00071                 {
00072                         LOGI("OpenGL: Could not allocate point cloud (0x%x)\n", error);
00073                         vertex_buffers_ = 0;
00074                 }
00075                 else if(links.size())
00076                 {
00077                         neighborIndices_.resize(links.size() * 2);
00078                         loopClosureIndices_.resize(links.size() * 2);
00079                         int oiNeighbors = 0;
00080                         int oiLoopClosures = 0;
00081                         for(std::multimap<int, rtabmap::Link>::const_iterator iter=links.begin(); iter!=links.end(); ++iter)
00082                         {
00083                                 std::map<int, int>::const_iterator jterFrom = idsToIndices.find(iter->second.from());
00084                                 std::map<int, int>::const_iterator jterTo = idsToIndices.find(iter->second.to());
00085                                 if(jterFrom != idsToIndices.end() && jterTo != idsToIndices.end())
00086                                 {
00087                                         if(iter->second.type() == rtabmap::Link::kNeighbor)
00088                                         {
00089                                                 neighborIndices_[oiNeighbors++] = (unsigned short)jterFrom->second;
00090                                                 neighborIndices_[oiNeighbors++] = (unsigned short)jterTo->second;
00091                                         }
00092                                         else
00093                                         {
00094                                                 loopClosureIndices_[oiLoopClosures++] = (unsigned short)jterFrom->second;
00095                                                 loopClosureIndices_[oiLoopClosures++] = (unsigned short)jterTo->second;
00096                                         }
00097                                 }
00098                         }
00099                         neighborIndices_.resize(oiNeighbors);
00100                         loopClosureIndices_.resize(oiLoopClosures);
00101                 }
00102         }
00103 }
00104 
00105 GraphDrawable::~GraphDrawable()
00106 {
00107         LOGI("Freeing cloud buffer %d", vertex_buffers_);
00108         if (vertex_buffers_)
00109         {
00110                 glDeleteBuffers(1, &vertex_buffers_);
00111                 tango_gl::util::CheckGlError("GraphDrawable::~GraphDrawable()");
00112                 vertex_buffers_ = 0;
00113         }
00114 }
00115 
00116 void GraphDrawable::setPose(const rtabmap::Transform & pose)
00117 {
00118         UASSERT(!pose.isNull());
00119 
00120         pose_ = glmFromTransform(pose);
00121 }
00122 
00123 void GraphDrawable::Render(const glm::mat4 & projectionMatrix, const glm::mat4 & viewMatrix) {
00124 
00125         if(vertex_buffers_ && (neighborIndices_.size() || loopClosureIndices_.size()) && visible_)
00126         {
00127                 glUseProgram(shader_program_);
00128                 glLineWidth(lineWidth_);
00129 
00130                 GLuint mvp_handle_ = glGetUniformLocation(shader_program_, "mvp");
00131                 glm::mat4 mvp_mat = projectionMatrix * viewMatrix * pose_;
00132                 glUniformMatrix4fv(mvp_handle_, 1, GL_FALSE, glm::value_ptr(mvp_mat));
00133 
00134                 GLuint color_handle = glGetUniformLocation(shader_program_, "color");
00135 
00136                 GLint attribute_vertex = glGetAttribLocation(shader_program_, "vertex");
00137 
00138                 glEnableVertexAttribArray(attribute_vertex);
00139                 glBindBuffer(GL_ARRAY_BUFFER, vertex_buffers_);
00140                 glVertexAttribPointer(attribute_vertex, 3, GL_FLOAT, GL_FALSE, 3*sizeof(GLfloat), 0);
00141 
00142                 if(neighborIndices_.size())
00143                 {
00144                         glUniform3f(color_handle, 1.0f, 0.0f, 0.0f); // blue for neighbors
00145                         glDrawElements(GL_LINES, neighborIndices_.size(), GL_UNSIGNED_SHORT, neighborIndices_.data());
00146                 }
00147                 if(loopClosureIndices_.size())
00148                 {
00149                         glUniform3f(color_handle, 0.0f, 0.0f, 1.0f); // red for loop closures
00150                         glDrawElements(GL_LINES, loopClosureIndices_.size(), GL_UNSIGNED_SHORT, loopClosureIndices_.data());
00151                 }
00152 
00153                 glDisableVertexAttribArray(0);
00154                 glBindBuffer(GL_ARRAY_BUFFER, 0);
00155 
00156                 glUseProgram(0);
00157                 tango_gl::util::CheckGlError("GraphDrawable::Render()");
00158         }
00159 }
00160 


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:16