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" 82 color_camera_to_display_rotation_(ROTATION_0),
84 graph_shader_program_(0),
88 meshRenderingTexture_(
true),
90 boundingBoxRendering_(
false),
92 backfaceCulling_(
true),
153 LOGI(
"Scene::DeleteResources()");
174 glDeleteFramebuffers(1, &
fboId_);
186 LOGI(
"Scene::clear()");
210 LOGE(
"Setup graphic height not valid");
214 glViewport(0, 0, w, h);
219 glDeleteFramebuffers(1, &
fboId_);
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);
237 glGenFramebuffers(1, &
fboId_);
238 glBindFramebuffer(GL_FRAMEBUFFER,
fboId_);
241 glFramebufferTexture2D(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_TEXTURE_2D,
depthTexture_, 0);
243 GLuint status = glCheckFramebufferStatus(GL_FRAMEBUFFER);
244 if ( status != GL_FRAMEBUFFER_COMPLETE)
246 LOGE(
"Frame buffer cannot be generated! Status: %in", status);
248 glBindFramebuffer(GL_FRAMEBUFFER,0);
257 std::vector<glm::vec4> planes(6);
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];
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];
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];
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];
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];
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];
303 for(
unsigned int i=0;i<planes.size(); ++i)
307 float d =
std::sqrt(planes[i].x * planes[i].x + planes[i].y * planes[i].y + planes[i].z * planes[i].z);
327 const std::vector<glm::vec4> &planes,
328 const pcl::PointXYZ &boxMin,
329 const pcl::PointXYZ &boxMax)
332 const pcl::PointXYZ * box[] = {&boxMin, &boxMax};
335 for (
unsigned int i = 0; i < planes.size(); ++i)
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;
353 (p.
z*box[pz]->z) + p.
w;
356 if (dp < 0) {
return false; }
392 0.0
f, 0.0
f, 1.0
f, 0.0
f,
393 0.0
f, 1.0
f, 0.0
f, 0.0
f,
394 -1.0
f, 0.0
f, 0.0
f, 0.0
f);
398 std::vector<PointCloudDrawable*> cloudsToDraw(
pointClouds_.size());
407 if(iter->second->isVisible())
410 iter->second->aabbMinWorld(),
411 iter->second->aabbMaxWorld()))
413 cloudsToDraw[oi++] = iter->second;
417 cloudsToDraw.resize(oi);
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);
429 glEnable(GL_CULL_FACE);
433 glDisable(GL_CULL_FACE);
439 if(onlineBlending &&
fboId_)
442 glBindFramebuffer(GL_FRAMEBUFFER,
fboId_);
445 glClearColor(1, 1, 1, 1);
446 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
449 for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
456 glBindFramebuffer(GL_FRAMEBUFFER, 0);
457 glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);
462 glClearColor(0, 0, 0, 0);
463 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
465 for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
468 (*iter)->Render(projectionMatrix, viewMatrix,
meshRendering_,
pointSize_*10.0
f,
false,
false, 999.0f, 0, 0, 0, 0, 0,
true);
473 float fromFixed = 256.0f/255.0f;
474 float zValueF = float(zValue[0]/255.0
f)*fromFixed + float(zValue[1]/255.0
f)*fromFixed/255.0f + float(zValue[2]/255.0
f)*fromFixed/65025.0f + float(zValue[3]/255.0
f)*fromFixed/160581375.0f;
478 zValueF = zValueF*2.0-1.0;
486 glClearColor(
r_,
g_,
b_, 1.0
f);
487 glClear(GL_DEPTH_BUFFER_BIT | GL_COLOR_BUFFER_BIT);
529 for(std::vector<PointCloudDrawable*>::const_iterator iter=cloudsToDraw.begin(); iter!=cloudsToDraw.end(); ++iter)
539 Eigen::Vector3f cloudToCamera(
542 cloud->
getPose().
z() - openglCamera.
z());
543 float distanceToCameraSqr = cloudToCamera[0]*cloudToCamera[0] + cloudToCamera[1]*cloudToCamera[1] + cloudToCamera[2]*cloudToCamera[2];
545 cloud->
Render(projectionMatrix, viewMatrix,
meshRendering_,
pointSize_,
meshRenderingTexture_,
lighting_, distanceToCameraSqr, onlineBlending?
depthTexture_:0,
screenWidth_,
screenHeight_,
gesture_camera_->
getNearClipPlane(),
gesture_camera_->
getFarClipPlane(),
false,
wireFrame_);
550 glDisable (GL_BLEND);
551 glDepthMask(GL_TRUE);
554 return (
int)cloudsToDraw.size();
597 float y0,
float x1,
float y1) {
617 const std::map<int, rtabmap::Transform> & poses,
618 const std::multimap<int, rtabmap::Link> & links)
653 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
654 const pcl::IndicesPtr & indices,
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);
675 bool createWireframe)
677 LOGI(
"add mesh %d",
id);
678 std::map<int, PointCloudDrawable*>::iterator iter=
pointClouds_.find(
id);
697 for(
unsigned int i=0; i<mesh.
polygons.size(); ++i)
699 for(
unsigned int j=0; j<mesh.
polygons[i].vertices.size(); ++j)
711 if(mesh.
cloud->isOrganized())
713 for(
unsigned int i=0; i<mesh.
indices->size(); ++i)
724 for(
unsigned int i=0; i<mesh.
cloud->size(); ++i)
739 LOGD(
"compute min height %f s", time.
ticks());
747 std::map<int, PointCloudDrawable*>::iterator iter=
pointClouds_.find(
id);
750 iter->second->setPose(pose);
756 std::map<int, PointCloudDrawable*>::iterator iter=
pointClouds_.find(
id);
759 iter->second->setVisible(visible);
785 std::map<int, PointCloudDrawable*>::iterator iter=
pointClouds_.find(
id);
788 iter->second->updatePolygons(polygons);
794 std::map<int, PointCloudDrawable*>::iterator iter=
pointClouds_.find(
id);
797 iter->second->updateMesh(mesh);
803 std::map<int, PointCloudDrawable*>::iterator iter=
pointClouds_.find(
id);
806 iter->second->setGains(gainR, gainG, gainB);
void Render(const glm::mat4 &projectionMatrix, const glm::mat4 &viewMatrix)
static void releaseShaderPrograms()
const glm::vec3 kHeightOffset
void setGridVisible(bool visible)
BoundingBoxDrawable * box_
void updateCloudPolygons(int id, const std::vector< pcl::Vertices > &polygons)
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
void SetupViewPort(int w, int h)
rtabmap::Transform GetOpenGLCameraPose(float *fov=0) const
void setCloudPose(int id, const rtabmap::Transform &pose)
void SetCameraType(CameraType camera_index)
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
std::map< int, PointCloudDrawable * > pointClouds_
void setPose(const rtabmap::Transform &pose)
void setGridColor(float r, float g, float b)
const glm::vec3 kFrustumScale
highp_quat quat
Quaternion of default single-precision floating-point numbers.
std::set< K > uKeysSet(const std::map< K, V > &m)
bool hasMesh(int id) const
void SetWindowSize(const float width, const float height)
std::vector< pcl::Vertices > polygons
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
GLuint CreateProgram(const char *vertex_source, const char *fragment_source)
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
bool hasCloud(int id) const
bool meshRenderingTexture_
tango_gl::Frustum * frustum_
const std::string kGraphVertexShader
void setOrthoCropFactor(float value)
float getFarClipPlane() const
#define UASSERT(condition)
Wrappers of STL for convenient functions.
void updateGains(int id, float gainR, float gainG, float gainB)
GLM_FUNC_DECL genType normalize(genType const &x)
rtabmap::Transform getPose() const
void SetFieldOfView(const float fov)
void SetCameraPose(const rtabmap::Transform &pose)
const std::string kGraphFragmentShader
void addCloud(int id, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const rtabmap::Transform &pose)
void setCloudVisible(int id, bool visible)
std::vector< glm::vec4 > computeFrustumPlanes(const glm::mat4 &mat, bool normalize=true)
void updateGraph(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links)
std::set< int > getAddedClouds() const
void SetColor(const Color &color)
bool hasTexture(int id) const
void updateMesh(int id, const Mesh &mesh)
cv::Point2f doubleTapPos_
void OnTouchEvent(int touch_count, TouchEvent event, float x0, float y0, float x1, float y1)
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
void SetAnchorPosition(const glm::vec3 &pos, const glm::quat &rotation)
void SetOrthoCropFactor(float value)
bool intersectFrustumAABB(const std::vector< glm::vec4 > &planes, const pcl::PointXYZ &boxMin, const pcl::PointXYZ &boxMax)
const pcl::PointXYZ & aabbMaxWorld() const
void Render(const glm::mat4 &projection_mat, const glm::mat4 &view_mat) const
void UpdateVertexArray(const glm::vec3 &v)
void setTraceVisible(bool visible)
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
void SetAnchorOffset(const glm::vec3 &pos)
ULogger class and convenient macros.
void Render(const glm::mat4 &projection_mat, const glm::mat4 &view_mat) const
void setGraphVisible(bool visible)
const pcl::PointXYZ & aabbMinWorld() const
float getNearClipPlane() const
static void createShaderPrograms()
void addMesh(int id, const Mesh &mesh, const rtabmap::Transform &pose, bool createWireframe=false)
bool boundingBoxRendering_
CameraType GetCameraType() const
rtabmap::Transform glmToTransform(const glm::mat4 &mat)
void setGridRotation(float angleDeg)
void updateVertices(const pcl::PointXYZ &min, const pcl::PointXYZ &max)
glm::mat4 GetProjectionMatrix()
tango_gl::GestureCamera * gesture_camera_
TangoSupportRotation color_camera_to_display_rotation_
const tango_gl::Color kGridColor(0.85f, 0.85f, 0.85f)
const tango_gl::Color kTraceColor(0.66f, 0.66f, 0.66f)
rtabmap::Transform * currentPose_
glm::mat4 GetViewMatrix()
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)
GLuint graph_shader_program_