scene.h
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 #ifndef TANGO_POINT_CLOUD_SCENE_H_
00018 #define TANGO_POINT_CLOUD_SCENE_H_
00019 
00020 #include <jni.h>
00021 #include <memory>
00022 #include <set>
00023 
00024 #include <tango_client_api.h>  // NOLINT
00025 #include <tango-gl/axis.h>
00026 #include <tango-gl/camera.h>
00027 #include <tango-gl/color.h>
00028 #include <tango-gl/gesture_camera.h>
00029 #include <tango-gl/grid.h>
00030 #include <tango-gl/frustum.h>
00031 #include <tango-gl/trace.h>
00032 #include <tango-gl/transform.h>
00033 #include <tango-gl/util.h>
00034 
00035 #include <rtabmap/core/Transform.h>
00036 #include <rtabmap/core/Link.h>
00037 
00038 #include <point_cloud_drawable.h>
00039 #include <graph_drawable.h>
00040 #include <bounding_box_drawable.h>
00041 
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 
00045 // Scene provides OpenGL drawable objects and renders them for visualization.
00046 class Scene {
00047  public:
00048   // Constructor and destructor.
00049   Scene();
00050   ~Scene();
00051 
00052   // Allocate OpenGL resources for rendering.
00053   void InitGLContent();
00054 
00055   // Release non-OpenGL allocated resources.
00056   void DeleteResources();
00057 
00058   // Setup GL view port.
00059   void SetupViewPort(int w, int h);
00060   int getViewPortWidth() const {return screenWidth_;}
00061   int getViewPortHeight() const {return screenHeight_;}
00062 
00063   void setScreenRotation(TangoSupportRotation colorCameraToDisplayRotation) {color_camera_to_display_rotation_ = colorCameraToDisplayRotation;}
00064 
00065   void clear(); // removed all point clouds
00066 
00067   // Render loop.
00068   // @param: cur_pose_transformation, latest pose's transformation.
00069   // @param: point_cloud_transformation, pose transformation at point cloud
00070   //         frame's timestamp.
00071   // @param: point_cloud_vertices, point cloud's vertices of the current point
00072   //         frame.
00073   int Render();
00074 
00075   // Set render camera's viewing angle, first person, third person or top down.
00076   //
00077   // @param: camera_type, camera type includes first person, third person and
00078   //         top down
00079   void SetCameraType(tango_gl::GestureCamera::CameraType camera_type);
00080 
00081   void SetCameraPose(const rtabmap::Transform & pose);
00082   rtabmap::Transform GetCameraPose() const {return currentPose_!=0?*currentPose_:rtabmap::Transform();}
00083   rtabmap::Transform GetOpenGLCameraPose(float * fov = 0) const;
00084 
00085   // Touch event passed from android activity. This function only support two
00086   // touches.
00087   //
00088   // @param: touch_count, total count for touches.
00089   // @param: event, touch event of current touch.
00090   // @param: x0, normalized touch location for touch 0 on x axis.
00091   // @param: y0, normalized touch location for touch 0 on y axis.
00092   // @param: x1, normalized touch location for touch 1 on x axis.
00093   // @param: y1, normalized touch location for touch 1 on y axis.
00094   void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event,
00095                     float x0, float y0, float x1, float y1);
00096 
00097   void updateGraph(
00098                 const std::map<int, rtabmap::Transform> & poses,
00099                 const std::multimap<int, rtabmap::Link> & links);
00100 
00101   void setGraphVisible(bool visible);
00102   void setGridVisible(bool visible);
00103   void setTraceVisible(bool visible);
00104 
00105   void addCloud(
00106                   int id,
00107                   const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00108                   const pcl::IndicesPtr & indices,
00109                   const rtabmap::Transform & pose);
00110   void addMesh(
00111                 int id,
00112                 const Mesh & mesh,
00113                 const rtabmap::Transform & pose,
00114                 bool createWireframe = false);
00115 
00116   void setCloudPose(int id, const rtabmap::Transform & pose);
00117   void setCloudVisible(int id, bool visible);
00118   bool hasCloud(int id) const;
00119   bool hasMesh(int id) const;
00120   bool hasTexture(int id) const;
00121   std::set<int> getAddedClouds() const;
00122   void updateCloudPolygons(int id, const std::vector<pcl::Vertices> & polygons);
00123   void updateMesh(int id, const Mesh & mesh);
00124   void updateGains(int id, float gainR, float gainG, float gainB);
00125 
00126   void setBlending(bool enabled) {blending_ = enabled;}
00127   void setMapRendering(bool enabled) {mapRendering_ = enabled;}
00128   void setMeshRendering(bool enabled, bool withTexture) {meshRendering_ = enabled; meshRenderingTexture_ = withTexture;}
00129   void setPointSize(float size) {pointSize_ = size;}
00130   void setFOV(float angle);
00131   void setOrthoCropFactor(float value);
00132   void setGridRotation(float angleDeg);
00133   void setLighting(bool enabled) {lighting_ = enabled;}
00134   void setBackfaceCulling(bool enabled) {backfaceCulling_ = enabled;}
00135   void setWireframe(bool enabled) {wireFrame_ = enabled;}
00136   void setBackgroundColor(float r, float g, float b) {r_=r; g_=g; b_=b;} // 0.0f <> 1.0f
00137   void setGridColor(float r, float g, float b);
00138 
00139   bool isBlending() const {return blending_;}
00140   bool isMapRendering() const {return mapRendering_;}
00141   bool isMeshRendering() const {return meshRendering_;}
00142   bool isMeshTexturing() const {return meshRendering_ && meshRenderingTexture_;}
00143   float getPointSize() const {return pointSize_;}
00144   bool isLighting() const {return lighting_;}
00145   bool isBackfaceCulling() const {return backfaceCulling_;}
00146 
00147  private:
00148   // Camera object that allows user to use touch input to interact with.
00149   tango_gl::GestureCamera* gesture_camera_;
00150 
00151   // Device axis (in device frame of reference).
00152   tango_gl::Axis* axis_;
00153 
00154   // Device frustum.
00155   tango_gl::Frustum* frustum_;
00156 
00157   // Ground grid.
00158   tango_gl::Grid* grid_;
00159 
00160   // Bounding box
00161   BoundingBoxDrawable * box_;
00162 
00163   // Trace of pose data.
00164   tango_gl::Trace* trace_;
00165   GraphDrawable * graph_;
00166   bool graphVisible_;
00167   bool gridVisible_;
00168   bool traceVisible_;
00169 
00170   TangoSupportRotation color_camera_to_display_rotation_;
00171 
00172   std::map<int, PointCloudDrawable*> pointClouds_;
00173 
00174   rtabmap::Transform * currentPose_;
00175 
00176   // Shader to display point cloud.
00177   GLuint graph_shader_program_;
00178 
00179   bool blending_;
00180   bool mapRendering_;
00181   bool meshRendering_;
00182   bool meshRenderingTexture_;
00183   float pointSize_;
00184   bool boundingBoxRendering_;
00185   bool lighting_;
00186   bool backfaceCulling_;
00187   bool wireFrame_;
00188   float r_;
00189   float g_;
00190   float b_;
00191   GLuint fboId_;
00192   GLuint depthTexture_;
00193   GLsizei screenWidth_;
00194   GLsizei screenHeight_;
00195   bool doubleTapOn_;
00196   cv::Point2f doubleTapPos_;
00197 };
00198 
00199 #endif  // TANGO_POINT_CLOUD_SCENE_H_


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