28 #ifndef TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_ 29 #define TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_ 35 #include <pcl/point_cloud.h> 36 #include <pcl/point_types.h> 38 #include <pcl/Vertices.h> 52 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
53 const pcl::IndicesPtr & indices,
59 bool createWireframe =
false);
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);
88 bool meshRendering =
true,
89 float pointSize = 3.0
f,
90 bool textureRendering =
false,
92 float distanceToCamSqr = 0.0
f,
93 const GLuint & depthTexture = 0,
96 float nearClipPlane = 0,
97 float farClipPlane = 0,
98 bool packDepthToColorChannel =
false,
99 bool wireFrame =
false)
const;
102 template<
class Po
intT>
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;
142 #endif // TANGO_POINT_CLOUD_POINT_CLOUD_DRAWABLE_H_
void updateMesh(const rtabmap::Mesh &mesh, bool createWireframe=false)
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_
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)
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
pcl::PointXYZ aabbMaxWorld_
void updateCloud(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices)
std::vector< GLuint > verticesLowRes_
pcl::PointXYZ aabbMinWorld_
rtabmap::Transform getPose() const
pcl::PointXYZ aabbMinModel_
void setGains(float gainR, float gainG, float gainB)
std::vector< GLuint > verticesLowLowRes_
virtual ~PointCloudDrawable()
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_
const glm::mat4 & getPoseGl() const
const pcl::PointXYZ & aabbMaxModel() const
pcl::PointXYZ aabbMaxModel_
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()