#include <ransac.h>

Classes | |
| struct | SHAPE_S |
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) |
| void | enableCylinders (const bool b) |
| void | enablePlanes (const bool b) |
| void | enableSpheres (const bool b) |
| 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_RANSAC () | |
| constructor, setups variables | |
| virtual void | setInputCloud (const boost::shared_ptr< const pcl::PointCloud< Point > > &cloud) |
| sets preprocessed input cloud | |
| virtual | ~Segmentation_RANSAC () |
| destructor | |
Private Attributes | |
| bool | cylinders_ |
| boost::shared_ptr< const pcl::PointCloud< Point > > | input_ |
| bool | planes_ |
| std::vector< SHAPE_S > | shapes_ |
| bool | spheres_ |
a segmentation implementation based on quad-trees and regression
| Segmentation::Segmentation_RANSAC< Point, PointLabel >::Segmentation_RANSAC | ( | ) | [inline] |
| virtual Segmentation::Segmentation_RANSAC< Point, PointLabel >::~Segmentation_RANSAC | ( | ) | [inline, virtual] |
| bool Segmentation::Segmentation_RANSAC< Point, PointLabel >::compute | ( | ) | [virtual] |
Implements GeneralSegmentation< Point, PointLabel >.
Definition at line 12 of file ransac.hpp.
| void Segmentation::Segmentation_RANSAC< Point, 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 109 of file ransac.hpp.
| void Segmentation::Segmentation_RANSAC< Point, PointLabel >::enableCylinders | ( | const bool | b | ) | [inline] |
| void Segmentation::Segmentation_RANSAC< Point, PointLabel >::enablePlanes | ( | const bool | b | ) | [inline] |
| void Segmentation::Segmentation_RANSAC< Point, PointLabel >::enableSpheres | ( | const bool | b | ) | [inline] |
| virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > Segmentation::Segmentation_RANSAC< Point, PointLabel >::getOutputCloud | ( | ) | [inline, virtual] |
gets preprocessed output cloud
Implements GeneralSegmentation< Point, PointLabel >.
| boost::shared_ptr< const pcl::PointCloud< PointLabel > > Segmentation::Segmentation_RANSAC< Point, PointLabel >::getReconstructedOutputCloud | ( | ) | [virtual] |
gets reconstructed output cloud
Definition at line 69 of file ransac.hpp.
| virtual Segmentation::Segmentation_RANSAC< Point, PointLabel >::operator cob_3d_mapping_msgs::ShapeArray | ( | ) | const [inline, virtual] |
convert to ROS message
Implements GeneralSegmentation< Point, PointLabel >.
| Segmentation::Segmentation_RANSAC< Point, PointLabel >::operator visualization_msgs::Marker | ( | ) | const |
convert edges to ROS message
| virtual void Segmentation::Segmentation_RANSAC< Point, PointLabel >::setInputCloud | ( | const boost::shared_ptr< const pcl::PointCloud< Point > > & | cloud | ) | [inline, virtual] |
sets preprocessed input cloud
Implements GeneralSegmentation< Point, PointLabel >.
bool Segmentation::Segmentation_RANSAC< Point, PointLabel >::cylinders_ [private] |
boost::shared_ptr<const pcl::PointCloud<Point> > Segmentation::Segmentation_RANSAC< Point, PointLabel >::input_ [private] |
bool Segmentation::Segmentation_RANSAC< Point, PointLabel >::planes_ [private] |
std::vector<SHAPE_S> Segmentation::Segmentation_RANSAC< Point, PointLabel >::shapes_ [private] |
bool Segmentation::Segmentation_RANSAC< Point, PointLabel >::spheres_ [private] |