point_cloud_drawable.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_
29 #define TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_
30 
31 #include <jni.h>
32 
33 #include <tango-gl/util.h>
34 #include <vector>
35 #include <pcl/point_cloud.h>
36 #include <pcl/point_types.h>
37 #include <rtabmap/core/Transform.h>
38 #include <pcl/Vertices.h>
39 #include "util.h"
40 
41 // PointCloudDrawable is responsible for the point cloud rendering.
43 public:
44  static void createShaderPrograms();
45  static void releaseShaderPrograms();
46 
47 private:
48  static std::vector<GLuint> shaderPrograms_;
49 
50  public:
52  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
53  const pcl::IndicesPtr & indices,
54  float gainR = 1.0f,
55  float gainG = 1.0f,
56  float gainB = 1.0f);
58  const Mesh & mesh,
59  bool createWireframe = false);
60  virtual ~PointCloudDrawable();
61 
62  void updatePolygons(const std::vector<pcl::Vertices> & polygons, const std::vector<pcl::Vertices> & polygonsLowRes = std::vector<pcl::Vertices>(), bool createWireframe = false);
63  void updateCloud(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud, const pcl::IndicesPtr & indices);
64  void updateMesh(const Mesh & mesh, bool createWireframe = false);
65  void setPose(const rtabmap::Transform & pose);
66  void setVisible(bool visible) {visible_=visible;}
67  void setGains(float gainR, float gainG, float gainB) {gainR_ = gainR; gainG_ = gainG; gainB_ = gainB;}
68  rtabmap::Transform getPose() const {return pose_;}
69  const glm::mat4 & getPoseGl() const {return poseGl_;}
70  bool isVisible() const {return visible_;}
71  bool hasMesh() const {return polygons_.size()!=0;}
72  bool hasTexture() const {return textures_ != 0;}
73  float getMinHeight() const {return minHeight_;}
74  const pcl::PointXYZ & aabbMinModel() const {return aabbMinModel_;}
75  const pcl::PointXYZ & aabbMaxModel() const {return aabbMaxModel_;}
76  const pcl::PointXYZ & aabbMinWorld() const {return aabbMinWorld_;}
77  const pcl::PointXYZ & aabbMaxWorld() const {return aabbMaxWorld_;}
78 
79  // Update current point cloud data.
80  //
81  // @param projection_mat: projection matrix from current render camera.
82  // @param view_mat: view matrix from current render camera.
83  // @param model_mat: model matrix for this point cloud frame.
84  // @param vertices: all vertices in this point cloud frame.
85  void Render(
86  const glm::mat4 & projectionMatrix,
87  const glm::mat4 & viewMatrix,
88  bool meshRendering = true,
89  float pointSize = 3.0f,
90  bool textureRendering = false,
91  bool lighting = true,
92  float distanceToCamSqr = 0.0f,
93  const GLuint & depthTexture = 0,
94  int screenWidth = 0, // nonnull if depthTexture>0
95  int screenHeight = 0, // nonnull if depthTexture>0
96  float nearClipPlane = 0, // nonnull if depthTexture>0
97  float farClipPlane = 0, // nonnull if depthTexture>0
98  bool packDepthToColorChannel = false,
99  bool wireFrame = false) const;
100 
101  private:
102  template<class PointT>
103  void updateAABBMinMax(const PointT & pt, pcl::PointXYZ & min, pcl::PointXYZ & max)
104  {
105  if(pt.x<min.x) min.x = pt.x;
106  if(pt.y<min.y) min.y = pt.y;
107  if(pt.z<min.z) min.z = pt.z;
108  if(pt.x>max.x) max.x = pt.x;
109  if(pt.y>max.y) max.y = pt.y;
110  if(pt.z>max.z) max.z = pt.z;
111  }
112  void updateAABBWorld(const rtabmap::Transform & pose);
113 
114  private:
115  // Vertex buffer of the point cloud geometry.
118  std::vector<GLuint> polygons_;
119  std::vector<GLuint> polygonsLowRes_;
120  std::vector<GLuint> polygonLines_;
121  std::vector<GLuint> polygonLinesLowRes_;
122  std::vector<GLuint> verticesLowRes_;
123  std::vector<GLuint> verticesLowLowRes_;
124  int nPoints_;
127  bool visible_;
129  std::vector<unsigned int> organizedToDenseIndices_;
130  float minHeight_; // odom frame
131 
132  float gainR_;
133  float gainG_;
134  float gainB_;
135 
136  pcl::PointXYZ aabbMinModel_;
137  pcl::PointXYZ aabbMaxModel_;
138  pcl::PointXYZ aabbMinWorld_;
139  pcl::PointXYZ aabbMaxWorld_;
140 };
141 
142 #endif // TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_
static void releaseShaderPrograms()
std::vector< GLuint > polygonLinesLowRes_
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
std::vector< GLuint > polygons_
std::vector< GLuint > polygonLines_
f
void setPose(const rtabmap::Transform &pose)
std::vector< GLuint > polygonsLowRes_
void updatePolygons(const std::vector< pcl::Vertices > &polygons, const std::vector< pcl::Vertices > &polygonsLowRes=std::vector< pcl::Vertices >(), bool createWireframe=false)
Definition: util.h:147
float getMinHeight() const
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
void updateCloud(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices)
std::vector< GLuint > verticesLowRes_
unsigned int GLuint
Definition: dummy.cpp:78
rtabmap::Transform getPose() const
void setGains(float gainR, float gainG, float gainB)
std::vector< GLuint > verticesLowLowRes_
PointCloudDrawable(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float gainR=1.0f, float gainG=1.0f, float gainB=1.0f)
void updateAABBWorld(const rtabmap::Transform &pose)
static std::vector< GLuint > shaderPrograms_
std::vector< unsigned int > organizedToDenseIndices_
rtabmap::Transform pose_
void updateMesh(const Mesh &mesh, bool createWireframe=false)
const glm::mat4 & getPoseGl() const
const pcl::PointXYZ & aabbMaxModel() const
void updateAABBMinMax(const PointT &pt, pcl::PointXYZ &min, pcl::PointXYZ &max)
const pcl::PointXYZ & aabbMaxWorld() const
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
const pcl::PointXYZ & aabbMinModel() const
void setVisible(bool visible)
const pcl::PointXYZ & aabbMinWorld() const
static void createShaderPrograms()


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32