Public Member Functions | Private Attributes
Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel > Class Template Reference

#include <multi_plane.h>

Inheritance diagram for Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool compute ()
void compute_accuracy (float &mean, float &var, float &mean_weighted, float &var_weighted, size_t &used, size_t &mem, size_t &points, float &avg_dist, const boost::shared_ptr< const pcl::PointCloud< PointLabel > > &labeled_pc, double &true_positive, double &false_positive)
virtual boost::shared_ptr
< const pcl::PointCloud
< PointLabel > > 
getOutputCloud ()
 gets preprocessed output cloud
virtual boost::shared_ptr
< const pcl::PointCloud
< PointLabel > > 
getReconstructedOutputCloud ()
 gets reconstructed output cloud
virtual operator cob_3d_mapping_msgs::ShapeArray () const
 convert to ROS message
 operator visualization_msgs::Marker () const
 convert edges to ROS message
 Segmentation_MultiPlane ()
 constructor, setups variables
virtual void setInputCloud (const boost::shared_ptr< const pcl::PointCloud< Point > > &cloud)
 sets preprocessed input cloud
virtual ~Segmentation_MultiPlane ()
 destructor

Private Attributes

std::vector< pcl::PointIndices > boundary_indices
std::vector
< pcl::ModelCoefficients > 
coef
std::vector< pcl::PointIndices > inlier_indices
boost::shared_ptr< const
pcl::PointCloud< Point > > 
input_
pcl::PointCloud< pcl::Label >::Ptr l
std::vector< pcl::PointIndices > label_indices
std::vector< typename
pcl::PlanarRegion< Point >
, Eigen::aligned_allocator
< typename pcl::PlanarRegion
< Point > > > 
regions

Detailed Description

template<typename Point, typename PointTypeNormal, typename PointLabel>
class Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >

a segmentation implementation based on quad-trees and regression

Definition at line 75 of file multi_plane.h.


Constructor & Destructor Documentation

template<typename Point, typename PointTypeNormal, typename PointLabel>
Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::Segmentation_MultiPlane ( ) [inline]

constructor, setups variables

Definition at line 88 of file multi_plane.h.

template<typename Point, typename PointTypeNormal, typename PointLabel>
virtual Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::~Segmentation_MultiPlane ( ) [inline, virtual]

destructor

Definition at line 92 of file multi_plane.h.


Member Function Documentation

template<typename Point , typename PointTypeNormal , typename PointLabel >
bool Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::compute ( ) [virtual]

Implements GeneralSegmentation< Point, PointLabel >.

Definition at line 12 of file multi_plane.hpp.

template<typename Point , typename PointTypeNormal , typename PointLabel >
void Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::compute_accuracy ( float &  mean,
float &  var,
float &  mean_weighted,
float &  var_weighted,
size_t &  used,
size_t &  mem,
size_t &  points,
float &  avg_dist,
const boost::shared_ptr< const pcl::PointCloud< PointLabel > > &  labeled_pc,
double &  true_positive,
double &  false_positive 
)

Definition at line 84 of file multi_plane.hpp.

template<typename Point, typename PointTypeNormal, typename PointLabel>
virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::getOutputCloud ( ) [inline, virtual]

gets preprocessed output cloud

Implements GeneralSegmentation< Point, PointLabel >.

Definition at line 113 of file multi_plane.h.

template<typename Point , typename PointTypeNormal , typename PointLabel >
boost::shared_ptr< const pcl::PointCloud< PointLabel > > Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::getReconstructedOutputCloud ( ) [virtual]

gets reconstructed output cloud

Definition at line 51 of file multi_plane.hpp.

template<typename Point, typename PointTypeNormal, typename PointLabel>
virtual Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::operator cob_3d_mapping_msgs::ShapeArray ( ) const [inline, virtual]

convert to ROS message

Implements GeneralSegmentation< Point, PointLabel >.

Definition at line 116 of file multi_plane.h.

template<typename Point, typename PointTypeNormal, typename PointLabel>
Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::operator visualization_msgs::Marker ( ) const

convert edges to ROS message

template<typename Point, typename PointTypeNormal, typename PointLabel>
virtual void Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::setInputCloud ( const boost::shared_ptr< const pcl::PointCloud< Point > > &  cloud) [inline, virtual]

sets preprocessed input cloud

Implements GeneralSegmentation< Point, PointLabel >.

Definition at line 96 of file multi_plane.h.


Member Data Documentation

template<typename Point, typename PointTypeNormal, typename PointLabel>
std::vector<pcl::PointIndices> Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::boundary_indices [private]

Definition at line 81 of file multi_plane.h.

template<typename Point, typename PointTypeNormal, typename PointLabel>
std::vector<pcl::ModelCoefficients> Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::coef [private]

Definition at line 78 of file multi_plane.h.

template<typename Point, typename PointTypeNormal, typename PointLabel>
std::vector<pcl::PointIndices> Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::inlier_indices [private]

Definition at line 79 of file multi_plane.h.

template<typename Point, typename PointTypeNormal, typename PointLabel>
boost::shared_ptr<const pcl::PointCloud<Point> > Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::input_ [private]

Definition at line 84 of file multi_plane.h.

template<typename Point, typename PointTypeNormal, typename PointLabel>
pcl::PointCloud<pcl::Label>::Ptr Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::l [private]

Definition at line 82 of file multi_plane.h.

template<typename Point, typename PointTypeNormal, typename PointLabel>
std::vector<pcl::PointIndices> Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::label_indices [private]

Definition at line 80 of file multi_plane.h.

template<typename Point, typename PointTypeNormal, typename PointLabel>
std::vector<typename pcl::PlanarRegion<Point>, Eigen::aligned_allocator<typename pcl::PlanarRegion<Point> > > Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::regions [private]

Definition at line 77 of file multi_plane.h.


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


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:04