27 #include <pcl/common/transforms.h>
28 #include <pcl/common/common.h>
51 "precision mediump float;\n"
52 "precision mediump int;\n"
53 "attribute vec3 vertex;\n"
54 "uniform vec3 color;\n"
56 "varying vec3 v_color;\n"
58 " gl_Position = mvp*vec4(vertex.x, vertex.y, vertex.z, 1.0);\n"
62 "precision mediump float;\n"
63 "precision mediump int;\n"
64 "varying vec3 v_color;\n"
66 " gl_FragColor = vec4(v_color.z, v_color.y, v_color.x, 1.0);\n"
72 background_renderer_(0),
83 frustumVisible_(
true),
86 graph_shader_program_(0),
90 meshRenderingTexture_(
true),
92 boundingBoxRendering_(
false),
94 backfaceCulling_(
true),
156 LOGI(
"Scene::DeleteResources()");
178 glDeleteFramebuffers(1, &
fboId_);
180 glDeleteRenderbuffers(1, &
rboId_);
192 LOGI(
"Scene::clear()");
221 LOGE(
"Setup graphic height not valid");
226 glViewport(0, 0,
w,
h);
229 UINFO(
"Setup viewport OpenGL: %dx%d",
w,
h);
233 glDeleteFramebuffers(1, &
fboId_);
235 glDeleteRenderbuffers(1, &
rboId_);
242 glGetIntegerv(GL_FRAMEBUFFER_BINDING, &originid);
246 glGenFramebuffers(1, &
fboId_);
247 glBindFramebuffer(GL_FRAMEBUFFER,
fboId_);
252 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
253 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
254 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
255 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
256 glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA,
w,
h, 0, GL_RGBA, GL_UNSIGNED_BYTE,
NULL);
257 glBindTexture(GL_TEXTURE_2D, 0);
259 glGenRenderbuffers(1, &
rboId_);
260 glBindRenderbuffer(GL_RENDERBUFFER,
rboId_);
261 glRenderbufferStorage(GL_RENDERBUFFER, GL_DEPTH_COMPONENT16,
w,
h);
262 glBindRenderbuffer(GL_RENDERBUFFER, 0);
265 glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D,
depthTexture_, 0);
266 glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_RENDERBUFFER,
rboId_);
268 GLuint status = glCheckFramebufferStatus(GL_FRAMEBUFFER);
269 UASSERT ( status == GL_FRAMEBUFFER_COMPLETE);
270 glBindFramebuffer(GL_FRAMEBUFFER, originid);
279 std::vector<glm::vec4>
planes(6);
325 for(
unsigned int i=0;
i<
planes.size(); ++
i)
350 const std::vector<glm::vec4> &planes,
351 const pcl::PointXYZ &boxMin,
352 const pcl::PointXYZ &boxMax)
358 for (
unsigned int i = 0;
i <
planes.size(); ++
i)
366 const int px =
p.x > 0.0f?1:0;
367 const int py =
p.y > 0.0f?1:0;
368 const int pz =
p.z > 0.0f?1:0;
376 (
p.z*
box[pz]->z) +
p.w;
379 if (dp < 0) {
return false; }
417 bool renderBackgroundCamera =
423 if(renderBackgroundCamera)
425 if(projectionMatrix[0][0] > arProjectionMatrix[0][0]-0.3)
427 projectionMatrix = arProjectionMatrix;
428 viewMatrix = arViewMatrix;
432 renderBackgroundCamera =
false;
439 0.0
f, 0.0
f, 1.0
f, 0.0
f,
440 0.0
f, 1.0
f, 0.0
f, 0.0
f,
441 -1.0
f, 0.0
f, 0.0
f, 0.0
f);
445 std::vector<PointCloudDrawable*> cloudsToDraw(
pointClouds_.size());
454 if(
iter->second->isVisible())
457 iter->second->aabbMinWorld(),
458 iter->second->aabbMaxWorld()))
460 cloudsToDraw[oi++] =
iter->second;
464 cloudsToDraw.resize(oi);
467 glEnable(GL_DEPTH_TEST);
468 glDepthFunc(GL_LESS);
469 glDepthMask(GL_TRUE);
470 glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);
471 glDisable (GL_BLEND);
472 glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
476 glEnable(GL_CULL_FACE);
480 glDisable(GL_CULL_FACE);
483 bool onlineBlending =
485 occlusionMesh.
cloud.get() &&
486 occlusionMesh.
cloud->size()) ||
490 (cloudsToDraw.size() > 1 || (renderBackgroundCamera &&
wireFrame_)));
492 if(onlineBlending &&
fboId_)
495 glGetIntegerv(GL_FRAMEBUFFER_BINDING, &originid);
498 glBindFramebuffer(GL_FRAMEBUFFER,
fboId_);
500 glClearColor(0, 0, 0, 0);
501 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
504 for(std::vector<PointCloudDrawable*>::const_iterator
iter=cloudsToDraw.begin();
iter!=cloudsToDraw.end(); ++
iter)
506 Eigen::Vector3f cloudToCamera(
507 (*iter)->getPose().x() - openglCamera.
x(),
508 (*iter)->getPose().y() - openglCamera.
y(),
509 (*iter)->getPose().z() - openglCamera.
z());
510 float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
511 (*iter)->Render(projectionMatrix, viewMatrix,
meshRendering_,
pointSize_,
false,
false, distanceToCameraSqr, 0, 0, 0, 0, 0,
true);
517 drawable.
Render(projectionMatrix, viewMatrix,
true,
pointSize_,
false,
false, 0, 0, 0, 0, 0, 0,
true);
521 glBindFramebuffer(GL_FRAMEBUFFER, originid);
526 glClearColor(0, 0, 0, 0);
527 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
530 for(std::vector<PointCloudDrawable*>::const_iterator
iter=cloudsToDraw.begin();
iter!=cloudsToDraw.end(); ++
iter)
532 Eigen::Vector3f cloudToCamera(
533 (*iter)->getPose().x() - openglCamera.
x(),
534 (*iter)->getPose().y() - openglCamera.
y(),
535 (*iter)->getPose().z() - openglCamera.
z());
536 float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
538 (*iter)->Render(projectionMatrix, viewMatrix,
meshRendering_,
pointSize_*10.0
f,
false,
false, distanceToCameraSqr, 0, 0, 0, 0, 0,
true);
543 float zValueF =
float(zValue[0]/255.0
f) +
float(zValue[1]/255.0
f)/255.0f +
float(zValue[2]/255.0
f)/65025.0f +
float(zValue[3]/255.0
f)/160581375.0f;
547 zValueF = zValueF*2.0-1.0;
555 glClearColor(
r_,
g_,
b_, 1.0
f);
556 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
558 if(renderBackgroundCamera && (!onlineBlending || !
meshRendering_))
579 glm::vec3 positionCamera(cameraFrame.
x(), cameraFrame.
y(), cameraFrame.
z());
581 glm::quat rotationCamera(quatCamera.w(), quatCamera.x(), quatCamera.y(), quatCamera.z());
616 for(std::vector<PointCloudDrawable*>::const_iterator
iter=cloudsToDraw.begin();
iter!=cloudsToDraw.end(); ++
iter)
626 Eigen::Vector3f cloudToCamera(
629 cloud->
getPose().
z() - openglCamera.
z());
630 float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
632 cloud->
Render(projectionMatrix, viewMatrix,
meshRendering_,
pointSize_,
meshRenderingTexture_,
lighting_, distanceToCameraSqr, onlineBlending?
depthTexture_:0,
screenWidth_,
screenHeight_,
gesture_camera_->
getNearClipPlane(),
gesture_camera_->
getFarClipPlane(),
false,
wireFrame_);
642 glDisable (GL_BLEND);
643 glDepthMask(GL_TRUE);
649 iter->second->Render(projectionMatrix, viewMatrix);
652 return (
int)cloudsToDraw.size();
698 float y0,
float x1,
float y1) {
718 const std::map<int, rtabmap::Transform> & poses,
719 const std::multimap<int, rtabmap::Link> & links)
753 LOGI(
"add marker %d",
id);
754 std::map<int, tango_gl::Axis*>::iterator
iter=
markers_.find(
id);
761 markers_.insert(std::make_pair(
id, drawable));
768 std::map<int, tango_gl::Axis*>::iterator
iter=
markers_.find(
id);
784 std::map<int, tango_gl::Axis*>::iterator
iter=
markers_.find(
id);
798 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
799 const pcl::IndicesPtr & indices,
802 LOGI(
"add cloud %d (%d points %d indices)",
id, (
int)cloud->size(),
indices.get()?(
int)
indices->size():0);
820 bool createWireframe)
822 LOGI(
"add mesh %d",
id);
844 for(
unsigned int j=0;
j<mesh.
polygons[
i].vertices.size(); ++
j)
856 if(mesh.
cloud->isOrganized())
858 for(
unsigned int i=0;
i<mesh.
indices->size(); ++
i)
869 for(
unsigned int i=0;
i<mesh.
cloud->size(); ++
i)
884 LOGD(
"compute min height %f s",
time.ticks());
895 iter->second->setPose(pose);
904 iter->second->setVisible(visible);
933 iter->second->updatePolygons(polygons);
942 iter->second->updateMesh(mesh);
951 iter->second->setGains(gainR, gainG, gainB);