Public Types | Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes
PlanePatch Class Reference

#include <PlanePatch.h>

List of all members.

Public Types

typedef pcl::PointCloud
< ColoredPointT
ColoredPointCloud
typedef pcl::PointXYZRGB ColoredPointT
typedef boost::shared_ptr
< const GridMap
GridMapConstPtr
typedef boost::shared_ptr
< GridMap
GridMapPtr
typedef pcl::PointCloud
< IntensityPointT
IntensityPointCloud
typedef pcl::PointXYZI IntensityPointT
typedef std::pair< unsigned
int, unsigned int > 
Pair2ui
typedef boost::shared_ptr
< const PlanePatch
PlanePatchConstPtr
typedef std::list< PlanePatchPtrPlanePatches
typedef boost::shared_ptr
< PlanePatch
PlanePatchPtr
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 checkPointConnection (const Vec3 &p, const int connectionNeighbors) const
void computeAlphaMap (const PointCloud &pointCloud, const float texelSizeFactor=2.f, const unsigned int dilateIterations=0)
void computeBoundingRectangle ()
template<typename PointCloudType >
void computeHeightMap (const float texturePixelSize, const PointCloudType &pointCloud, const unsigned int dilateIterations)
void computeIntensityTextureMap (const IntensityPointCloud &pointCloud, const float texelSizeFactor=2.f, const unsigned int dilateIterations=0)
void computeNormalMap ()
void computeOrientedBoundingBox ()
void computeRGBTextureMap (const ColoredPointCloud &pointCloud, const float texelSizeFactor=2.f, const unsigned int dilateIterations=0)
void computeTextureSize (float &texPixSize, unsigned int &wPot, unsigned int &hPot, const float texelSizeFactor)
float distanceToOBB (const Vec3 &p) const
float getArea () const
const PointsgetBBVertices () const
const PointsgetBRVertices () const
float getDistanceThreshold () const
const cv::Mat & getHeightMap () const
size_t getId () const
const PointIndicesgetInliers () const
void getLimitsXY (float &xMin, float &xMax, float &yMin, float &yMax) const
const cv::Mat & getNormalMap () const
const Plane3DgetPlane3D () const
const Vec3getPlaneCoG () const
float getTextureHeightRatio () const
const cv::Mat & getTextureMap () const
float getTextureWidthRatio () const
GridMapPtr grid ()
GridMapConstPtr grid () const
bool hasGrid () const
void newGrid (const float cellSize)
template<typename PointCloudType >
 PlanePatch (const Eigen::Vector3f &normal, const float distance, const PointIndices &inliers, const PointCloudType &pointCloud, const float distanceThreshold=-1.f)
template<typename PointCloudType >
 PlanePatch (const PointIndices &inliers, const PointCloudType &pointCloud, const float distanceThreshold)
 PlanePatch (const Vec3 &normal, const float distance, const float distanceThreshold, const Points &brVertices, const float texWidthRatio, const float texHeightRatio, const cv::Mat &heightMap, const cv::Mat &textureMap)
 PlanePatch ()
void setGrid (GridMap *newGridMapPtr)
void setId (size_t id)
float & xMax ()
const float & xMax () const
float & xMin ()
const float & xMin () const
float & yMax ()
const float & yMax () const
float & yMin ()
const float & yMin () const

Static Public Member Functions

static void compute2PotTexSize (float &widthRatio, float &heightRatio, unsigned int &wPot, unsigned int &hPot, const unsigned int width, const unsigned int height)

Private Member Functions

template<typename PointCloudType >
void calculateMinMax (const PointCloudType &pointCloud)
template<typename PointCloudType >
void initializeTransformationsWithoutPCA (const PointCloudType &pointCloud)
template<typename PointCloudType >
void initializeTransformationsWithPCA (const PointCloudType &pointCloud)
template<typename PointCloudType >
void initializeWithoutPCA (const PointCloudType &pointcloud)
template<typename PointCloudType >
void initializeWithPCA (const PointCloudType &pointCloud)
PlanePatchoperator= (const PlanePatch &)
 PlanePatch (const PlanePatch &)
template<typename PointCloudType >
void rotateToPrincipalAxis (Eigen::Matrix3f &m, const PointCloudType &pointCloud, const Vec3 &greatestEigenVector=Vec3::Zero()) const

Private Attributes

Points mBBVertices
Points mBRVertices
Vec3 mCoG
float mDistanceThreshold
GridMapPtr mGrid
cv::Mat mHeightMap
PointIndices mInlierIndices
cv::Mat mNormalMap
Plane3D mPlane
size_t mPlaneId
float mTextureHeightRatio
cv::Mat mTextureMap
float mTextureWidthRatio
float mXMax
float mXMin
float mYMax
float mYMin
float mZMax
float mZMin

Detailed Description

Definition at line 54 of file PlanePatch.h.


Member Typedef Documentation

Definition at line 65 of file PlanePatch.h.

typedef pcl::PointXYZRGB PlanePatch::ColoredPointT

Definition at line 62 of file PlanePatch.h.

typedef boost::shared_ptr<const GridMap> PlanePatch::GridMapConstPtr

Definition at line 71 of file PlanePatch.h.

typedef boost::shared_ptr<GridMap> PlanePatch::GridMapPtr

Definition at line 70 of file PlanePatch.h.

Definition at line 66 of file PlanePatch.h.

typedef pcl::PointXYZI PlanePatch::IntensityPointT

Definition at line 63 of file PlanePatch.h.

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

Definition at line 67 of file PlanePatch.h.

typedef boost::shared_ptr<const PlanePatch> PlanePatch::PlanePatchConstPtr

Definition at line 57 of file PlanePatch.h.

Definition at line 58 of file PlanePatch.h.

typedef boost::shared_ptr<PlanePatch> PlanePatch::PlanePatchPtr

Definition at line 56 of file PlanePatch.h.

Definition at line 64 of file PlanePatch.h.

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

Definition at line 60 of file PlanePatch.h.

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

Definition at line 69 of file PlanePatch.h.

typedef pcl::PointXYZ PlanePatch::PointT

Definition at line 61 of file PlanePatch.h.

typedef Eigen::Vector3f PlanePatch::Vec3

Definition at line 68 of file PlanePatch.h.


Constructor & Destructor Documentation

template<typename PointCloudType >
PlanePatch::PlanePatch ( const Eigen::Vector3f &  normal,
const float  distance,
const PointIndices inliers,
const PointCloudType &  pointCloud,
const float  distanceThreshold = -1.f 
)

Definition at line 248 of file PlanePatch.h.

template<typename PointCloudType >
PlanePatch::PlanePatch ( const PointIndices inliers,
const PointCloudType &  pointCloud,
const float  distanceThreshold 
)

Definition at line 259 of file PlanePatch.h.

PlanePatch::PlanePatch ( const Vec3 normal,
const float  distance,
const float  distanceThreshold,
const Points brVertices,
const float  texWidthRatio,
const float  texHeightRatio,
const cv::Mat &  heightMap,
const cv::Mat &  textureMap 
)

Definition at line 7 of file PlanePatch.cpp.

PlanePatch::PlanePatch ( const PlanePatch ) [inline, private]

Definition at line 167 of file PlanePatch.h.


Member Function Documentation

template<typename PointCloudType >
void PlanePatch::addPoints ( const PointIndices pointIndices,
const PointCloudType &  pointCloud 
)

Definition at line 269 of file PlanePatch.h.

template<typename PointCloudType >
void PlanePatch::calculateMinMax ( const PointCloudType &  pointCloud) [private]

Definition at line 377 of file PlanePatch.h.

bool PlanePatch::checkPointConnection ( const Vec3 p,
const int  connectionNeighbors 
) const

Definition at line 221 of file PlanePatch.cpp.

void PlanePatch::compute2PotTexSize ( float &  widthRatio,
float &  heightRatio,
unsigned int &  wPot,
unsigned int &  hPot,
const unsigned int  width,
const unsigned int  height 
) [static]

Definition at line 47 of file PlanePatch.cpp.

void PlanePatch::computeAlphaMap ( const PointCloud pointCloud,
const float  texelSizeFactor = 2.f,
const unsigned int  dilateIterations = 0 
)

Definition at line 138 of file PlanePatch.cpp.

Definition at line 206 of file PlanePatch.cpp.

template<typename PointCloudType >
void PlanePatch::computeHeightMap ( const float  texturePixelSize,
const PointCloudType &  pointCloud,
const unsigned int  dilateIterations 
)

Definition at line 286 of file PlanePatch.h.

void PlanePatch::computeIntensityTextureMap ( const IntensityPointCloud pointCloud,
const float  texelSizeFactor = 2.f,
const unsigned int  dilateIterations = 0 
)

Definition at line 106 of file PlanePatch.cpp.

Definition at line 164 of file PlanePatch.cpp.

Definition at line 187 of file PlanePatch.cpp.

void PlanePatch::computeRGBTextureMap ( const ColoredPointCloud pointCloud,
const float  texelSizeFactor = 2.f,
const unsigned int  dilateIterations = 0 
)

Definition at line 62 of file PlanePatch.cpp.

void PlanePatch::computeTextureSize ( float &  texPixSize,
unsigned int &  wPot,
unsigned int &  hPot,
const float  texelSizeFactor 
)

Definition at line 36 of file PlanePatch.cpp.

float PlanePatch::distanceToOBB ( const Vec3 p) const

Definition at line 227 of file PlanePatch.cpp.

float PlanePatch::getArea ( ) const [inline]

Definition at line 128 of file PlanePatch.h.

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

Definition at line 103 of file PlanePatch.h.

const Points& PlanePatch::getBRVertices ( ) const [inline]

Definition at line 102 of file PlanePatch.h.

float PlanePatch::getDistanceThreshold ( ) const [inline]

Definition at line 130 of file PlanePatch.h.

const cv::Mat& PlanePatch::getHeightMap ( ) const [inline]

Definition at line 109 of file PlanePatch.h.

size_t PlanePatch::getId ( ) const [inline]

Definition at line 135 of file PlanePatch.h.

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

Definition at line 129 of file PlanePatch.h.

void PlanePatch::getLimitsXY ( float &  xMin,
float &  xMax,
float &  yMin,
float &  yMax 
) const

Definition at line 21 of file PlanePatch.cpp.

const cv::Mat& PlanePatch::getNormalMap ( ) const [inline]

Definition at line 113 of file PlanePatch.h.

const Plane3D& PlanePatch::getPlane3D ( ) const [inline]

Definition at line 121 of file PlanePatch.h.

const Vec3& PlanePatch::getPlaneCoG ( ) const [inline]

Definition at line 120 of file PlanePatch.h.

float PlanePatch::getTextureHeightRatio ( ) const [inline]

Definition at line 118 of file PlanePatch.h.

const cv::Mat& PlanePatch::getTextureMap ( ) const [inline]

Definition at line 105 of file PlanePatch.h.

float PlanePatch::getTextureWidthRatio ( ) const [inline]

Definition at line 117 of file PlanePatch.h.

Definition at line 96 of file PlanePatch.h.

GridMapConstPtr PlanePatch::grid ( ) const [inline]

Definition at line 132 of file PlanePatch.h.

bool PlanePatch::hasGrid ( ) const [inline]

Definition at line 133 of file PlanePatch.h.

template<typename PointCloudType >
void PlanePatch::initializeTransformationsWithoutPCA ( const PointCloudType &  pointCloud) [private]

Definition at line 321 of file PlanePatch.h.

template<typename PointCloudType >
void PlanePatch::initializeTransformationsWithPCA ( const PointCloudType &  pointCloud) [private]

Definition at line 332 of file PlanePatch.h.

template<typename PointCloudType >
void PlanePatch::initializeWithoutPCA ( const PointCloudType &  pointcloud) [private]

Definition at line 357 of file PlanePatch.h.

template<typename PointCloudType >
void PlanePatch::initializeWithPCA ( const PointCloudType &  pointCloud) [private]

Definition at line 367 of file PlanePatch.h.

void PlanePatch::newGrid ( const float  cellSize)

Definition at line 30 of file PlanePatch.cpp.

PlanePatch& PlanePatch::operator= ( const PlanePatch ) [inline, private]

Definition at line 172 of file PlanePatch.h.

template<typename PointCloudType >
void PlanePatch::rotateToPrincipalAxis ( Eigen::Matrix3f &  m,
const PointCloudType &  pointCloud,
const Vec3 greatestEigenVector = Vec3::Zero() 
) const [private]

Definition at line 407 of file PlanePatch.h.

void PlanePatch::setGrid ( GridMap newGridMapPtr) [inline]

Definition at line 97 of file PlanePatch.h.

void PlanePatch::setId ( size_t  id) [inline]

Definition at line 99 of file PlanePatch.h.

float& PlanePatch::xMax ( ) [inline]

Definition at line 93 of file PlanePatch.h.

const float& PlanePatch::xMax ( ) const [inline]

Definition at line 126 of file PlanePatch.h.

float& PlanePatch::xMin ( ) [inline]

Definition at line 91 of file PlanePatch.h.

const float& PlanePatch::xMin ( ) const [inline]

Definition at line 124 of file PlanePatch.h.

float& PlanePatch::yMax ( ) [inline]

Definition at line 94 of file PlanePatch.h.

const float& PlanePatch::yMax ( ) const [inline]

Definition at line 127 of file PlanePatch.h.

float& PlanePatch::yMin ( ) [inline]

Definition at line 92 of file PlanePatch.h.

const float& PlanePatch::yMin ( ) const [inline]

Definition at line 125 of file PlanePatch.h.


Member Data Documentation

Definition at line 203 of file PlanePatch.h.

Definition at line 202 of file PlanePatch.h.

Definition at line 199 of file PlanePatch.h.

Definition at line 209 of file PlanePatch.h.

Definition at line 204 of file PlanePatch.h.

cv::Mat PlanePatch::mHeightMap [private]

Definition at line 206 of file PlanePatch.h.

Definition at line 201 of file PlanePatch.h.

cv::Mat PlanePatch::mNormalMap [private]

Definition at line 207 of file PlanePatch.h.

Definition at line 198 of file PlanePatch.h.

size_t PlanePatch::mPlaneId [private]

Definition at line 210 of file PlanePatch.h.

Definition at line 208 of file PlanePatch.h.

cv::Mat PlanePatch::mTextureMap [private]

Definition at line 205 of file PlanePatch.h.

Definition at line 208 of file PlanePatch.h.

float PlanePatch::mXMax [private]

Definition at line 200 of file PlanePatch.h.

float PlanePatch::mXMin [private]

Definition at line 200 of file PlanePatch.h.

float PlanePatch::mYMax [private]

Definition at line 200 of file PlanePatch.h.

float PlanePatch::mYMin [private]

Definition at line 200 of file PlanePatch.h.

float PlanePatch::mZMax [private]

Definition at line 200 of file PlanePatch.h.

float PlanePatch::mZMin [private]

Definition at line 200 of file PlanePatch.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