#include <quad_regression_algo.h>
Public Member Functions | |
void | back_check_repeat () |
segmentation on quad-tree | |
virtual void | buildTree (const pcl::PointCloud< Point > &pc) |
setup level size | |
void | calc () |
build quad-tree | |
virtual bool | compute () |
void | getExecutionTimes (double &quadtree, double &growing, double &extraction) |
repeat back check on model | |
bool | getFilter () const |
setter for "only planes"-option (limits higher polynomials to planes afterwards) | |
bool | getOnlyPlanes () const |
getter for filter parameter (pixels/area) | |
const std::vector < Segmentation::S_POLYGON < Degree > > & | getPolygons () const |
get polygons | |
virtual void | prepare (const pcl::PointCloud< Point > &pc) |
getter for "only planes"-option (limits higher polynomials to planes afterwards) | |
QuadRegression () | |
constructor, setups variables | |
void | setFilter (const float f) |
virtual void | setInputCloud (const boost::shared_ptr< const pcl::PointCloud< Point > > &cloud) |
sets preprocessed input cloud | |
void | setOnlyPlanes (const bool b) |
setter for filter parameter (pixels/area) | |
virtual | ~QuadRegression () |
destructor | |
Protected Types | |
enum | { DEGREE = Degree } |
Protected Member Functions | |
int | getInd (const int i, const int x, const int y) const |
get index for element at (x,y) on level i (0: leaves) of quadtree | |
int | getIndPC (const int w, const int x, const int y) const |
get index for element at (x,y) in ordered pc | |
int | isOccupied (const int i, const int x, const int y) const |
check occupation from down to top | |
Protected Attributes | |
double | execution_time_growing_ |
double | execution_time_polyextraction_ |
double | execution_time_quadtree_ |
result of surface reconstruction | |
boost::shared_ptr< const pcl::PointCloud< Point > > | input_ |
std::vector < SubStructure::ParamC< Degree > > | levels_ |
input point cloud (no need for color) | |
std::vector < Segmentation::S_POLYGON < Degree > > | polygons_ |
quad-tree levels/stages | |
Private Member Functions | |
void | addPoint (const int i, const int x, const int y, const int mark, S_POLYGON< Degree > &poly, const SubStructure::Model< Degree > &model, const float v=0.f) |
bool | checkModelAt (const SubStructure::Model< Degree > &model, const int i, const int x, const int y) const |
bool | filterOccupied (const int i, const int x, const int y, const int mark) const |
int | getPos (int *ch, const int xx, const int yy, const int w, const int h) |
void | grow (SubStructure::Model< Degree > &model, const int i, const int x, const int y) |
filter option | |
void | grow (SubStructure::VISITED_LIST< SubStructure::SVALUE > &list, SubStructure::Model< Degree > &model, const int i, const int mark, bool first_lvl) |
int | otherOccupied (const int i, const int x, const int y, const int mark) const |
void | outline (int *ch, const int w, const int h, std::vector< SubStructure::SXY > &out, const int i, S_POLYGON< Degree > &poly, const SubStructure::Model< Degree > &model, const int mark) |
Private Attributes | |
CameraModel | camera_ |
search down to ... | |
int * | ch_ |
camera model | |
float | filter_ |
remember size for var. above | |
const unsigned int | FINAL_LOD |
minimum of nodes for a segment | |
const unsigned int | GO_DOWN_TO_LVL |
lowest level = 0 | |
const unsigned int | MIN_LOD |
bool | only_planes_ |
ratio points per area | |
bool * | outline_check_ |
mark-array | |
size_t | outline_check_size_ |
needed for outline, no need to reallocate every time |
a segmentation implementation based on quad-trees and regression
Definition at line 137 of file quad_regression_algo.h.
anonymous enum [protected] |
Definition at line 170 of file quad_regression_algo.h.
Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::QuadRegression | ( | ) |
constructor, setups variables
Definition at line 93 of file quad_regression_algo.hpp.
virtual Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::~QuadRegression | ( | ) | [inline, virtual] |
destructor
Definition at line 501 of file quad_regression_algo.h.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::addPoint | ( | const int | i, |
const int | x, | ||
const int | y, | ||
const int | mark, | ||
S_POLYGON< Degree > & | poly, | ||
const SubStructure::Model< Degree > & | model, | ||
const float | v = 0.f |
||
) | [inline, private] |
Definition at line 233 of file quad_regression_algo.h.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::back_check_repeat | ( | ) |
segmentation on quad-tree
Reimplemented in Segmentation::Segmentation_QuadRegression< Point, PointLabel, Segmentation::QPPF::QuadRegression< 2, Point, Segmentation::QPPF::CameraModel_Kinect< Point > > >.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::buildTree | ( | const pcl::PointCloud< Point > & | pc | ) | [virtual] |
setup level size
lowest-level: take points
lowest-level: take points
Reimplemented in Segmentation::QPPF::QuadRegression_Downsampled< Degree, Point, CameraModel >.
Definition at line 160 of file quad_regression_algo.hpp.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::calc | ( | ) |
build quad-tree
Definition at line 338 of file quad_regression_algo.hpp.
bool Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::checkModelAt | ( | const SubStructure::Model< Degree > & | model, |
const int | i, | ||
const int | x, | ||
const int | y | ||
) | const [inline, private] |
Definition at line 222 of file quad_regression_algo.h.
bool Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::compute | ( | ) | [virtual] |
Reimplemented in Segmentation::Segmentation_QuadRegression< Point, PointLabel, Segmentation::QPPF::QuadRegression< 2, Point, Segmentation::QPPF::CameraModel_Kinect< Point > > >.
Definition at line 107 of file quad_regression_algo.hpp.
bool Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::filterOccupied | ( | const int | i, |
const int | x, | ||
const int | y, | ||
const int | mark | ||
) | const [inline, private] |
Definition at line 191 of file quad_regression_algo.h.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::getExecutionTimes | ( | double & | quadtree, |
double & | growing, | ||
double & | extraction | ||
) | [inline] |
repeat back check on model
Definition at line 533 of file quad_regression_algo.h.
bool Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::getFilter | ( | ) | const [inline] |
setter for "only planes"-option (limits higher polynomials to planes afterwards)
Definition at line 523 of file quad_regression_algo.h.
int Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::getInd | ( | const int | i, |
const int | x, | ||
const int | y | ||
) | const [inline, protected] |
get index for element at (x,y) on level i (0: leaves) of quadtree
Definition at line 142 of file quad_regression_algo.h.
int Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::getIndPC | ( | const int | w, |
const int | x, | ||
const int | y | ||
) | const [inline, protected] |
get index for element at (x,y) in ordered pc
Definition at line 147 of file quad_regression_algo.h.
bool Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::getOnlyPlanes | ( | ) | const [inline] |
getter for filter parameter (pixels/area)
Definition at line 524 of file quad_regression_algo.h.
const std::vector<Segmentation::S_POLYGON<Degree> >& Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::getPolygons | ( | ) | const [inline] |
get polygons
Definition at line 518 of file quad_regression_algo.h.
int Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::getPos | ( | int * | ch, |
const int | xx, | ||
const int | yy, | ||
const int | w, | ||
const int | h | ||
) | [private] |
Definition at line 641 of file quad_regression_algo.hpp.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::grow | ( | SubStructure::Model< Degree > & | model, |
const int | i, | ||
const int | x, | ||
const int | y | ||
) | [private] |
filter option
Definition at line 406 of file quad_regression_algo.hpp.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::grow | ( | SubStructure::VISITED_LIST< SubStructure::SVALUE > & | list, |
SubStructure::Model< Degree > & | model, | ||
const int | i, | ||
const int | mark, | ||
bool | first_lvl | ||
) | [private] |
Definition at line 415 of file quad_regression_algo.hpp.
int Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::isOccupied | ( | const int | i, |
const int | x, | ||
const int | y | ||
) | const [inline, protected] |
check occupation from down to top
Definition at line 152 of file quad_regression_algo.h.
int Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::otherOccupied | ( | const int | i, |
const int | x, | ||
const int | y, | ||
const int | mark | ||
) | const [inline, private] |
Definition at line 199 of file quad_regression_algo.h.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::outline | ( | int * | ch, |
const int | w, | ||
const int | h, | ||
std::vector< SubStructure::SXY > & | out, | ||
const int | i, | ||
S_POLYGON< Degree > & | poly, | ||
const SubStructure::Model< Degree > & | model, | ||
const int | mark | ||
) | [private] |
Definition at line 657 of file quad_regression_algo.hpp.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::prepare | ( | const pcl::PointCloud< Point > & | pc | ) | [virtual] |
getter for "only planes"-option (limits higher polynomials to planes afterwards)
Reimplemented in Segmentation::QPPF::QuadRegression_Downsampled< Degree, Point, CameraModel >.
Definition at line 116 of file quad_regression_algo.hpp.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::setFilter | ( | const float | f | ) | [inline] |
Definition at line 520 of file quad_regression_algo.h.
virtual void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::setInputCloud | ( | const boost::shared_ptr< const pcl::PointCloud< Point > > & | cloud | ) | [inline, virtual] |
sets preprocessed input cloud
Reimplemented in Segmentation::Segmentation_QuadRegression< Point, PointLabel, Segmentation::QPPF::QuadRegression< 2, Point, Segmentation::QPPF::CameraModel_Kinect< Point > > >.
Definition at line 507 of file quad_regression_algo.h.
void Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::setOnlyPlanes | ( | const bool | b | ) | [inline] |
setter for filter parameter (pixels/area)
Definition at line 521 of file quad_regression_algo.h.
CameraModel Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::camera_ [private] |
search down to ...
Definition at line 179 of file quad_regression_algo.h.
int* Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::ch_ [private] |
camera model
Definition at line 181 of file quad_regression_algo.h.
double Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::execution_time_growing_ [protected] |
Definition at line 167 of file quad_regression_algo.h.
double Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::execution_time_polyextraction_ [protected] |
Definition at line 167 of file quad_regression_algo.h.
double Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::execution_time_quadtree_ [protected] |
result of surface reconstruction
Definition at line 167 of file quad_regression_algo.h.
float Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::filter_ [private] |
remember size for var. above
Definition at line 185 of file quad_regression_algo.h.
const unsigned int Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::FINAL_LOD [private] |
minimum of nodes for a segment
Definition at line 175 of file quad_regression_algo.h.
const unsigned int Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::GO_DOWN_TO_LVL [private] |
lowest level = 0
Definition at line 176 of file quad_regression_algo.h.
boost::shared_ptr<const pcl::PointCloud<Point> > Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::input_ [protected] |
Definition at line 161 of file quad_regression_algo.h.
std::vector<SubStructure::ParamC<Degree> > Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::levels_ [protected] |
input point cloud (no need for color)
Definition at line 162 of file quad_regression_algo.h.
const unsigned int Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::MIN_LOD [private] |
Definition at line 174 of file quad_regression_algo.h.
bool Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::only_planes_ [private] |
ratio points per area
Definition at line 186 of file quad_regression_algo.h.
bool* Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::outline_check_ [private] |
mark-array
Definition at line 183 of file quad_regression_algo.h.
size_t Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::outline_check_size_ [private] |
needed for outline, no need to reallocate every time
Definition at line 184 of file quad_regression_algo.h.
std::vector<Segmentation::S_POLYGON<Degree> > Segmentation::QPPF::QuadRegression< Degree, Point, CameraModel >::polygons_ [protected] |
quad-tree levels/stages
Definition at line 163 of file quad_regression_algo.h.