Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
PointCloudDrawable Class Reference

#include <point_cloud_drawable.h>

Public Member Functions

const pcl::PointXYZ & aabbMaxModel () const
 
const pcl::PointXYZ & aabbMaxWorld () const
 
const pcl::PointXYZ & aabbMinModel () const
 
const pcl::PointXYZ & aabbMinWorld () const
 
float getMinHeight () const
 
rtabmap::Transform getPose () const
 
const glm::mat4getPoseGl () const
 
bool hasMesh () const
 
bool hasTexture () const
 
bool isVisible () const
 
 PointCloudDrawable (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float gainR=1.0f, float gainG=1.0f, float gainB=1.0f)
 
 PointCloudDrawable (const Mesh &mesh, bool createWireframe=false)
 
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 setGains (float gainR, float gainG, float gainB)
 
void setPose (const rtabmap::Transform &pose)
 
void setVisible (bool visible)
 
void updateCloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices)
 
void updateMesh (const Mesh &mesh, bool createWireframe=false)
 
void updatePolygons (const std::vector< pcl::Vertices > &polygons, const std::vector< pcl::Vertices > &polygonsLowRes=std::vector< pcl::Vertices >(), bool createWireframe=false)
 
virtual ~PointCloudDrawable ()
 

Static Public Member Functions

static void createShaderPrograms ()
 
static void releaseShaderPrograms ()
 

Private Member Functions

template<class PointT >
void updateAABBMinMax (const PointT &pt, pcl::PointXYZ &min, pcl::PointXYZ &max)
 
void updateAABBWorld (const rtabmap::Transform &pose)
 

Private Attributes

pcl::PointXYZ aabbMaxModel_
 
pcl::PointXYZ aabbMaxWorld_
 
pcl::PointXYZ aabbMinModel_
 
pcl::PointXYZ aabbMinWorld_
 
float gainB_
 
float gainG_
 
float gainR_
 
bool hasNormals_
 
float minHeight_
 
int nPoints_
 
std::vector< unsigned int > organizedToDenseIndices_
 
std::vector< GLuintpolygonLines_
 
std::vector< GLuintpolygonLinesLowRes_
 
std::vector< GLuintpolygons_
 
std::vector< GLuintpolygonsLowRes_
 
rtabmap::Transform pose_
 
glm::mat4 poseGl_
 
GLuint textures_
 
GLuint vertex_buffers_
 
std::vector< GLuintverticesLowLowRes_
 
std::vector< GLuintverticesLowRes_
 
bool visible_
 

Static Private Attributes

static std::vector< GLuintshaderPrograms_
 

Detailed Description

Definition at line 42 of file point_cloud_drawable.h.

Constructor & Destructor Documentation

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 
)

Definition at line 300 of file point_cloud_drawable.cpp.

PointCloudDrawable::PointCloudDrawable ( const Mesh mesh,
bool  createWireframe = false 
)

Definition at line 320 of file point_cloud_drawable.cpp.

PointCloudDrawable::~PointCloudDrawable ( )
virtual

Definition at line 337 of file point_cloud_drawable.cpp.

Member Function Documentation

const pcl::PointXYZ& PointCloudDrawable::aabbMaxModel ( ) const
inline

Definition at line 75 of file point_cloud_drawable.h.

const pcl::PointXYZ& PointCloudDrawable::aabbMaxWorld ( ) const
inline

Definition at line 77 of file point_cloud_drawable.h.

const pcl::PointXYZ& PointCloudDrawable::aabbMinModel ( ) const
inline

Definition at line 74 of file point_cloud_drawable.h.

const pcl::PointXYZ& PointCloudDrawable::aabbMinWorld ( ) const
inline

Definition at line 76 of file point_cloud_drawable.h.

void PointCloudDrawable::createShaderPrograms ( )
static

Definition at line 263 of file point_cloud_drawable.cpp.

float PointCloudDrawable::getMinHeight ( ) const
inline

Definition at line 73 of file point_cloud_drawable.h.

rtabmap::Transform PointCloudDrawable::getPose ( ) const
inline

Definition at line 68 of file point_cloud_drawable.h.

const glm::mat4& PointCloudDrawable::getPoseGl ( ) const
inline

Definition at line 69 of file point_cloud_drawable.h.

bool PointCloudDrawable::hasMesh ( ) const
inline

Definition at line 71 of file point_cloud_drawable.h.

bool PointCloudDrawable::hasTexture ( ) const
inline

Definition at line 72 of file point_cloud_drawable.h.

bool PointCloudDrawable::isVisible ( ) const
inline

Definition at line 70 of file point_cloud_drawable.h.

void PointCloudDrawable::releaseShaderPrograms ( )
static

Definition at line 291 of file point_cloud_drawable.cpp.

void PointCloudDrawable::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

Definition at line 867 of file point_cloud_drawable.cpp.

void PointCloudDrawable::setGains ( float  gainR,
float  gainG,
float  gainB 
)
inline

Definition at line 67 of file point_cloud_drawable.h.

void PointCloudDrawable::setPose ( const rtabmap::Transform pose)

Definition at line 829 of file point_cloud_drawable.cpp.

void PointCloudDrawable::setVisible ( bool  visible)
inline

Definition at line 66 of file point_cloud_drawable.h.

template<class PointT >
void PointCloudDrawable::updateAABBMinMax ( const PointT &  pt,
pcl::PointXYZ &  min,
pcl::PointXYZ &  max 
)
inlineprivate

Definition at line 103 of file point_cloud_drawable.h.

void PointCloudDrawable::updateAABBWorld ( const rtabmap::Transform pose)
private

Definition at line 842 of file point_cloud_drawable.cpp.

void PointCloudDrawable::updateCloud ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
const pcl::IndicesPtr &  indices 
)

Definition at line 411 of file point_cloud_drawable.cpp.

void PointCloudDrawable::updateMesh ( const Mesh mesh,
bool  createWireframe = false 
)

Definition at line 528 of file point_cloud_drawable.cpp.

void PointCloudDrawable::updatePolygons ( const std::vector< pcl::Vertices > &  polygons,
const std::vector< pcl::Vertices > &  polygonsLowRes = std::vector<pcl::Vertices>(),
bool  createWireframe = false 
)

Definition at line 355 of file point_cloud_drawable.cpp.

Member Data Documentation

pcl::PointXYZ PointCloudDrawable::aabbMaxModel_
private

Definition at line 137 of file point_cloud_drawable.h.

pcl::PointXYZ PointCloudDrawable::aabbMaxWorld_
private

Definition at line 139 of file point_cloud_drawable.h.

pcl::PointXYZ PointCloudDrawable::aabbMinModel_
private

Definition at line 136 of file point_cloud_drawable.h.

pcl::PointXYZ PointCloudDrawable::aabbMinWorld_
private

Definition at line 138 of file point_cloud_drawable.h.

float PointCloudDrawable::gainB_
private

Definition at line 134 of file point_cloud_drawable.h.

float PointCloudDrawable::gainG_
private

Definition at line 133 of file point_cloud_drawable.h.

float PointCloudDrawable::gainR_
private

Definition at line 132 of file point_cloud_drawable.h.

bool PointCloudDrawable::hasNormals_
private

Definition at line 128 of file point_cloud_drawable.h.

float PointCloudDrawable::minHeight_
private

Definition at line 130 of file point_cloud_drawable.h.

int PointCloudDrawable::nPoints_
private

Definition at line 124 of file point_cloud_drawable.h.

std::vector<unsigned int> PointCloudDrawable::organizedToDenseIndices_
private

Definition at line 129 of file point_cloud_drawable.h.

std::vector<GLuint> PointCloudDrawable::polygonLines_
private

Definition at line 120 of file point_cloud_drawable.h.

std::vector<GLuint> PointCloudDrawable::polygonLinesLowRes_
private

Definition at line 121 of file point_cloud_drawable.h.

std::vector<GLuint> PointCloudDrawable::polygons_
private

Definition at line 118 of file point_cloud_drawable.h.

std::vector<GLuint> PointCloudDrawable::polygonsLowRes_
private

Definition at line 119 of file point_cloud_drawable.h.

rtabmap::Transform PointCloudDrawable::pose_
private

Definition at line 125 of file point_cloud_drawable.h.

glm::mat4 PointCloudDrawable::poseGl_
private

Definition at line 126 of file point_cloud_drawable.h.

std::vector< GLuint > PointCloudDrawable::shaderPrograms_
staticprivate

Definition at line 48 of file point_cloud_drawable.h.

GLuint PointCloudDrawable::textures_
private

Definition at line 117 of file point_cloud_drawable.h.

GLuint PointCloudDrawable::vertex_buffers_
private

Definition at line 116 of file point_cloud_drawable.h.

std::vector<GLuint> PointCloudDrawable::verticesLowLowRes_
private

Definition at line 123 of file point_cloud_drawable.h.

std::vector<GLuint> PointCloudDrawable::verticesLowRes_
private

Definition at line 122 of file point_cloud_drawable.h.

bool PointCloudDrawable::visible_
private

Definition at line 127 of file point_cloud_drawable.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:42