scene.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2014 Google Inc. All Rights Reserved.
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include <tango-gl/conversions.h>
00018 #include <tango-gl/gesture_camera.h>
00019 #include <tango-gl/util.h>
00020 
00021 #include <rtabmap/utilite/ULogger.h>
00022 #include <rtabmap/utilite/UStl.h>
00023 #include <rtabmap/utilite/UTimer.h>
00024 #include <rtabmap/core/util3d_filtering.h>
00025 #include <rtabmap/core/util3d_transforms.h>
00026 #include <rtabmap/core/util3d_surface.h>
00027 #include <pcl/common/transforms.h>
00028 #include <pcl/common/common.h>
00029 
00030 #include <glm/gtx/transform.hpp>
00031 
00032 #include "scene.h"
00033 #include "util.h"
00034 
00035 // We want to represent the device properly with respect to the ground so we'll
00036 // add an offset in z to our origin. We'll set this offset to 1.3 meters based
00037 // on the average height of a human standing with a Tango device. This allows us
00038 // to place a grid roughly on the ground for most users.
00039 const glm::vec3 kHeightOffset = glm::vec3(0.0f, -1.3f, 0.0f);
00040 
00041 // Color of the motion tracking trajectory.
00042 const tango_gl::Color kTraceColor(0.66f, 0.66f, 0.66f);
00043 
00044 // Color of the ground grid.
00045 const tango_gl::Color kGridColor(0.85f, 0.85f, 0.85f);
00046 
00047 // Frustum scale.
00048 const glm::vec3 kFrustumScale = glm::vec3(0.4f, 0.3f, 0.5f);
00049 
00050 const std::string kGraphVertexShader =
00051     "precision mediump float;\n"
00052     "precision mediump int;\n"
00053     "attribute vec3 vertex;\n"
00054     "uniform vec3 color;\n"
00055     "uniform mat4 mvp;\n"
00056     "varying vec3 v_color;\n"
00057     "void main() {\n"
00058     "  gl_Position = mvp*vec4(vertex.x, vertex.y, vertex.z, 1.0);\n"
00059     "  v_color = color;\n"
00060     "}\n";
00061 const std::string kGraphFragmentShader =
00062     "precision mediump float;\n"
00063     "precision mediump int;\n"
00064     "varying vec3 v_color;\n"
00065     "void main() {\n"
00066     "  gl_FragColor = vec4(v_color.z, v_color.y, v_color.x, 1.0);\n"
00067     "}\n";
00068 
00069 
00070 
00071 Scene::Scene() :
00072                 gesture_camera_(0),
00073                 axis_(0),
00074                 frustum_(0),
00075                 grid_(0),
00076                 box_(0),
00077                 trace_(0),
00078                 graph_(0),
00079                 graphVisible_(true),
00080                 gridVisible_(true),
00081                 traceVisible_(true),
00082                 color_camera_to_display_rotation_(ROTATION_0),
00083                 currentPose_(0),
00084                 graph_shader_program_(0),
00085                 blending_(true),
00086                 mapRendering_(true),
00087                 meshRendering_(true),
00088                 meshRenderingTexture_(true),
00089                 pointSize_(5.0f),
00090                 boundingBoxRendering_(false),
00091                 lighting_(false),
00092                 backfaceCulling_(true),
00093                 wireFrame_(false),
00094                 r_(0.0f),
00095                 g_(0.0f),
00096                 b_(0.0f),
00097                 fboId_(0),
00098                 depthTexture_(0),
00099                 screenWidth_(0),
00100                 screenHeight_(0),
00101                 doubleTapOn_(false)
00102 {
00103         gesture_camera_ = new tango_gl::GestureCamera();
00104         gesture_camera_->SetCameraType(
00105               tango_gl::GestureCamera::kFirstPerson);
00106 }
00107 
00108 Scene::~Scene() {
00109         DeleteResources();
00110         delete gesture_camera_;
00111 }
00112 
00113 //Should only be called in OpenGL thread!
00114 void Scene::InitGLContent()
00115 {
00116         if(axis_ != 0)
00117         {
00118                 DeleteResources();
00119         }
00120 
00121         UASSERT(axis_ == 0);
00122 
00123 
00124         axis_ = new tango_gl::Axis();
00125         frustum_ = new tango_gl::Frustum();
00126         trace_ = new tango_gl::Trace();
00127         grid_ = new tango_gl::Grid();
00128         box_ = new BoundingBoxDrawable();
00129         currentPose_ = new rtabmap::Transform();
00130 
00131 
00132         axis_->SetScale(glm::vec3(0.5f,0.5f,0.5f));
00133         frustum_->SetColor(kTraceColor);
00134         trace_->ClearVertexArray();
00135         trace_->SetColor(kTraceColor);
00136         grid_->SetColor(kGridColor);
00137         grid_->SetPosition(kHeightOffset);
00138         box_->SetShader();
00139         box_->SetColor(1,0,0);
00140 
00141         PointCloudDrawable::createShaderPrograms();
00142 
00143         if(graph_shader_program_ == 0)
00144         {
00145                 graph_shader_program_ = tango_gl::util::CreateProgram(kGraphVertexShader.c_str(), kGraphFragmentShader.c_str());
00146                 UASSERT(graph_shader_program_ != 0);
00147         }
00148 }
00149 
00150 //Should only be called in OpenGL thread!
00151 void Scene::DeleteResources() {
00152 
00153         LOGI("Scene::DeleteResources()");
00154         if(axis_)
00155         {
00156                 delete axis_;
00157                 axis_ = 0;
00158                 delete frustum_;
00159                 delete trace_;
00160                 delete grid_;
00161                 delete currentPose_;
00162                 delete box_;
00163         }
00164 
00165         PointCloudDrawable::releaseShaderPrograms();
00166 
00167         if (graph_shader_program_) {
00168                 glDeleteShader(graph_shader_program_);
00169                 graph_shader_program_ = 0;
00170         }
00171 
00172         if(fboId_>0)
00173         {
00174                 glDeleteFramebuffers(1, &fboId_);
00175                 fboId_ = 0;
00176                 glDeleteTextures(1, &depthTexture_);
00177                 depthTexture_ = 0;
00178         }
00179 
00180         clear();
00181 }
00182 
00183 //Should only be called in OpenGL thread!
00184 void Scene::clear()
00185 {
00186         LOGI("Scene::clear()");
00187         for(std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.begin(); iter!=pointClouds_.end(); ++iter)
00188         {
00189                 delete iter->second;
00190         }
00191         if(trace_)
00192         {
00193                 trace_->ClearVertexArray();
00194         }
00195         if(graph_)
00196         {
00197                 delete graph_;
00198                 graph_ = 0;
00199         }
00200         pointClouds_.clear();
00201         if(grid_)
00202         {
00203                 grid_->SetPosition(kHeightOffset);
00204         }
00205 }
00206 
00207 //Should only be called in OpenGL thread!
00208 void Scene::SetupViewPort(int w, int h) {
00209         if (h == 0) {
00210                 LOGE("Setup graphic height not valid");
00211         }
00212         UASSERT(gesture_camera_ != 0);
00213         gesture_camera_->SetWindowSize(static_cast<float>(w), static_cast<float>(h));
00214         glViewport(0, 0, w, h);
00215         if(screenWidth_ != w || fboId_ == 0)
00216         {
00217                 if(fboId_>0)
00218                 {
00219                         glDeleteFramebuffers(1, &fboId_);
00220                         fboId_ = 0;
00221                         glDeleteTextures(1, &depthTexture_);
00222                         depthTexture_ = 0;
00223                 }
00224 
00225                 // Create depth texture
00226                 glGenTextures(1, &depthTexture_);
00227                 glBindTexture(GL_TEXTURE_2D, depthTexture_);
00228                 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
00229                 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
00230                 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
00231                 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
00232                 glTexImage2D(GL_TEXTURE_2D, 0, GL_DEPTH_COMPONENT, w, h, 0, GL_DEPTH_COMPONENT, GL_UNSIGNED_INT, NULL);
00233                 glBindTexture(GL_TEXTURE_2D, 0);
00234 
00235                 // regenerate fbo texture
00236                 // create a framebuffer object, you need to delete them when program exits.
00237                 glGenFramebuffers(1, &fboId_);
00238                 glBindFramebuffer(GL_FRAMEBUFFER, fboId_);
00239 
00240                 // Set the texture to be at the depth attachment point of the FBO
00241                 glFramebufferTexture2D(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_TEXTURE_2D, depthTexture_, 0);
00242 
00243                 GLuint status = glCheckFramebufferStatus(GL_FRAMEBUFFER);
00244                 if ( status != GL_FRAMEBUFFER_COMPLETE)
00245                 {
00246                         LOGE("Frame buffer cannot be generated! Status: %in", status);
00247                 }
00248                 glBindFramebuffer(GL_FRAMEBUFFER,0);
00249         }
00250         screenWidth_ = w;
00251         screenHeight_ = h;
00252 }
00253 
00254 std::vector<glm::vec4> computeFrustumPlanes(const glm::mat4 & mat, bool normalize = true)
00255 {
00256         // http://www.txutxi.com/?p=444
00257         std::vector<glm::vec4> planes(6);
00258 
00259         // Left Plane
00260         // col4 + col1
00261         planes[0].x = mat[0][3] + mat[0][0];
00262         planes[0].y = mat[1][3] + mat[1][0];
00263         planes[0].z = mat[2][3] + mat[2][0];
00264         planes[0].w = mat[3][3] + mat[3][0];
00265 
00266         // Right Plane
00267         // col4 - col1
00268         planes[1].x = mat[0][3] - mat[0][0];
00269         planes[1].y = mat[1][3] - mat[1][0];
00270         planes[1].z = mat[2][3] - mat[2][0];
00271         planes[1].w = mat[3][3] - mat[3][0];
00272 
00273         // Bottom Plane
00274         // col4 + col2
00275         planes[2].x = mat[0][3] + mat[0][1];
00276         planes[2].y = mat[1][3] + mat[1][1];
00277         planes[2].z = mat[2][3] + mat[2][1];
00278         planes[2].w = mat[3][3] + mat[3][1];
00279 
00280         // Top Plane
00281         // col4 - col2
00282         planes[3].x = mat[0][3] - mat[0][1];
00283         planes[3].y = mat[1][3] - mat[1][1];
00284         planes[3].z = mat[2][3] - mat[2][1];
00285         planes[3].w = mat[3][3] - mat[3][1];
00286 
00287         // Near Plane
00288         // col4 + col3
00289         planes[4].x = mat[0][3] + mat[0][2];
00290         planes[4].y = mat[1][3] + mat[1][2];
00291         planes[4].z = mat[2][3] + mat[2][2];
00292         planes[4].w = mat[3][3] + mat[3][2];
00293 
00294         // Far Plane
00295         // col4 - col3
00296         planes[5].x = mat[0][3] - mat[0][2];
00297         planes[5].y = mat[1][3] - mat[1][2];
00298         planes[5].z = mat[2][3] - mat[2][2];
00299         planes[5].w = mat[3][3] - mat[3][2];
00300 
00301         //if(normalize)
00302         {
00303                 for(unsigned int i=0;i<planes.size(); ++i)
00304                 {
00305                         if(normalize)
00306                         {
00307                                 float d = std::sqrt(planes[i].x * planes[i].x + planes[i].y * planes[i].y + planes[i].z * planes[i].z); // for normalizing the coordinates
00308                                 planes[i].x/=d;
00309                                 planes[i].y/=d;
00310                                 planes[i].z/=d;
00311                                 planes[i].w/=d;
00312                         }
00313                 }
00314         }
00315 
00316         return planes;
00317 }
00318 
00326 bool intersectFrustumAABB(
00327         const std::vector<glm::vec4> &planes,
00328         const pcl::PointXYZ &boxMin,
00329                 const pcl::PointXYZ &boxMax)
00330 {
00331   // Indexed for the 'index trick' later
00332         const pcl::PointXYZ * box[] = {&boxMin, &boxMax};
00333 
00334   // We only need to do 6 point-plane tests
00335   for (unsigned int i = 0; i < planes.size(); ++i)
00336   {
00337     // This is the current plane
00338     const glm::vec4 &p = planes[i];
00339 
00340     // p-vertex selection (with the index trick)
00341     // According to the plane normal we can know the
00342     // indices of the positive vertex
00343     const int px = p.x > 0.0f?1:0;
00344     const int py = p.y > 0.0f?1:0;
00345     const int pz = p.z > 0.0f?1:0;
00346 
00347     // Dot product
00348     // project p-vertex on plane normal
00349     // (How far is p-vertex from the origin)
00350     const float dp =
00351         (p.x*box[px]->x) +
00352         (p.y*box[py]->y) +
00353         (p.z*box[pz]->z) + p.w;
00354 
00355     // Doesn't intersect if it is behind the plane
00356     if (dp < 0) {return false; }
00357   }
00358   return true;
00359 }
00360 
00361 //Should only be called in OpenGL thread!
00362 int Scene::Render() {
00363         UASSERT(gesture_camera_ != 0);
00364 
00365         glm::vec3 position(currentPose_->x(), currentPose_->y(), currentPose_->z());
00366         Eigen::Quaternionf quat = currentPose_->getQuaternionf();
00367         glm::quat rotation(quat.w(), quat.x(), quat.y(), quat.z());
00368         glm::mat4 rotateM;
00369         if(!currentPose_->isNull())
00370         {
00371                 rotateM = glm::rotate<float>(float(color_camera_to_display_rotation_)*-1.57079632679489661923132169163975144, glm::vec3(0.0f, 0.0f, 1.0f));
00372 
00373                 if (gesture_camera_->GetCameraType() == tango_gl::GestureCamera::kFirstPerson)
00374                 {
00375                         // In first person mode, we directly control camera's motion.
00376                         gesture_camera_->SetPosition(position);
00377                         gesture_camera_->SetRotation(rotation*glm::quat(rotateM));
00378                 }
00379                 else
00380                 {
00381                         // In third person or top down mode, we follow the camera movement.
00382                         gesture_camera_->SetAnchorPosition(position, rotation*glm::quat(rotateM));
00383                 }
00384         }
00385 
00386         glm::mat4 projectionMatrix = gesture_camera_->GetProjectionMatrix();
00387         glm::mat4 viewMatrix = gesture_camera_->GetViewMatrix();
00388 
00389         rtabmap::Transform openglCamera = GetOpenGLCameraPose();//*rtabmap::Transform(0.0f, 0.0f, 3.0f, 0.0f, 0.0f, 0.0f);
00390         // transform in same coordinate as frustum filtering
00391         openglCamera *= rtabmap::Transform(
00392                  0.0f,  0.0f,  1.0f, 0.0f,
00393                  0.0f,  1.0f,  0.0f, 0.0f,
00394                 -1.0f,  0.0f,  0.0f, 0.0f);
00395 
00396         //Culling
00397         std::vector<glm::vec4> planes = computeFrustumPlanes(projectionMatrix*viewMatrix, true);
00398         std::vector<PointCloudDrawable*> cloudsToDraw(pointClouds_.size());
00399         int oi=0;
00400         for(std::map<int, PointCloudDrawable*>::const_iterator iter=pointClouds_.begin(); iter!=pointClouds_.end(); ++iter)
00401         {
00402                 if(!mapRendering_ && iter->first > 0)
00403                 {
00404                         break;
00405                 }
00406 
00407                 if(iter->second->isVisible())
00408                 {
00409                         if(intersectFrustumAABB(planes,
00410                                         iter->second->aabbMinWorld(),
00411                                         iter->second->aabbMaxWorld()))
00412                         {
00413                                 cloudsToDraw[oi++] = iter->second;
00414                         }
00415                 }
00416         }
00417         cloudsToDraw.resize(oi);
00418 
00419         // First rendering to get depth texture
00420         glEnable(GL_DEPTH_TEST);
00421         glDepthFunc(GL_LESS);
00422         glDepthMask(GL_TRUE);
00423         glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);
00424         glDisable (GL_BLEND);
00425         glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
00426 
00427         if(backfaceCulling_)
00428         {
00429                 glEnable(GL_CULL_FACE);
00430         }
00431         else
00432         {
00433                 glDisable(GL_CULL_FACE);
00434         }
00435 
00436         UTimer timer;
00437 
00438         bool onlineBlending = blending_ && gesture_camera_->GetCameraType()!=tango_gl::GestureCamera::kTopOrtho && mapRendering_ && meshRendering_ && cloudsToDraw.size()>1;
00439         if(onlineBlending && fboId_)
00440         {
00441                 // set the rendering destination to FBO
00442                 glBindFramebuffer(GL_FRAMEBUFFER, fboId_);
00443 
00444                 glColorMask(GL_FALSE, GL_FALSE, GL_FALSE, GL_FALSE);
00445                 glClearColor(1, 1, 1, 1);
00446                 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
00447 
00448                 // Draw scene
00449                 for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
00450                 {
00451                         // set large distance to cam to use low res polygons for fast processing
00452                         (*iter)->Render(projectionMatrix, viewMatrix, meshRendering_, pointSize_, false, false, 999.0f);
00453                 }
00454 
00455                 // back to normal window-system-provided framebuffer
00456                 glBindFramebuffer(GL_FRAMEBUFFER, 0); // unbind
00457                 glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);
00458         }
00459 
00460         if(doubleTapOn_ && gesture_camera_->GetCameraType() != tango_gl::GestureCamera::kFirstPerson)
00461         {
00462                 glClearColor(0, 0, 0, 0);
00463                 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
00464 
00465                 for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
00466                 {
00467                         // set large distance to cam to use low res polygons for fast processing
00468                         (*iter)->Render(projectionMatrix, viewMatrix, meshRendering_, pointSize_*10.0f, false, false, 999.0f, 0, 0, 0, 0, 0, true);
00469                 }
00470 
00471                 GLubyte zValue[4];
00472                 glReadPixels(doubleTapPos_.x*screenWidth_, screenHeight_-doubleTapPos_.y*screenHeight_, 1, 1, GL_RGBA, GL_UNSIGNED_BYTE, zValue);
00473                 float fromFixed = 256.0f/255.0f;
00474                 float zValueF = float(zValue[0]/255.0f)*fromFixed + float(zValue[1]/255.0f)*fromFixed/255.0f + float(zValue[2]/255.0f)*fromFixed/65025.0f + float(zValue[3]/255.0f)*fromFixed/160581375.0f;
00475 
00476                 if(zValueF != 0.0f)
00477                 {
00478                         zValueF = zValueF*2.0-1.0;//NDC
00479                         glm::vec4 point = glm::inverse(projectionMatrix*viewMatrix)*glm::vec4(doubleTapPos_.x*2.0f-1.0f, (1.0f-doubleTapPos_.y)*2.0f-1.0f, zValueF, 1.0f);
00480                         point /= point.w;
00481                         gesture_camera_->SetAnchorOffset(glm::vec3(point.x, point.y, point.z) - position);
00482                 }
00483         }
00484         doubleTapOn_ = false;
00485 
00486         glClearColor(r_, g_, b_, 1.0f);
00487         glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
00488 
00489         if(!currentPose_->isNull())
00490         {
00491                 if (gesture_camera_->GetCameraType() != tango_gl::GestureCamera::kFirstPerson)
00492                 {
00493                         frustum_->SetPosition(position);
00494                         frustum_->SetRotation(rotation);
00495                         // Set the frustum scale to 4:3, this doesn't necessarily match the physical
00496                         // camera's aspect ratio, this is just for visualization purposes.
00497                         frustum_->SetScale(kFrustumScale);
00498                         frustum_->Render(projectionMatrix, viewMatrix);
00499 
00500                         axis_->SetPosition(position);
00501                         axis_->SetRotation(rotation);
00502                         axis_->Render(projectionMatrix, viewMatrix);
00503                 }
00504 
00505                 trace_->UpdateVertexArray(position);
00506                 if(traceVisible_)
00507                 {
00508                         trace_->Render(projectionMatrix, viewMatrix);
00509                 }
00510 
00511                 if(gridVisible_)
00512                 {
00513                         grid_->Render(projectionMatrix, viewMatrix);
00514                 }
00515         }
00516 
00517         if(graphVisible_ && graph_)
00518         {
00519                 graph_->Render(projectionMatrix, viewMatrix);
00520         }
00521 
00522 
00523         if(onlineBlending)
00524         {
00525                 glEnable (GL_BLEND);
00526                 glDepthMask(GL_FALSE);
00527         }
00528 
00529         for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
00530         {
00531                 PointCloudDrawable * cloud = *iter;
00532 
00533                 if(boundingBoxRendering_)
00534                 {
00535                         box_->updateVertices(cloud->aabbMinWorld(), cloud->aabbMaxWorld());
00536                         box_->Render(projectionMatrix, viewMatrix);
00537                 }
00538 
00539                 Eigen::Vector3f cloudToCamera(
00540                                 cloud->getPose().x() - openglCamera.x(),
00541                                 cloud->getPose().y() - openglCamera.y(),
00542                                 cloud->getPose().z() - openglCamera.z());
00543                 float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
00544 
00545                 cloud->Render(projectionMatrix, viewMatrix, meshRendering_, pointSize_, meshRenderingTexture_, lighting_, distanceToCameraSqr, onlineBlending?depthTexture_:0, screenWidth_, screenHeight_, gesture_camera_->getNearClipPlane(), gesture_camera_->getFarClipPlane(), false, wireFrame_);
00546         }
00547 
00548         if(onlineBlending)
00549         {
00550                 glDisable (GL_BLEND);
00551                 glDepthMask(GL_TRUE);
00552         }
00553 
00554         return (int)cloudsToDraw.size();
00555 }
00556 
00557 void Scene::SetCameraType(tango_gl::GestureCamera::CameraType camera_type) {
00558   gesture_camera_->SetCameraType(camera_type);
00559 }
00560 
00561 void Scene::SetCameraPose(const rtabmap::Transform & pose)
00562 {
00563         UASSERT(currentPose_ != 0);
00564         UASSERT(!pose.isNull());
00565         *currentPose_ = pose;
00566 }
00567 
00568 void Scene::setFOV(float angle)
00569 {
00570         gesture_camera_->SetFieldOfView(angle);
00571 }
00572 void Scene::setOrthoCropFactor(float value)
00573 {
00574         gesture_camera_->SetOrthoCropFactor(value);
00575 }
00576 void Scene::setGridRotation(float angleDeg)
00577 {
00578         float angleRad = angleDeg * DEGREE_2_RADIANS;
00579         if(grid_)
00580         {
00581                 glm::quat rot = glm::rotate(glm::quat(1,0,0,0), angleRad, glm::vec3(0, 1, 0));
00582                 grid_->SetRotation(rot);
00583         }
00584 }
00585 
00586 rtabmap::Transform Scene::GetOpenGLCameraPose(float * fov) const
00587 {
00588         if(fov)
00589         {
00590                 *fov = gesture_camera_->getFOV();
00591         }
00592         return glmToTransform(gesture_camera_->GetTransformationMatrix());
00593 }
00594 
00595 void Scene::OnTouchEvent(int touch_count,
00596                          tango_gl::GestureCamera::TouchEvent event, float x0,
00597                          float y0, float x1, float y1) {
00598         UASSERT(gesture_camera_ != 0);
00599         if(touch_count == 3)
00600         {
00601                 //doubletap
00602                 if(!doubleTapOn_)
00603                 {
00604                         doubleTapPos_.x = x0;
00605                         doubleTapPos_.y = y0;
00606                         doubleTapOn_ = true;
00607                 }
00608         }
00609         else
00610         {
00611                 // rotate/translate/zoom
00612                 gesture_camera_->OnTouchEvent(touch_count, event, x0, y0, x1, y1);
00613         }
00614 }
00615 
00616 void Scene::updateGraph(
00617                 const std::map<int, rtabmap::Transform> & poses,
00618                 const std::multimap<int, rtabmap::Link> & links)
00619 {
00620         LOGI("updateGraph");
00621         if(graph_)
00622         {
00623                 delete graph_;
00624                 graph_ = 0;
00625         }
00626 
00627         //create
00628         if(graphVisible_)
00629         {
00630                 UASSERT(graph_shader_program_ != 0);
00631                 graph_ = new GraphDrawable(graph_shader_program_, poses, links);
00632         }
00633 }
00634 
00635 void Scene::setGraphVisible(bool visible)
00636 {
00637         graphVisible_ = visible;
00638 }
00639 
00640 void Scene::setGridVisible(bool visible)
00641 {
00642         gridVisible_ = visible;
00643 }
00644 
00645 void Scene::setTraceVisible(bool visible)
00646 {
00647         traceVisible_ = visible;
00648 }
00649 
00650 //Should only be called in OpenGL thread!
00651 void Scene::addCloud(
00652                 int id,
00653                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00654                 const pcl::IndicesPtr & indices,
00655                 const rtabmap::Transform & pose)
00656 {
00657         LOGI("add cloud %d (%d points %d indices)", id, (int)cloud->size(), indices.get()?(int)indices->size():0);
00658         std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
00659         if(iter != pointClouds_.end())
00660         {
00661                 delete iter->second;
00662                 pointClouds_.erase(iter);
00663         }
00664 
00665         //create
00666         PointCloudDrawable * drawable = new PointCloudDrawable(cloud, indices);
00667         drawable->setPose(pose);
00668         pointClouds_.insert(std::make_pair(id, drawable));
00669 }
00670 
00671 void Scene::addMesh(
00672                 int id,
00673                 const Mesh & mesh,
00674                 const rtabmap::Transform & pose,
00675                 bool createWireframe)
00676 {
00677         LOGI("add mesh %d", id);
00678         std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
00679         if(iter != pointClouds_.end())
00680         {
00681                 delete iter->second;
00682                 pointClouds_.erase(iter);
00683         }
00684 
00685         //create
00686         PointCloudDrawable * drawable = new PointCloudDrawable(mesh, createWireframe);
00687         drawable->setPose(pose);
00688         pointClouds_.insert(std::make_pair(id, drawable));
00689 
00690         if(!mesh.pose.isNull() && mesh.cloud->size() && (!mesh.cloud->isOrganized() || mesh.indices->size()))
00691         {
00692                 UTimer time;
00693                 float height = 0.0f;
00694                 Eigen::Affine3f affinePose = mesh.pose.toEigen3f();
00695                 if(mesh.polygons.size())
00696                 {
00697                         for(unsigned int i=0; i<mesh.polygons.size(); ++i)
00698                         {
00699                                 for(unsigned int j=0; j<mesh.polygons[i].vertices.size(); ++j)
00700                                 {
00701                                         pcl::PointXYZRGB pt = pcl::transformPoint(mesh.cloud->at(mesh.polygons[i].vertices[j]), affinePose);
00702                                         if(pt.z < height)
00703                                         {
00704                                                 height = pt.z;
00705                                         }
00706                                 }
00707                         }
00708                 }
00709                 else
00710                 {
00711                         if(mesh.cloud->isOrganized())
00712                         {
00713                                 for(unsigned int i=0; i<mesh.indices->size(); ++i)
00714                                 {
00715                                         pcl::PointXYZRGB pt = pcl::transformPoint(mesh.cloud->at(mesh.indices->at(i)), affinePose);
00716                                         if(pt.z < height)
00717                                         {
00718                                                 height = pt.z;
00719                                         }
00720                                 }
00721                         }
00722                         else
00723                         {
00724                                 for(unsigned int i=0; i<mesh.cloud->size(); ++i)
00725                                 {
00726                                         pcl::PointXYZRGB pt = pcl::transformPoint(mesh.cloud->at(i), affinePose);
00727                                         if(pt.z < height)
00728                                         {
00729                                                 height = pt.z;
00730                                         }
00731                                 }
00732                         }
00733                 }
00734 
00735                 if(grid_->GetPosition().y == kHeightOffset.y || grid_->GetPosition().y > height)
00736                 {
00737                         grid_->SetPosition(glm::vec3(0,height,0));
00738                 }
00739                 LOGD("compute min height %f s", time.ticks());
00740         }
00741 }
00742 
00743 
00744 void Scene::setCloudPose(int id, const rtabmap::Transform & pose)
00745 {
00746         UASSERT(!pose.isNull());
00747         std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
00748         if(iter != pointClouds_.end())
00749         {
00750                 iter->second->setPose(pose);
00751         }
00752 }
00753 
00754 void Scene::setCloudVisible(int id, bool visible)
00755 {
00756         std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
00757         if(iter != pointClouds_.end())
00758         {
00759                 iter->second->setVisible(visible);
00760         }
00761 }
00762 
00763 bool Scene::hasCloud(int id) const
00764 {
00765         return pointClouds_.find(id) != pointClouds_.end();
00766 }
00767 
00768 bool Scene::hasMesh(int id) const
00769 {
00770         return pointClouds_.find(id) != pointClouds_.end() && pointClouds_.at(id)->hasMesh();
00771 }
00772 
00773 bool Scene::hasTexture(int id) const
00774 {
00775         return pointClouds_.find(id) != pointClouds_.end() && pointClouds_.at(id)->hasTexture();
00776 }
00777 
00778 std::set<int> Scene::getAddedClouds() const
00779 {
00780         return uKeysSet(pointClouds_);
00781 }
00782 
00783 void Scene::updateCloudPolygons(int id, const std::vector<pcl::Vertices> & polygons)
00784 {
00785         std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
00786         if(iter != pointClouds_.end())
00787         {
00788                 iter->second->updatePolygons(polygons);
00789         }
00790 }
00791 
00792 void Scene::updateMesh(int id, const Mesh & mesh)
00793 {
00794         std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
00795         if(iter != pointClouds_.end())
00796         {
00797                 iter->second->updateMesh(mesh);
00798         }
00799 }
00800 
00801 void Scene::updateGains(int id, float gainR, float gainG, float gainB)
00802 {
00803         std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
00804         if(iter != pointClouds_.end())
00805         {
00806                 iter->second->setGains(gainR, gainG, gainB);
00807         }
00808 }
00809 
00810 void Scene::setGridColor(float r, float g, float b)
00811 {
00812         if(grid_)
00813         {
00814                 grid_->SetColor(r, g, b);
00815         }
00816 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:22