scene.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2014 Google Inc. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <tango-gl/conversions.h>
19 #include <tango-gl/util.h>
20 
22 #include <rtabmap/utilite/UStl.h>
23 #include <rtabmap/utilite/UTimer.h>
27 #include <pcl/common/transforms.h>
28 #include <pcl/common/common.h>
29 
30 #include <glm/gtx/transform.hpp>
31 
32 #include "scene.h"
33 #include "util.h"
34 
35 // We want to represent the device properly with respect to the ground so we'll
36 // add an offset in z to our origin. We'll set this offset to 1.3 meters based
37 // on the average height of a human standing with a Tango device. This allows us
38 // to place a grid roughly on the ground for most users.
39 const glm::vec3 kHeightOffset = glm::vec3(0.0f, -1.3f, 0.0f);
40 
41 // Color of the motion tracking trajectory.
42 const tango_gl::Color kTraceColor(0.66f, 0.66f, 0.66f);
43 
44 // Color of the ground grid.
45 const tango_gl::Color kGridColor(0.85f, 0.85f, 0.85f);
46 
47 // Frustum scale.
48 const glm::vec3 kFrustumScale = glm::vec3(0.4f, 0.3f, 0.5f);
49 
50 const std::string kGraphVertexShader =
51  "precision mediump float;\n"
52  "precision mediump int;\n"
53  "attribute vec3 vertex;\n"
54  "uniform vec3 color;\n"
55  "uniform mat4 mvp;\n"
56  "varying vec3 v_color;\n"
57  "void main() {\n"
58  " gl_Position = mvp*vec4(vertex.x, vertex.y, vertex.z, 1.0);\n"
59  " v_color = color;\n"
60  "}\n";
61 const std::string kGraphFragmentShader =
62  "precision mediump float;\n"
63  "precision mediump int;\n"
64  "varying vec3 v_color;\n"
65  "void main() {\n"
66  " gl_FragColor = vec4(v_color.z, v_color.y, v_color.x, 1.0);\n"
67  "}\n";
68 
69 
70 
72  gesture_camera_(0),
73  axis_(0),
74  frustum_(0),
75  grid_(0),
76  box_(0),
77  trace_(0),
78  graph_(0),
79  graphVisible_(true),
80  gridVisible_(true),
81  traceVisible_(true),
82  color_camera_to_display_rotation_(ROTATION_0),
83  currentPose_(0),
84  graph_shader_program_(0),
85  blending_(true),
86  mapRendering_(true),
87  meshRendering_(true),
88  meshRenderingTexture_(true),
89  pointSize_(5.0f),
90  boundingBoxRendering_(false),
91  lighting_(false),
92  backfaceCulling_(true),
93  wireFrame_(false),
94  r_(0.0f),
95  g_(0.0f),
96  b_(0.0f),
97  fboId_(0),
98  depthTexture_(0),
99  screenWidth_(0),
100  screenHeight_(0),
101  doubleTapOn_(false)
102 {
106 }
107 
109  DeleteResources();
110  delete gesture_camera_;
111 }
112 
113 //Should only be called in OpenGL thread!
115 {
116  if(axis_ != 0)
117  {
118  DeleteResources();
119  }
120 
121  UASSERT(axis_ == 0);
122 
123 
124  axis_ = new tango_gl::Axis();
125  frustum_ = new tango_gl::Frustum();
126  trace_ = new tango_gl::Trace();
127  grid_ = new tango_gl::Grid();
128  box_ = new BoundingBoxDrawable();
130 
131 
132  axis_->SetScale(glm::vec3(0.5f,0.5f,0.5f));
137  grid_->SetPosition(kHeightOffset);
138  box_->SetShader();
139  box_->SetColor(1,0,0);
140 
142 
143  if(graph_shader_program_ == 0)
144  {
147  }
148 }
149 
150 //Should only be called in OpenGL thread!
152 
153  LOGI("Scene::DeleteResources()");
154  if(axis_)
155  {
156  delete axis_;
157  axis_ = 0;
158  delete frustum_;
159  delete trace_;
160  delete grid_;
161  delete currentPose_;
162  delete box_;
163  }
164 
166 
167  if (graph_shader_program_) {
168  glDeleteShader(graph_shader_program_);
170  }
171 
172  if(fboId_>0)
173  {
174  glDeleteFramebuffers(1, &fboId_);
175  fboId_ = 0;
176  glDeleteTextures(1, &depthTexture_);
177  depthTexture_ = 0;
178  }
179 
180  clear();
181 }
182 
183 //Should only be called in OpenGL thread!
185 {
186  LOGI("Scene::clear()");
187  for(std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.begin(); iter!=pointClouds_.end(); ++iter)
188  {
189  delete iter->second;
190  }
191  if(trace_)
192  {
194  }
195  if(graph_)
196  {
197  delete graph_;
198  graph_ = 0;
199  }
200  pointClouds_.clear();
201  if(grid_)
202  {
203  grid_->SetPosition(kHeightOffset);
204  }
205 }
206 
207 //Should only be called in OpenGL thread!
208 void Scene::SetupViewPort(int w, int h) {
209  if (h == 0) {
210  LOGE("Setup graphic height not valid");
211  }
212  UASSERT(gesture_camera_ != 0);
213  gesture_camera_->SetWindowSize(static_cast<float>(w), static_cast<float>(h));
214  glViewport(0, 0, w, h);
215  if(screenWidth_ != w || fboId_ == 0)
216  {
217  if(fboId_>0)
218  {
219  glDeleteFramebuffers(1, &fboId_);
220  fboId_ = 0;
221  glDeleteTextures(1, &depthTexture_);
222  depthTexture_ = 0;
223  }
224 
225  // Create depth texture
226  glGenTextures(1, &depthTexture_);
227  glBindTexture(GL_TEXTURE_2D, depthTexture_);
228  glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
229  glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
230  glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
231  glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
232  glTexImage2D(GL_TEXTURE_2D, 0, GL_DEPTH_COMPONENT, w, h, 0, GL_DEPTH_COMPONENT, GL_UNSIGNED_INT, NULL);
233  glBindTexture(GL_TEXTURE_2D, 0);
234 
235  // regenerate fbo texture
236  // create a framebuffer object, you need to delete them when program exits.
237  glGenFramebuffers(1, &fboId_);
238  glBindFramebuffer(GL_FRAMEBUFFER, fboId_);
239 
240  // Set the texture to be at the depth attachment point of the FBO
241  glFramebufferTexture2D(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_TEXTURE_2D, depthTexture_, 0);
242 
243  GLuint status = glCheckFramebufferStatus(GL_FRAMEBUFFER);
244  if ( status != GL_FRAMEBUFFER_COMPLETE)
245  {
246  LOGE("Frame buffer cannot be generated! Status: %in", status);
247  }
248  glBindFramebuffer(GL_FRAMEBUFFER,0);
249  }
250  screenWidth_ = w;
251  screenHeight_ = h;
252 }
253 
254 std::vector<glm::vec4> computeFrustumPlanes(const glm::mat4 & mat, bool normalize = true)
255 {
256  // http://www.txutxi.com/?p=444
257  std::vector<glm::vec4> planes(6);
258 
259  // Left Plane
260  // col4 + col1
261  planes[0].x = mat[0][3] + mat[0][0];
262  planes[0].y = mat[1][3] + mat[1][0];
263  planes[0].z = mat[2][3] + mat[2][0];
264  planes[0].w = mat[3][3] + mat[3][0];
265 
266  // Right Plane
267  // col4 - col1
268  planes[1].x = mat[0][3] - mat[0][0];
269  planes[1].y = mat[1][3] - mat[1][0];
270  planes[1].z = mat[2][3] - mat[2][0];
271  planes[1].w = mat[3][3] - mat[3][0];
272 
273  // Bottom Plane
274  // col4 + col2
275  planes[2].x = mat[0][3] + mat[0][1];
276  planes[2].y = mat[1][3] + mat[1][1];
277  planes[2].z = mat[2][3] + mat[2][1];
278  planes[2].w = mat[3][3] + mat[3][1];
279 
280  // Top Plane
281  // col4 - col2
282  planes[3].x = mat[0][3] - mat[0][1];
283  planes[3].y = mat[1][3] - mat[1][1];
284  planes[3].z = mat[2][3] - mat[2][1];
285  planes[3].w = mat[3][3] - mat[3][1];
286 
287  // Near Plane
288  // col4 + col3
289  planes[4].x = mat[0][3] + mat[0][2];
290  planes[4].y = mat[1][3] + mat[1][2];
291  planes[4].z = mat[2][3] + mat[2][2];
292  planes[4].w = mat[3][3] + mat[3][2];
293 
294  // Far Plane
295  // col4 - col3
296  planes[5].x = mat[0][3] - mat[0][2];
297  planes[5].y = mat[1][3] - mat[1][2];
298  planes[5].z = mat[2][3] - mat[2][2];
299  planes[5].w = mat[3][3] - mat[3][2];
300 
301  //if(normalize)
302  {
303  for(unsigned int i=0;i<planes.size(); ++i)
304  {
305  if(normalize)
306  {
307  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
308  planes[i].x/=d;
309  planes[i].y/=d;
310  planes[i].z/=d;
311  planes[i].w/=d;
312  }
313  }
314  }
315 
316  return planes;
317 }
318 
327  const std::vector<glm::vec4> &planes,
328  const pcl::PointXYZ &boxMin,
329  const pcl::PointXYZ &boxMax)
330 {
331  // Indexed for the 'index trick' later
332  const pcl::PointXYZ * box[] = {&boxMin, &boxMax};
333 
334  // We only need to do 6 point-plane tests
335  for (unsigned int i = 0; i < planes.size(); ++i)
336  {
337  // This is the current plane
338  const glm::vec4 &p = planes[i];
339 
340  // p-vertex selection (with the index trick)
341  // According to the plane normal we can know the
342  // indices of the positive vertex
343  const int px = p.x > 0.0f?1:0;
344  const int py = p.y > 0.0f?1:0;
345  const int pz = p.z > 0.0f?1:0;
346 
347  // Dot product
348  // project p-vertex on plane normal
349  // (How far is p-vertex from the origin)
350  const float dp =
351  (p.x*box[px]->x) +
352  (p.y*box[py]->y) +
353  (p.z*box[pz]->z) + p.w;
354 
355  // Doesn't intersect if it is behind the plane
356  if (dp < 0) {return false; }
357  }
358  return true;
359 }
360 
361 //Should only be called in OpenGL thread!
363  UASSERT(gesture_camera_ != 0);
364 
365  glm::vec3 position(currentPose_->x(), currentPose_->y(), currentPose_->z());
366  Eigen::Quaternionf quat = currentPose_->getQuaternionf();
367  glm::quat rotation(quat.w(), quat.x(), quat.y(), quat.z());
368  glm::mat4 rotateM;
369  if(!currentPose_->isNull())
370  {
371  rotateM = glm::rotate<float>(float(color_camera_to_display_rotation_)*-1.57079632679489661923132169163975144, glm::vec3(0.0f, 0.0f, 1.0f));
372 
374  {
375  // In first person mode, we directly control camera's motion.
376  gesture_camera_->SetPosition(position);
378  }
379  else
380  {
381  // In third person or top down mode, we follow the camera movement.
383  }
384  }
385 
386  glm::mat4 projectionMatrix = gesture_camera_->GetProjectionMatrix();
387  glm::mat4 viewMatrix = gesture_camera_->GetViewMatrix();
388 
389  rtabmap::Transform openglCamera = GetOpenGLCameraPose();//*rtabmap::Transform(0.0f, 0.0f, 3.0f, 0.0f, 0.0f, 0.0f);
390  // transform in same coordinate as frustum filtering
391  openglCamera *= rtabmap::Transform(
392  0.0f, 0.0f, 1.0f, 0.0f,
393  0.0f, 1.0f, 0.0f, 0.0f,
394  -1.0f, 0.0f, 0.0f, 0.0f);
395 
396  //Culling
397  std::vector<glm::vec4> planes = computeFrustumPlanes(projectionMatrix*viewMatrix, true);
398  std::vector<PointCloudDrawable*> cloudsToDraw(pointClouds_.size());
399  int oi=0;
400  for(std::map<int, PointCloudDrawable*>::const_iterator iter=pointClouds_.begin(); iter!=pointClouds_.end(); ++iter)
401  {
402  if(!mapRendering_ && iter->first > 0)
403  {
404  break;
405  }
406 
407  if(iter->second->isVisible())
408  {
409  if(intersectFrustumAABB(planes,
410  iter->second->aabbMinWorld(),
411  iter->second->aabbMaxWorld()))
412  {
413  cloudsToDraw[oi++] = iter->second;
414  }
415  }
416  }
417  cloudsToDraw.resize(oi);
418 
419  // First rendering to get depth texture
420  glEnable(GL_DEPTH_TEST);
421  glDepthFunc(GL_LESS);
422  glDepthMask(GL_TRUE);
423  glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);
424  glDisable (GL_BLEND);
425  glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
426 
427  if(backfaceCulling_)
428  {
429  glEnable(GL_CULL_FACE);
430  }
431  else
432  {
433  glDisable(GL_CULL_FACE);
434  }
435 
436  UTimer timer;
437 
438  bool onlineBlending = blending_ && gesture_camera_->GetCameraType()!=tango_gl::GestureCamera::kTopOrtho && mapRendering_ && meshRendering_ && cloudsToDraw.size()>1;
439  if(onlineBlending && fboId_)
440  {
441  // set the rendering destination to FBO
442  glBindFramebuffer(GL_FRAMEBUFFER, fboId_);
443 
444  glColorMask(GL_FALSE, GL_FALSE, GL_FALSE, GL_FALSE);
445  glClearColor(1, 1, 1, 1);
446  glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
447 
448  // Draw scene
449  for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
450  {
451  // set large distance to cam to use low res polygons for fast processing
452  (*iter)->Render(projectionMatrix, viewMatrix, meshRendering_, pointSize_, false, false, 999.0f);
453  }
454 
455  // back to normal window-system-provided framebuffer
456  glBindFramebuffer(GL_FRAMEBUFFER, 0); // unbind
457  glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);
458  }
459 
461  {
462  glClearColor(0, 0, 0, 0);
463  glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
464 
465  for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
466  {
467  // set large distance to cam to use low res polygons for fast processing
468  (*iter)->Render(projectionMatrix, viewMatrix, meshRendering_, pointSize_*10.0f, false, false, 999.0f, 0, 0, 0, 0, 0, true);
469  }
470 
471  GLubyte zValue[4];
472  glReadPixels(doubleTapPos_.x*screenWidth_, screenHeight_-doubleTapPos_.y*screenHeight_, 1, 1, GL_RGBA, GL_UNSIGNED_BYTE, zValue);
473  float fromFixed = 256.0f/255.0f;
474  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;
475 
476  if(zValueF != 0.0f)
477  {
478  zValueF = zValueF*2.0-1.0;//NDC
479  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);
480  point /= point.w;
481  gesture_camera_->SetAnchorOffset(glm::vec3(point.x, point.y, point.z) - position);
482  }
483  }
484  doubleTapOn_ = false;
485 
486  glClearColor(r_, g_, b_, 1.0f);
487  glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
488 
489  if(!currentPose_->isNull())
490  {
492  {
493  frustum_->SetPosition(position);
495  // Set the frustum scale to 4:3, this doesn't necessarily match the physical
496  // camera's aspect ratio, this is just for visualization purposes.
497  frustum_->SetScale(kFrustumScale);
498  frustum_->Render(projectionMatrix, viewMatrix);
499 
500  axis_->SetPosition(position);
502  axis_->Render(projectionMatrix, viewMatrix);
503  }
504 
505  trace_->UpdateVertexArray(position);
506  if(traceVisible_)
507  {
508  trace_->Render(projectionMatrix, viewMatrix);
509  }
510 
511  if(gridVisible_)
512  {
513  grid_->Render(projectionMatrix, viewMatrix);
514  }
515  }
516 
517  if(graphVisible_ && graph_)
518  {
519  graph_->Render(projectionMatrix, viewMatrix);
520  }
521 
522 
523  if(onlineBlending)
524  {
525  glEnable (GL_BLEND);
526  glDepthMask(GL_FALSE);
527  }
528 
529  for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
530  {
531  PointCloudDrawable * cloud = *iter;
532 
534  {
535  box_->updateVertices(cloud->aabbMinWorld(), cloud->aabbMaxWorld());
536  box_->Render(projectionMatrix, viewMatrix);
537  }
538 
539  Eigen::Vector3f cloudToCamera(
540  cloud->getPose().x() - openglCamera.x(),
541  cloud->getPose().y() - openglCamera.y(),
542  cloud->getPose().z() - openglCamera.z());
543  float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
544 
545  cloud->Render(projectionMatrix, viewMatrix, meshRendering_, pointSize_, meshRenderingTexture_, lighting_, distanceToCameraSqr, onlineBlending?depthTexture_:0, screenWidth_, screenHeight_, gesture_camera_->getNearClipPlane(), gesture_camera_->getFarClipPlane(), false, wireFrame_);
546  }
547 
548  if(onlineBlending)
549  {
550  glDisable (GL_BLEND);
551  glDepthMask(GL_TRUE);
552  }
553 
554  return (int)cloudsToDraw.size();
555 }
556 
558  gesture_camera_->SetCameraType(camera_type);
559 }
560 
562 {
563  UASSERT(currentPose_ != 0);
564  UASSERT(!pose.isNull());
565  *currentPose_ = pose;
566 }
567 
568 void Scene::setFOV(float angle)
569 {
571 }
572 void Scene::setOrthoCropFactor(float value)
573 {
575 }
576 void Scene::setGridRotation(float angleDeg)
577 {
578  float angleRad = angleDeg * DEGREE_2_RADIANS;
579  if(grid_)
580  {
581  glm::quat rot = glm::rotate(glm::quat(1,0,0,0), angleRad, glm::vec3(0, 1, 0));
582  grid_->SetRotation(rot);
583  }
584 }
585 
587 {
588  if(fov)
589  {
590  *fov = gesture_camera_->getFOV();
591  }
593 }
594 
595 void Scene::OnTouchEvent(int touch_count,
596  tango_gl::GestureCamera::TouchEvent event, float x0,
597  float y0, float x1, float y1) {
598  UASSERT(gesture_camera_ != 0);
599  if(touch_count == 3)
600  {
601  //doubletap
602  if(!doubleTapOn_)
603  {
604  doubleTapPos_.x = x0;
605  doubleTapPos_.y = y0;
606  doubleTapOn_ = true;
607  }
608  }
609  else
610  {
611  // rotate/translate/zoom
612  gesture_camera_->OnTouchEvent(touch_count, event, x0, y0, x1, y1);
613  }
614 }
615 
617  const std::map<int, rtabmap::Transform> & poses,
618  const std::multimap<int, rtabmap::Link> & links)
619 {
620  LOGI("updateGraph");
621  if(graph_)
622  {
623  delete graph_;
624  graph_ = 0;
625  }
626 
627  //create
628  if(graphVisible_)
629  {
631  graph_ = new GraphDrawable(graph_shader_program_, poses, links);
632  }
633 }
634 
635 void Scene::setGraphVisible(bool visible)
636 {
637  graphVisible_ = visible;
638 }
639 
640 void Scene::setGridVisible(bool visible)
641 {
642  gridVisible_ = visible;
643 }
644 
645 void Scene::setTraceVisible(bool visible)
646 {
647  traceVisible_ = visible;
648 }
649 
650 //Should only be called in OpenGL thread!
652  int id,
653  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
654  const pcl::IndicesPtr & indices,
655  const rtabmap::Transform & pose)
656 {
657  LOGI("add cloud %d (%d points %d indices)", id, (int)cloud->size(), indices.get()?(int)indices->size():0);
658  std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
659  if(iter != pointClouds_.end())
660  {
661  delete iter->second;
662  pointClouds_.erase(iter);
663  }
664 
665  //create
666  PointCloudDrawable * drawable = new PointCloudDrawable(cloud, indices);
667  drawable->setPose(pose);
668  pointClouds_.insert(std::make_pair(id, drawable));
669 }
670 
672  int id,
673  const Mesh & mesh,
674  const rtabmap::Transform & pose,
675  bool createWireframe)
676 {
677  LOGI("add mesh %d", id);
678  std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
679  if(iter != pointClouds_.end())
680  {
681  delete iter->second;
682  pointClouds_.erase(iter);
683  }
684 
685  //create
686  PointCloudDrawable * drawable = new PointCloudDrawable(mesh, createWireframe);
687  drawable->setPose(pose);
688  pointClouds_.insert(std::make_pair(id, drawable));
689 
690  if(!mesh.pose.isNull() && mesh.cloud->size() && (!mesh.cloud->isOrganized() || mesh.indices->size()))
691  {
692  UTimer time;
693  float height = 0.0f;
694  Eigen::Affine3f affinePose = mesh.pose.toEigen3f();
695  if(mesh.polygons.size())
696  {
697  for(unsigned int i=0; i<mesh.polygons.size(); ++i)
698  {
699  for(unsigned int j=0; j<mesh.polygons[i].vertices.size(); ++j)
700  {
701  pcl::PointXYZRGB pt = pcl::transformPoint(mesh.cloud->at(mesh.polygons[i].vertices[j]), affinePose);
702  if(pt.z < height)
703  {
704  height = pt.z;
705  }
706  }
707  }
708  }
709  else
710  {
711  if(mesh.cloud->isOrganized())
712  {
713  for(unsigned int i=0; i<mesh.indices->size(); ++i)
714  {
715  pcl::PointXYZRGB pt = pcl::transformPoint(mesh.cloud->at(mesh.indices->at(i)), affinePose);
716  if(pt.z < height)
717  {
718  height = pt.z;
719  }
720  }
721  }
722  else
723  {
724  for(unsigned int i=0; i<mesh.cloud->size(); ++i)
725  {
726  pcl::PointXYZRGB pt = pcl::transformPoint(mesh.cloud->at(i), affinePose);
727  if(pt.z < height)
728  {
729  height = pt.z;
730  }
731  }
732  }
733  }
734 
735  if(grid_->GetPosition().y == kHeightOffset.y || grid_->GetPosition().y > height)
736  {
737  grid_->SetPosition(glm::vec3(0,height,0));
738  }
739  LOGD("compute min height %f s", time.ticks());
740  }
741 }
742 
743 
744 void Scene::setCloudPose(int id, const rtabmap::Transform & pose)
745 {
746  UASSERT(!pose.isNull());
747  std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
748  if(iter != pointClouds_.end())
749  {
750  iter->second->setPose(pose);
751  }
752 }
753 
754 void Scene::setCloudVisible(int id, bool visible)
755 {
756  std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
757  if(iter != pointClouds_.end())
758  {
759  iter->second->setVisible(visible);
760  }
761 }
762 
763 bool Scene::hasCloud(int id) const
764 {
765  return pointClouds_.find(id) != pointClouds_.end();
766 }
767 
768 bool Scene::hasMesh(int id) const
769 {
770  return pointClouds_.find(id) != pointClouds_.end() && pointClouds_.at(id)->hasMesh();
771 }
772 
773 bool Scene::hasTexture(int id) const
774 {
775  return pointClouds_.find(id) != pointClouds_.end() && pointClouds_.at(id)->hasTexture();
776 }
777 
778 std::set<int> Scene::getAddedClouds() const
779 {
780  return uKeysSet(pointClouds_);
781 }
782 
783 void Scene::updateCloudPolygons(int id, const std::vector<pcl::Vertices> & polygons)
784 {
785  std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
786  if(iter != pointClouds_.end())
787  {
788  iter->second->updatePolygons(polygons);
789  }
790 }
791 
792 void Scene::updateMesh(int id, const Mesh & mesh)
793 {
794  std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
795  if(iter != pointClouds_.end())
796  {
797  iter->second->updateMesh(mesh);
798  }
799 }
800 
801 void Scene::updateGains(int id, float gainR, float gainG, float gainB)
802 {
803  std::map<int, PointCloudDrawable*>::iterator iter=pointClouds_.find(id);
804  if(iter != pointClouds_.end())
805  {
806  iter->second->setGains(gainR, gainG, gainB);
807  }
808 }
809 
810 void Scene::setGridColor(float r, float g, float b)
811 {
812  if(grid_)
813  {
814  grid_->SetColor(r, g, b);
815  }
816 }
float b_
Definition: scene.h:190
d
glm::vec3 GetPosition() const
Definition: transform.cpp:39
void Render(const glm::mat4 &projectionMatrix, const glm::mat4 &viewMatrix)
#define NULL
highp_vec4 vec4
Definition: type_vec.hpp:397
static void releaseShaderPrograms()
const glm::vec3 kHeightOffset
Definition: scene.cpp:39
Definition: UTimer.h:46
float g_
Definition: scene.h:189
void setGridVisible(bool visible)
Definition: scene.cpp:640
highp_vec3 vec3
Definition: type_vec.hpp:392
void SetRotation(const glm::quat &rotation)
Definition: transform.cpp:43
BoundingBoxDrawable * box_
Definition: scene.h:161
bool gridVisible_
Definition: scene.h:167
void updateCloudPolygons(int id, const std::vector< pcl::Vertices > &polygons)
Definition: scene.cpp:783
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
Definition: scene.cpp:595
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
bool wireFrame_
Definition: scene.h:187
void SetupViewPort(int w, int h)
Definition: scene.cpp:208
rtabmap::Transform GetOpenGLCameraPose(float *fov=0) const
Definition: scene.cpp:586
void setCloudPose(int id, const rtabmap::Transform &pose)
Definition: scene.cpp:744
f
void SetCameraType(CameraType camera_index)
void setFOV(float angle)
Definition: scene.cpp:568
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
std::map< int, PointCloudDrawable * > pointClouds_
Definition: scene.h:172
bool backfaceCulling_
Definition: scene.h:186
void setPose(const rtabmap::Transform &pose)
void setGridColor(float r, float g, float b)
Definition: scene.cpp:810
const glm::vec3 kFrustumScale
Definition: scene.cpp:48
GLuint fboId_
Definition: scene.h:191
glm::mat4 GetTransformationMatrix() const
Definition: transform.cpp:67
highp_quat quat
Quaternion of default single-precision floating-point numbers.
Definition: fwd.hpp:68
std::set< K > uKeysSet(const std::map< K, V > &m)
Definition: UStl.h:186
bool hasMesh(int id) const
Definition: scene.cpp:768
void SetWindowSize(const float width, const float height)
Definition: camera.cpp:46
float r_
Definition: scene.h:188
~Scene()
Definition: scene.cpp:108
GLsizei screenWidth_
Definition: scene.h:193
Definition: util.h:147
bool graphVisible_
Definition: scene.h:166
void clear()
Definition: scene.cpp:184
std::vector< pcl::Vertices > polygons
Definition: util.h:162
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
GLuint CreateProgram(const char *vertex_source, const char *fragment_source)
Definition: util.cpp:75
void Render(const glm::mat4 &projectionMatrix, const glm::mat4 &viewMatrix, bool meshRendering=true, float pointSize=3.0f, bool textureRendering=false, bool lighting=true, float distanceToCamSqr=0.0f, const GLuint &depthTexture=0, int screenWidth=0, int screenHeight=0, float nearClipPlane=0, float farClipPlane=0, bool packDepthToColorChannel=false, bool wireFrame=false) const
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud
Definition: util.h:159
#define LOGE(...)
GLsizei screenHeight_
Definition: scene.h:194
bool hasCloud(int id) const
Definition: scene.cpp:763
bool meshRenderingTexture_
Definition: scene.h:182
tango_gl::Frustum * frustum_
Definition: scene.h:155
unsigned int GLuint
Definition: dummy.cpp:78
const std::string kGraphVertexShader
Definition: scene.cpp:50
void DeleteResources()
Definition: scene.cpp:151
void setOrthoCropFactor(float value)
Definition: scene.cpp:572
bool lighting_
Definition: scene.h:185
float getFarClipPlane() const
Definition: camera.h:40
#define UASSERT(condition)
Wrappers of STL for convenient functions.
void updateGains(int id, float gainR, float gainG, float gainB)
Definition: scene.cpp:801
GLM_FUNC_DECL genType normalize(genType const &x)
void InitGLContent()
Definition: scene.cpp:114
rtabmap::Transform getPose() const
#define LOGD(...)
void SetFieldOfView(const float fov)
Definition: camera.cpp:52
#define true
Definition: ConvertUTF.c:57
#define GL_FALSE
Definition: dummy.cpp:79
bool isNull() const
Definition: Transform.cpp:107
Scene()
Definition: scene.cpp:71
GraphDrawable * graph_
Definition: scene.h:165
void SetCameraPose(const rtabmap::Transform &pose)
Definition: scene.cpp:561
GLuint depthTexture_
Definition: scene.h:192
bool mapRendering_
Definition: scene.h:180
const std::string kGraphFragmentShader
Definition: scene.cpp:61
void addCloud(int id, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const rtabmap::Transform &pose)
Definition: scene.cpp:651
bool blending_
Definition: scene.h:179
bool doubleTapOn_
Definition: scene.h:195
void setCloudVisible(int id, bool visible)
Definition: scene.cpp:754
std::vector< glm::vec4 > computeFrustumPlanes(const glm::mat4 &mat, bool normalize=true)
Definition: scene.cpp:254
void updateGraph(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links)
Definition: scene.cpp:616
std::set< int > getAddedClouds() const
Definition: scene.cpp:778
void SetColor(const Color &color)
bool hasTexture(int id) const
Definition: scene.cpp:773
void updateMesh(int id, const Mesh &mesh)
Definition: scene.cpp:792
cv::Point2f doubleTapPos_
Definition: scene.h:196
rtabmap::Transform pose
Definition: util.h:164
void OnTouchEvent(int touch_count, TouchEvent event, float x0, float y0, float x1, float y1)
tango_gl::Trace * trace_
Definition: scene.h:164
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
#define LOGI(...)
#define false
Definition: ConvertUTF.c:56
tango_gl::Grid * grid_
Definition: scene.h:158
void SetAnchorPosition(const glm::vec3 &pos, const glm::quat &rotation)
void SetOrthoCropFactor(float value)
Definition: camera.h:34
Eigen::Quaternionf getQuaternionf() const
Definition: Transform.cpp:354
bool intersectFrustumAABB(const std::vector< glm::vec4 > &planes, const pcl::PointXYZ &boxMin, const pcl::PointXYZ &boxMax)
Definition: scene.cpp:326
const pcl::PointXYZ & aabbMaxWorld() const
tango_gl::Axis * axis_
Definition: scene.h:152
void Render(const glm::mat4 &projection_mat, const glm::mat4 &view_mat) const
Definition: line.cpp:25
void UpdateVertexArray(const glm::vec3 &v)
Definition: trace.cpp:26
void setTraceVisible(bool visible)
Definition: scene.cpp:645
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
Definition: scene.cpp:557
void SetAnchorOffset(const glm::vec3 &pos)
ULogger class and convenient macros.
#define DEGREE_2_RADIANS
bool meshRendering_
Definition: scene.h:181
double ticks()
Definition: UTimer.cpp:110
void Render(const glm::mat4 &projection_mat, const glm::mat4 &view_mat) const
Definition: axis.cpp:53
void ClearVertexArray()
Definition: trace.cpp:37
void setGraphVisible(bool visible)
Definition: scene.cpp:635
const pcl::PointXYZ & aabbMinWorld() const
float getNearClipPlane() const
Definition: camera.h:39
static void createShaderPrograms()
void addMesh(int id, const Mesh &mesh, const rtabmap::Transform &pose, bool createWireframe=false)
Definition: scene.cpp:671
bool boundingBoxRendering_
Definition: scene.h:184
Eigen::Affine3f toEigen3f() const
Definition: Transform.cpp:344
CameraType GetCameraType() const
rtabmap::Transform glmToTransform(const glm::mat4 &mat)
Definition: util.h:126
void setGridRotation(float angleDeg)
Definition: scene.cpp:576
int Render()
Definition: scene.cpp:362
void SetPosition(const glm::vec3 &position)
Definition: transform.cpp:35
void updateVertices(const pcl::PointXYZ &min, const pcl::PointXYZ &max)
glm::mat4 GetProjectionMatrix()
Definition: camera.cpp:38
tango_gl::GestureCamera * gesture_camera_
Definition: scene.h:149
void SetScale(const glm::vec3 &scale)
Definition: transform.cpp:51
pcl::IndicesPtr indices
Definition: util.h:161
TangoSupportRotation color_camera_to_display_rotation_
Definition: scene.h:170
const tango_gl::Color kGridColor(0.85f, 0.85f, 0.85f)
float pointSize_
Definition: scene.h:183
bool traceVisible_
Definition: scene.h:168
const tango_gl::Color kTraceColor(0.66f, 0.66f, 0.66f)
rtabmap::Transform * currentPose_
Definition: scene.h:174
GLM_FUNC_DECL detail::tmat4x4< T, P > rotate(detail::tmat4x4< T, P > const &m, T const &angle, detail::tvec3< T, P > const &axis)
glm::mat4 GetViewMatrix()
Definition: camera.cpp:34
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)
GLuint graph_shader_program_
Definition: scene.h:177


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32