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),
96 textureColorSeamsHidden_(
true),
158 LOGI(
"Scene::DeleteResources()");
181 glDeleteFramebuffers(1, &
fboId_);
183 glDeleteRenderbuffers(1, &
rboId_);
195 LOGI(
"Scene::clear()");
261 LOGE(
"Setup graphic height not valid");
266 glViewport(0, 0,
w,
h);
269 UINFO(
"Setup viewport OpenGL: %dx%d",
w,
h);
273 glDeleteFramebuffers(1, &
fboId_);
275 glDeleteRenderbuffers(1, &
rboId_);
282 glGetIntegerv(GL_FRAMEBUFFER_BINDING, &originid);
286 glGenFramebuffers(1, &
fboId_);
287 glBindFramebuffer(GL_FRAMEBUFFER,
fboId_);
292 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
293 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
294 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
295 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
296 glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA,
w,
h, 0, GL_RGBA, GL_UNSIGNED_BYTE,
NULL);
297 glBindTexture(GL_TEXTURE_2D, 0);
299 glGenRenderbuffers(1, &
rboId_);
300 glBindRenderbuffer(GL_RENDERBUFFER,
rboId_);
301 glRenderbufferStorage(GL_RENDERBUFFER, GL_DEPTH_COMPONENT16,
w,
h);
302 glBindRenderbuffer(GL_RENDERBUFFER, 0);
305 glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D,
depthTexture_, 0);
306 glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_RENDERBUFFER,
rboId_);
308 GLuint status = glCheckFramebufferStatus(GL_FRAMEBUFFER);
309 UASSERT ( status == GL_FRAMEBUFFER_COMPLETE);
310 glBindFramebuffer(GL_FRAMEBUFFER, originid);
319 std::vector<glm::vec4>
planes(6);
365 for(
unsigned int i=0;
i<
planes.size(); ++
i)
390 const std::vector<glm::vec4> &planes,
391 const pcl::PointXYZ &boxMin,
392 const pcl::PointXYZ &boxMax)
398 for (
unsigned int i = 0;
i <
planes.size(); ++
i)
406 const int px =
p.x > 0.0f?1:0;
407 const int py =
p.y > 0.0f?1:0;
408 const int pz =
p.z > 0.0f?1:0;
416 (
p.z*
box[pz]->z) +
p.w;
419 if (dp < 0) {
return false; }
457 bool renderBackgroundCamera =
463 if(renderBackgroundCamera)
465 if(projectionMatrix[0][0] > arProjectionMatrix[0][0]-0.3)
467 projectionMatrix = arProjectionMatrix;
468 viewMatrix = arViewMatrix;
472 renderBackgroundCamera =
false;
479 0.0
f, 0.0
f, 1.0
f, 0.0
f,
480 0.0
f, 1.0
f, 0.0
f, 0.0
f,
481 -1.0
f, 0.0
f, 0.0
f, 0.0
f);
485 std::vector<PointCloudDrawable*> cloudsToDraw(
pointClouds_.size());
487 int positiveCloudIds = 0;
500 if(
iter->second->isVisible())
503 iter->second->aabbMinWorld(),
504 iter->second->aabbMaxWorld()))
506 cloudsToDraw[oi++] =
iter->second;
510 cloudsToDraw.resize(oi);
513 glEnable(GL_DEPTH_TEST);
514 glDepthFunc(GL_LESS);
515 glDepthMask(GL_TRUE);
516 glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);
517 glDisable (GL_BLEND);
518 glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
522 glEnable(GL_CULL_FACE);
526 glDisable(GL_CULL_FACE);
529 bool onlineBlending =
531 occlusionMesh.
cloud.get() &&
532 occlusionMesh.
cloud->size()) ||
536 (positiveCloudIds > 1 || (renderBackgroundCamera &&
wireFrame_)));
538 if(onlineBlending &&
fboId_)
541 glGetIntegerv(GL_FRAMEBUFFER_BINDING, &originid);
544 glBindFramebuffer(GL_FRAMEBUFFER,
fboId_);
546 glClearColor(0, 0, 0, 0);
547 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
550 for(std::vector<PointCloudDrawable*>::const_iterator
iter=cloudsToDraw.begin();
iter!=cloudsToDraw.end(); ++
iter)
552 Eigen::Vector3f cloudToCamera(
553 (*iter)->getPose().x() - openglCamera.
x(),
554 (*iter)->getPose().y() - openglCamera.
y(),
555 (*iter)->getPose().z() - openglCamera.
z());
556 float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
557 (*iter)->Render(projectionMatrix, viewMatrix,
meshRendering_,
pointSize_,
false,
false, distanceToCameraSqr, 0, 0, 0, 0, 0,
true);
563 drawable.
Render(projectionMatrix, viewMatrix,
true,
pointSize_,
false,
false, 0, 0, 0, 0, 0, 0,
true);
567 glBindFramebuffer(GL_FRAMEBUFFER, originid);
572 glClearColor(0, 0, 0, 0);
573 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
576 for(std::vector<PointCloudDrawable*>::const_iterator
iter=cloudsToDraw.begin();
iter!=cloudsToDraw.end(); ++
iter)
578 Eigen::Vector3f cloudToCamera(
579 (*iter)->getPose().x() - openglCamera.
x(),
580 (*iter)->getPose().y() - openglCamera.
y(),
581 (*iter)->getPose().z() - openglCamera.
z());
582 float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
584 (*iter)->Render(projectionMatrix, viewMatrix,
meshRendering_,
pointSize_*10.0
f,
false,
false, distanceToCameraSqr, 0, 0, 0, 0, 0,
true);
589 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;
593 zValueF = zValueF*2.0-1.0;
601 glClearColor(
r_,
g_,
b_, 1.0
f);
602 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
604 if(renderBackgroundCamera && (!onlineBlending || !
meshRendering_))
625 glm::vec3 positionCamera(cameraFrame.
x(), cameraFrame.
y(), cameraFrame.
z());
627 glm::quat rotationCamera(quatCamera.w(), quatCamera.x(), quatCamera.y(), quatCamera.z());
662 for(std::vector<PointCloudDrawable*>::const_iterator
iter=cloudsToDraw.begin();
iter!=cloudsToDraw.end(); ++
iter)
672 Eigen::Vector3f cloudToCamera(
675 cloud->
getPose().
z() - openglCamera.
z());
676 float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
678 cloud->
Render(projectionMatrix, viewMatrix,
meshRendering_,
pointSize_,
meshRenderingTexture_,
lighting_, distanceToCameraSqr, onlineBlending?
depthTexture_:0,
screenWidth_,
screenHeight_,
gesture_camera_->
getNearClipPlane(),
gesture_camera_->
getFarClipPlane(),
false,
wireFrame_,
textureColorSeamsHidden_);
684 glDisable(GL_CULL_FACE);
686 quad->
Render(projectionMatrix, viewMatrix);
687 glEnable(GL_CULL_FACE);
697 glDisable (GL_BLEND);
698 glDepthMask(GL_TRUE);
702 glDisable (GL_DEPTH_TEST);
708 line->
Render(projectionMatrix, viewMatrix);
715 glDisable(GL_CULL_FACE);
718 if(
iter->first!=55556)
721 quad->
Render(projectionMatrix, viewMatrix);
728 glDisable(GL_CULL_FACE);
732 circle->Render(projectionMatrix, viewMatrix);
737 glDisable(GL_CULL_FACE);
741 viewMatrixRotInv[3][0] = 0;
742 viewMatrixRotInv[3][1] = 0;
743 viewMatrixRotInv[3][2] = 0;
748 text->Render(projectionMatrix, viewMatrix, viewMatrixRotInv);
755 iter->second->Render(projectionMatrix, viewMatrix);
758 return (
int)cloudsToDraw.size();
804 float y0,
float x1,
float y1) {
824 const std::map<int, rtabmap::Transform> & poses,
825 const std::multimap<int, rtabmap::Link> & links)
859 LOGI(
"add marker %d",
id);
860 std::map<int, tango_gl::Axis*>::iterator
iter=
markers_.find(
id);
867 markers_.insert(std::make_pair(
id, drawable));
874 std::map<int, tango_gl::Axis*>::iterator
iter=
markers_.find(
id);
890 std::map<int, tango_gl::Axis*>::iterator
iter=
markers_.find(
id);
904 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
905 const pcl::IndicesPtr & indices,
908 LOGI(
"add cloud %d (%d points %d indices)",
id, (
int)cloud->size(),
indices.get()?(
int)
indices->size():0);
931 bool createWireframe)
933 LOGI(
"add mesh %d",
id);
950 for(
unsigned int j=0;
j<mesh.
polygons[
i].vertices.size(); ++
j)
962 if(mesh.
cloud->isOrganized())
964 for(
unsigned int i=0;
i<mesh.
indices->size(); ++
i)
975 for(
unsigned int i=0;
i<mesh.
cloud->size(); ++
i)
990 LOGD(
"compute min height %f s",
time.ticks());
996 const cv::Point3f & pt1,
997 const cv::Point3f & pt2,
1000 LOGI(
"add line %d",
id);
1006 std::vector<glm::vec3>
vertices(2);
1015 lines_.insert(std::make_pair(
id, line));
1020 std::map<int, tango_gl::Line*>::iterator
iter=
lines_.find(
id);
1023 delete iter->second;
1030 const std::string & text,
1035 LOGI(
"add text %d",
id);
1040 texts_.insert(std::make_pair(
id, textD));
1044 std::map<int, TextDrawable*>::iterator
iter=
texts_.find(
id);
1047 delete iter->second;
1060 std::map<int, QuadColor*>::iterator
iter=
quads_.find(
id);
1063 delete iter->second;
1072 quads_.insert(std::make_pair(
id, quad));
1093 quads_.insert(std::make_pair(
id, quad));
1098 std::map<int, QuadColor*>::iterator
iter=
quads_.find(
id);
1101 delete iter->second;
1119 std::map<int, tango_gl::Circle*>::iterator
iter=
circles_.find(
id);
1122 delete iter->second;
1136 std::map<int, tango_gl::Circle*>::iterator
iter=
circles_.find(
id);
1139 delete iter->second;
1155 iter->second->setPose(pose);
1164 iter->second->setVisible(visible);
1193 iter->second->updatePolygons(polygons);
1202 iter->second->updateMesh(mesh);
1211 iter->second->setGains(gainR, gainG, gainB);