point_cloud_drawable.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_
00029 #define TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_
00030 
00031 #include <jni.h>
00032 
00033 #include <tango-gl/util.h>
00034 #include <vector>
00035 #include <pcl/point_cloud.h>
00036 #include <pcl/point_types.h>
00037 #include <rtabmap/core/Transform.h>
00038 #include <pcl/Vertices.h>
00039 #include "util.h"
00040 
00041 // PointCloudDrawable is responsible for the point cloud rendering.
00042 class PointCloudDrawable {
00043 public:
00044         static void createShaderPrograms();
00045         static void releaseShaderPrograms();
00046 
00047 private:
00048         static std::vector<GLuint> shaderPrograms_;
00049 
00050  public:
00051   PointCloudDrawable(
00052                   const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00053                   const pcl::IndicesPtr & indices,
00054                   float gainR = 1.0f,
00055                   float gainG = 1.0f,
00056                   float gainB = 1.0f);
00057   PointCloudDrawable(
00058           const Mesh & mesh,
00059                   bool createWireframe = false);
00060   virtual ~PointCloudDrawable();
00061 
00062   void updatePolygons(const std::vector<pcl::Vertices> & polygons, const std::vector<pcl::Vertices> & polygonsLowRes = std::vector<pcl::Vertices>(), bool createWireframe = false);
00063   void updateCloud(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud, const pcl::IndicesPtr & indices);
00064   void updateMesh(const Mesh & mesh, bool createWireframe = false);
00065   void setPose(const rtabmap::Transform & pose);
00066   void setVisible(bool visible) {visible_=visible;}
00067   void setGains(float gainR, float gainG, float gainB) {gainR_ = gainR; gainG_ = gainG; gainB_ = gainB;}
00068   rtabmap::Transform getPose() const {return pose_;}
00069   const glm::mat4 & getPoseGl() const {return poseGl_;}
00070   bool isVisible() const {return visible_;}
00071   bool hasMesh() const {return polygons_.size()!=0;}
00072   bool hasTexture() const {return textures_ != 0;}
00073   float getMinHeight() const {return minHeight_;}
00074   const pcl::PointXYZ & aabbMinModel() const {return aabbMinModel_;}
00075   const pcl::PointXYZ & aabbMaxModel() const {return aabbMaxModel_;}
00076   const pcl::PointXYZ & aabbMinWorld() const {return aabbMinWorld_;}
00077   const pcl::PointXYZ & aabbMaxWorld() const {return aabbMaxWorld_;}
00078 
00079   // Update current point cloud data.
00080   //
00081   // @param projection_mat: projection matrix from current render camera.
00082   // @param view_mat: view matrix from current render camera.
00083   // @param model_mat: model matrix for this point cloud frame.
00084   // @param vertices: all vertices in this point cloud frame.
00085   void Render(
00086                   const glm::mat4 & projectionMatrix,
00087                   const glm::mat4 & viewMatrix,
00088                   bool meshRendering = true,
00089                   float pointSize = 3.0f,
00090                   bool textureRendering = false,
00091                   bool lighting = true,
00092                   float distanceToCamSqr = 0.0f,
00093                   const GLuint & depthTexture = 0,
00094                   int screenWidth = 0,     // nonnull if depthTexture>0
00095                   int screenHeight = 0,    // nonnull if depthTexture>0
00096                   float nearClipPlane = 0, // nonnull if depthTexture>0
00097                   float farClipPlane = 0,  // nonnull if depthTexture>0
00098                   bool packDepthToColorChannel = false,
00099                   bool wireFrame = false) const;
00100 
00101  private:
00102   template<class PointT>
00103   void updateAABBMinMax(const PointT & pt, pcl::PointXYZ & min, pcl::PointXYZ & max)
00104   {
00105           if(pt.x<min.x) min.x = pt.x;
00106           if(pt.y<min.y) min.y = pt.y;
00107           if(pt.z<min.z) min.z = pt.z;
00108           if(pt.x>max.x) max.x = pt.x;
00109           if(pt.y>max.y) max.y = pt.y;
00110           if(pt.z>max.z) max.z = pt.z;
00111   }
00112   void updateAABBWorld(const rtabmap::Transform & pose);
00113 
00114  private:
00115   // Vertex buffer of the point cloud geometry.
00116   GLuint vertex_buffers_;
00117   GLuint textures_;
00118   std::vector<GLuint> polygons_;
00119   std::vector<GLuint> polygonsLowRes_;
00120   std::vector<GLuint> polygonLines_;
00121   std::vector<GLuint> polygonLinesLowRes_;
00122   std::vector<GLuint> verticesLowRes_;
00123   std::vector<GLuint> verticesLowLowRes_;
00124   int nPoints_;
00125   rtabmap::Transform pose_;
00126   glm::mat4 poseGl_;
00127   bool visible_;
00128   bool hasNormals_;
00129   std::vector<unsigned int> organizedToDenseIndices_;
00130   float minHeight_; // odom frame
00131 
00132   float gainR_;
00133   float gainG_;
00134   float gainB_;
00135 
00136   pcl::PointXYZ aabbMinModel_;
00137   pcl::PointXYZ aabbMaxModel_;
00138   pcl::PointXYZ aabbMinWorld_;
00139   pcl::PointXYZ aabbMaxWorld_;
00140 };
00141 
00142 #endif  // TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_


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