#include <SphereUniformSampling.h>
Classes | |
class | NormalEntry |
Public Member Functions | |
void | addPointNoNeighbors (std::list< int >::iterator &points_it, std::list< float >::iterator &weights_it, const unsigned int i, const unsigned int j, const int index, const float weight=1.f) |
void | deletePointNWeightAt (const std::list< int >::iterator points_it, const std::list< float >::iterator weights_it, const unsigned int i, const unsigned int j) |
void | deletePointsAtAngle (const float phi, const float theta, const float max_angle) |
void | getAllAngleNeighbors (std::vector< Pair2ui > &neighbors, const float phi, const float theta, const float max_angle) const |
void | getAllAngleNeighbors (std::vector< Pair2ui > &neighbors, const Eigen::Vector3f &pointNormal, const float max_angle) const |
void | getHistogramAsPointCloud (pcl::PointCloud< pcl::PointXYZRGB > &histogramCloud, const float scale, const Eigen::Vector3f &translation) const |
float | getMaximum (unsigned int &imax, unsigned int &jmax) const |
float | getMaximumAngle (float &phi, float &theta, const float max_angle) const |
float | getMaximumIndices (unsigned int &idx_i, unsigned int &idx_j, const float max_angle) const |
Eigen::Vector3f | getNormal (const unsigned int i, const unsigned int j) const |
void | getPoints (std::vector< int > &points, const unsigned int i, const unsigned int j, std::vector< float > *weights=NULL) const |
void | getPointsAngle (std::list< int > &points, const float phi, const float theta, const float max_angle) const |
SphereUniformSampling (unsigned int phi_resolution, bool halfSphereFlip=false) | |
Static Public Member Functions | |
static void | getAnglesFromHistogramIndices (float &phi, float &theta, const unsigned int i, const unsigned int j, const unsigned int phi_resolution) |
static void | getHistogramIndicesFromAngles (unsigned int &i, unsigned int &j, const float phi, const float theta, const unsigned int phi_resolution) |
Private Member Functions | |
void | deleteEntry (unsigned int i, unsigned int j) |
float | getPlanarAngle (const float phi1, const float theta1, const float phi2, const float theta2) const |
float | getWeightAngle (const float phi, const float theta, const float max_angle) const |
Private Attributes | |
std::vector< std::vector < NormalEntry > > | mData |
bool | mHalfSphereFlip |
unsigned int | mPhi_resolution |
std::vector< float > | mRatioToNextData |
Definition at line 48 of file SphereUniformSampling.h.
SphereUniformSampling::SphereUniformSampling | ( | unsigned int | phi_resolution, |
bool | halfSphereFlip = false |
||
) |
Definition at line 38 of file SphereUniformSampling.cpp.
void SphereUniformSampling::addPointNoNeighbors | ( | std::list< int >::iterator & | points_it, |
std::list< float >::iterator & | weights_it, | ||
const unsigned int | i, | ||
const unsigned int | j, | ||
const int | index, | ||
const float | weight = 1.f |
||
) |
Definition at line 262 of file SphereUniformSampling.cpp.
void SphereUniformSampling::deleteEntry | ( | unsigned int | i, |
unsigned int | j | ||
) | [private] |
Definition at line 297 of file SphereUniformSampling.cpp.
void SphereUniformSampling::deletePointNWeightAt | ( | const std::list< int >::iterator | points_it, |
const std::list< float >::iterator | weights_it, | ||
const unsigned int | i, | ||
const unsigned int | j | ||
) |
Definition at line 275 of file SphereUniformSampling.cpp.
void SphereUniformSampling::deletePointsAtAngle | ( | const float | phi, |
const float | theta, | ||
const float | max_angle | ||
) |
Definition at line 267 of file SphereUniformSampling.cpp.
void SphereUniformSampling::getAllAngleNeighbors | ( | std::vector< Pair2ui > & | neighbors, |
const float | phi, | ||
const float | theta, | ||
const float | max_angle | ||
) | const |
Definition at line 198 of file SphereUniformSampling.cpp.
void SphereUniformSampling::getAllAngleNeighbors | ( | std::vector< Pair2ui > & | neighbors, |
const Eigen::Vector3f & | pointNormal, | ||
const float | max_angle | ||
) | const |
Definition at line 218 of file SphereUniformSampling.cpp.
void SphereUniformSampling::getAnglesFromHistogramIndices | ( | float & | phi, |
float & | theta, | ||
const unsigned int | i, | ||
const unsigned int | j, | ||
const unsigned int | phi_resolution | ||
) | [static] |
Definition at line 89 of file SphereUniformSampling.cpp.
void SphereUniformSampling::getHistogramAsPointCloud | ( | pcl::PointCloud< pcl::PointXYZRGB > & | histogramCloud, |
const float | scale, | ||
const Eigen::Vector3f & | translation | ||
) | const |
Definition at line 234 of file SphereUniformSampling.cpp.
void SphereUniformSampling::getHistogramIndicesFromAngles | ( | unsigned int & | i, |
unsigned int & | j, | ||
const float | phi, | ||
const float | theta, | ||
const unsigned int | phi_resolution | ||
) | [static] |
Definition at line 72 of file SphereUniformSampling.cpp.
float SphereUniformSampling::getMaximum | ( | unsigned int & | imax, |
unsigned int & | jmax | ||
) | const |
Definition at line 182 of file SphereUniformSampling.cpp.
float SphereUniformSampling::getMaximumAngle | ( | float & | phi, |
float & | theta, | ||
const float | max_angle | ||
) | const |
Definition at line 145 of file SphereUniformSampling.cpp.
float SphereUniformSampling::getMaximumIndices | ( | unsigned int & | idx_i, |
unsigned int & | idx_j, | ||
const float | max_angle | ||
) | const |
Definition at line 163 of file SphereUniformSampling.cpp.
Eigen::Vector3f SphereUniformSampling::getNormal | ( | const unsigned int | i, |
const unsigned int | j | ||
) | const [inline] |
Definition at line 79 of file SphereUniformSampling.h.
float SphereUniformSampling::getPlanarAngle | ( | const float | phi1, |
const float | theta1, | ||
const float | phi2, | ||
const float | theta2 | ||
) | const [private] |
Definition at line 291 of file SphereUniformSampling.cpp.
void SphereUniformSampling::getPoints | ( | std::vector< int > & | points, |
const unsigned int | i, | ||
const unsigned int | j, | ||
std::vector< float > * | weights = NULL |
||
) | const |
Definition at line 129 of file SphereUniformSampling.cpp.
void SphereUniformSampling::getPointsAngle | ( | std::list< int > & | points, |
const float | phi, | ||
const float | theta, | ||
const float | max_angle | ||
) | const |
Definition at line 116 of file SphereUniformSampling.cpp.
float SphereUniformSampling::getWeightAngle | ( | const float | phi, |
const float | theta, | ||
const float | max_angle | ||
) | const [private] |
Definition at line 281 of file SphereUniformSampling.cpp.
std::vector<std::vector<NormalEntry> > SphereUniformSampling::mData [private] |
Definition at line 103 of file SphereUniformSampling.h.
bool SphereUniformSampling::mHalfSphereFlip [private] |
Definition at line 102 of file SphereUniformSampling.h.
unsigned int SphereUniformSampling::mPhi_resolution [private] |
Definition at line 101 of file SphereUniformSampling.h.
std::vector<float> SphereUniformSampling::mRatioToNextData [private] |
Definition at line 104 of file SphereUniformSampling.h.