#include <multi_plane.h>

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 |
a segmentation implementation based on quad-trees and regression
Definition at line 75 of file multi_plane.h.
| Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::Segmentation_MultiPlane | ( | ) | [inline] |
constructor, setups variables
Definition at line 88 of file multi_plane.h.
| virtual Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::~Segmentation_MultiPlane | ( | ) | [inline, virtual] |
destructor
Definition at line 92 of file multi_plane.h.
| bool Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::compute | ( | ) | [virtual] |
Implements GeneralSegmentation< Point, PointLabel >.
Definition at line 12 of file multi_plane.hpp.
| 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.
| 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.
| 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.
| 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.
| Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::operator visualization_msgs::Marker | ( | ) | const |
convert edges to ROS message
| 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.
std::vector<pcl::PointIndices> Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::boundary_indices [private] |
Definition at line 81 of file multi_plane.h.
std::vector<pcl::ModelCoefficients> Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::coef [private] |
Definition at line 78 of file multi_plane.h.
std::vector<pcl::PointIndices> Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::inlier_indices [private] |
Definition at line 79 of file multi_plane.h.
boost::shared_ptr<const pcl::PointCloud<Point> > Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::input_ [private] |
Definition at line 84 of file multi_plane.h.
pcl::PointCloud<pcl::Label>::Ptr Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::l [private] |
Definition at line 82 of file multi_plane.h.
std::vector<pcl::PointIndices> Segmentation::Segmentation_MultiPlane< Point, PointTypeNormal, PointLabel >::label_indices [private] |
Definition at line 80 of file multi_plane.h.
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.