Public Types | Public Member Functions | Private Member Functions | Private Attributes
CylinderPatch Class Reference

#include <CylinderPatch.h>

Inheritance diagram for CylinderPatch:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud
< ColoredPointT
ColoredPointCloud
typedef pcl::PointXYZRGB ColoredPointT
typedef boost::shared_ptr
< const CylinderPatch
CylinderPatchConstPtr
typedef std::list
< CylinderPatchPtr
CylinderPatches
typedef boost::shared_ptr
< CylinderPatch
CylinderPatchPtr
typedef pcl::PointCloud
< IntensityPointT
IntensityPointCloud
typedef pcl::PointXYZI IntensityPointT
typedef Eigen::Matrix3f Mat3
typedef std::pair< unsigned
int, unsigned int > 
Pair2ui
typedef pcl::PointCloud< PointTPointCloud
typedef std::vector< int > PointIndices
typedef std::vector< Vec3,
Eigen::aligned_allocator< Vec3 > > 
Points
typedef pcl::PointXYZ PointT
typedef Eigen::Vector3f Vec3

Public Member Functions

template<typename PointCloudType >
void addPoints (const PointIndices &pointIndices, const PointCloudType &pointCloud)
bool checkDistance (const Vec3 &point) const
bool checkHeight (const Vec3 &point, const float &heightDev)
 CylinderPatch ()
template<typename PointCloudType >
 CylinderPatch (const PointIndices &inliers, const PointCloudType &pointCloud, const Vec3 &pointOnAxis, const Vec3 &axisDirection, const float radius, const float distThreshold)
template<typename PointCloudType >
 CylinderPatch (const PointIndices &inliers, const PointCloudType &pointCloud, const Vec3 &pointOnAxis, const Vec3 &axisDirection, const float radius, const Vec3 &rotationAxis, const float rotationAngle, const float distThreshold)
void getAxisLimits (float &min, float &max) const
float getAxisMax () const
float getAxisMin () const
const PointsgetBBVertices () const
const float & getHeight () const
const cv::Mat * getHeightMap () const
const size_t & getId () const
const PointIndicesgetInliers () const
const Vec3getMidPoint () const
const cv::Mat * getNormalMap () const
const cv::Mat * getTextureMap () const
const Vec3getTopPoint () const
void setId (const size_t &id)
virtual ~CylinderPatch ()

Private Member Functions

template<typename PointCloudType >
void addToHeight (const PointIndices &pointIndices, const PointCloudType &pointCloud)
void computeOrientedBoundingBox ()
template<typename PointCloudType >
void initialize (const PointIndices &pointIndices, const PointCloudType &pointCloud)
void setTransformation (const float rotationAngle, const Vec3 &rotationAxis)
 Compute distance from point to cylinder surface.

Private Attributes

float mAxisMax
float mAxisMin
Points mBBVertices
size_t mCylinderId
float mDistThreshold
float mHeight
cv::Mat * mHeightMap
Vec3 mMidPoint
cv::Mat * mNormalMap
PointIndices mPointIndices
cv::Mat * mTextureMap
Vec3 mTopPoint

Detailed Description

Definition at line 50 of file CylinderPatch.h.


Member Typedef Documentation

Definition at line 61 of file CylinderPatch.h.

typedef pcl::PointXYZRGB CylinderPatch::ColoredPointT

Definition at line 58 of file CylinderPatch.h.

typedef boost::shared_ptr<const CylinderPatch> CylinderPatch::CylinderPatchConstPtr

Definition at line 53 of file CylinderPatch.h.

Definition at line 54 of file CylinderPatch.h.

typedef boost::shared_ptr<CylinderPatch> CylinderPatch::CylinderPatchPtr

Definition at line 52 of file CylinderPatch.h.

Definition at line 62 of file CylinderPatch.h.

typedef pcl::PointXYZI CylinderPatch::IntensityPointT

Definition at line 59 of file CylinderPatch.h.

typedef Eigen::Matrix3f CylinderPatch::Mat3

Reimplemented from Cylinder3D.

Definition at line 65 of file CylinderPatch.h.

typedef std::pair<unsigned int, unsigned int> CylinderPatch::Pair2ui

Definition at line 63 of file CylinderPatch.h.

Definition at line 60 of file CylinderPatch.h.

typedef std::vector<int> CylinderPatch::PointIndices

Definition at line 56 of file CylinderPatch.h.

typedef std::vector<Vec3, Eigen::aligned_allocator<Vec3> > CylinderPatch::Points

Definition at line 66 of file CylinderPatch.h.

typedef pcl::PointXYZ CylinderPatch::PointT

Definition at line 57 of file CylinderPatch.h.

typedef Eigen::Vector3f CylinderPatch::Vec3

Reimplemented from Cylinder3D.

Definition at line 64 of file CylinderPatch.h.


Constructor & Destructor Documentation

Definition at line 69 of file CylinderPatch.h.

template<typename PointCloudType >
CylinderPatch::CylinderPatch ( const PointIndices inliers,
const PointCloudType &  pointCloud,
const Vec3 pointOnAxis,
const Vec3 axisDirection,
const float  radius,
const float  distThreshold 
) [inline]

Definition at line 75 of file CylinderPatch.h.

template<typename PointCloudType >
CylinderPatch::CylinderPatch ( const PointIndices inliers,
const PointCloudType &  pointCloud,
const Vec3 pointOnAxis,
const Vec3 axisDirection,
const float  radius,
const Vec3 rotationAxis,
const float  rotationAngle,
const float  distThreshold 
) [inline]

Definition at line 84 of file CylinderPatch.h.

virtual CylinderPatch::~CylinderPatch ( ) [inline, virtual]

Definition at line 92 of file CylinderPatch.h.


Member Function Documentation

template<typename PointCloudType >
void CylinderPatch::addPoints ( const PointIndices pointIndices,
const PointCloudType &  pointCloud 
) [inline]

Definition at line 162 of file CylinderPatch.h.

template<typename PointCloudType >
void CylinderPatch::addToHeight ( const PointIndices pointIndices,
const PointCloudType &  pointCloud 
) [private]

Definition at line 267 of file CylinderPatch.h.

bool CylinderPatch::checkDistance ( const Vec3 point) const [inline]

Definition at line 138 of file CylinderPatch.h.

bool CylinderPatch::checkHeight ( const Vec3 point,
const float &  heightDev 
) [inline]

Definition at line 154 of file CylinderPatch.h.

Definition at line 29 of file CylinderPatch.cpp.

void CylinderPatch::getAxisLimits ( float &  min,
float &  max 
) const [inline]

Definition at line 116 of file CylinderPatch.h.

float CylinderPatch::getAxisMax ( ) const [inline]

Definition at line 115 of file CylinderPatch.h.

float CylinderPatch::getAxisMin ( ) const [inline]

Definition at line 114 of file CylinderPatch.h.

const Points& CylinderPatch::getBBVertices ( ) const [inline]

Definition at line 110 of file CylinderPatch.h.

const float& CylinderPatch::getHeight ( ) const [inline]

Definition at line 117 of file CylinderPatch.h.

const cv::Mat* CylinderPatch::getHeightMap ( ) const [inline]

Definition at line 130 of file CylinderPatch.h.

const size_t& CylinderPatch::getId ( ) const [inline]

Definition at line 125 of file CylinderPatch.h.

const PointIndices& CylinderPatch::getInliers ( ) const [inline]

Definition at line 124 of file CylinderPatch.h.

const Vec3& CylinderPatch::getMidPoint ( ) const [inline]

Definition at line 119 of file CylinderPatch.h.

const cv::Mat* CylinderPatch::getNormalMap ( ) const [inline]

Definition at line 133 of file CylinderPatch.h.

const cv::Mat* CylinderPatch::getTextureMap ( ) const [inline]

Definition at line 127 of file CylinderPatch.h.

const Vec3& CylinderPatch::getTopPoint ( ) const [inline]

Definition at line 118 of file CylinderPatch.h.

template<typename PointCloudType >
void CylinderPatch::initialize ( const PointIndices pointIndices,
const PointCloudType &  pointCloud 
) [private]

Definition at line 246 of file CylinderPatch.h.

void CylinderPatch::setId ( const size_t &  id) [inline]

Definition at line 107 of file CylinderPatch.h.

void CylinderPatch::setTransformation ( const float  rotationAngle,
const Vec3 rotationAxis 
) [private]

Compute distance from point to cylinder surface.

Parameters:
pointCompute this point's distance. Calculate transformations from and to cylinder coordinate system. Set transformations from and to cylinder coordinate system.

Reimplemented from Cylinder3D.


Member Data Documentation

float CylinderPatch::mAxisMax [private]

Definition at line 213 of file CylinderPatch.h.

float CylinderPatch::mAxisMin [private]

Definition at line 213 of file CylinderPatch.h.

Definition at line 221 of file CylinderPatch.h.

size_t CylinderPatch::mCylinderId [private]

Definition at line 222 of file CylinderPatch.h.

Definition at line 218 of file CylinderPatch.h.

float CylinderPatch::mHeight [private]

Definition at line 214 of file CylinderPatch.h.

cv::Mat* CylinderPatch::mHeightMap [private]

Definition at line 225 of file CylinderPatch.h.

Definition at line 216 of file CylinderPatch.h.

cv::Mat* CylinderPatch::mNormalMap [private]

Definition at line 226 of file CylinderPatch.h.

Definition at line 220 of file CylinderPatch.h.

cv::Mat* CylinderPatch::mTextureMap [private]

Definition at line 224 of file CylinderPatch.h.

Definition at line 215 of file CylinderPatch.h.


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


structure_coloring_fkie
Author(s): Bastian Gaspers
autogenerated on Sun Jan 5 2014 11:38:09