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 
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/point_types.h>
00043 
00044 // Scene provides OpenGL drawable objects and renders them for visualization.
00045 class Scene {
00046  public:
00047   // Constructor and destructor.
00048   Scene();
00049   ~Scene();
00050 
00051   // Allocate OpenGL resources for rendering.
00052   void InitGLContent();
00053 
00054   // Release non-OpenGL allocated resources.
00055   void DeleteResources();
00056 
00057   // Setup GL view port.
00058   void SetupViewPort(int w, int h);
00059 
00060   void clear(); // removed all point clouds
00061 
00062   // Render loop.
00063   // @param: cur_pose_transformation, latest pose's transformation.
00064   // @param: point_cloud_transformation, pose transformation at point cloud
00065   //         frame's timestamp.
00066   // @param: point_cloud_vertices, point cloud's vertices of the current point
00067   //         frame.
00068   int Render();
00069 
00070   // Set render camera's viewing angle, first person, third person or top down.
00071   //
00072   // @param: camera_type, camera type includes first person, third person and
00073   //         top down
00074   void SetCameraType(tango_gl::GestureCamera::CameraType camera_type);
00075 
00076   void SetCameraPose(const rtabmap::Transform & pose);
00077   rtabmap::Transform GetCameraPose() const {return currentPose_!=0?*currentPose_:rtabmap::Transform();}
00078   rtabmap::Transform GetOpenGLCameraPose(float * fov) const;
00079 
00080   // Touch event passed from android activity. This function only support two
00081   // touches.
00082   //
00083   // @param: touch_count, total count for touches.
00084   // @param: event, touch event of current touch.
00085   // @param: x0, normalized touch location for touch 0 on x axis.
00086   // @param: y0, normalized touch location for touch 0 on y axis.
00087   // @param: x1, normalized touch location for touch 1 on x axis.
00088   // @param: y1, normalized touch location for touch 1 on y axis.
00089   void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event,
00090                     float x0, float y0, float x1, float y1);
00091 
00092   void updateGraph(
00093                 const std::map<int, rtabmap::Transform> & poses,
00094                 const std::multimap<int, rtabmap::Link> & links);
00095 
00096   void setGraphVisible(bool visible);
00097   void setTraceVisible(bool visible);
00098 
00099   void addCloud(
00100                   int id,
00101                   const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00102                   const std::vector<pcl::Vertices> & polygons,
00103                   const rtabmap::Transform & pose,
00104                   const cv::Mat & image = cv::Mat());
00105 
00106   void setCloudPose(int id, const rtabmap::Transform & pose);
00107   void setCloudVisible(int id, bool visible);
00108   bool hasCloud(int id) const;
00109   std::set<int> getAddedClouds() const;
00110 
00111   void setMapRendering(bool enabled) {mapRendering_ = enabled;}
00112   void setMeshRendering(bool enabled) {meshRendering_ = enabled;}
00113   void setPointSize(float size) {pointSize_ = size;}
00114 
00115  private:
00116   // Camera object that allows user to use touch input to interact with.
00117   tango_gl::GestureCamera* gesture_camera_;
00118 
00119   // Device axis (in device frame of reference).
00120   tango_gl::Axis* axis_;
00121 
00122   // Device frustum.
00123   tango_gl::Frustum* frustum_;
00124 
00125   // Ground grid.
00126   tango_gl::Grid* grid_;
00127 
00128   // Trace of pose data.
00129   tango_gl::Trace* trace_;
00130   GraphDrawable * graph_;
00131   bool graphVisible_;
00132   bool traceVisible_;
00133 
00134   std::map<int, PointCloudDrawable*> pointClouds_;
00135 
00136   rtabmap::Transform * currentPose_;
00137 
00138   // Shader to display point cloud.
00139   GLuint cloud_shader_program_;
00140   GLuint texture_mesh_shader_program_;
00141   GLuint graph_shader_program_;
00142 
00143   bool mapRendering_;
00144   bool meshRendering_;
00145   float pointSize_;
00146 };
00147 
00148 #endif  // TANGO_POINT_CLOUD_SCENE_H_


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17