#include <nurbs.h>
Classes | |
struct | SHAPE_S |
Public Member Functions | |
virtual bool | compute () |
void | compute_accuracy (float &mean, float &var, size_t &used, size_t &mem, size_t &points, float &avg_dist) |
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_NURBS () | |
constructor, setups variables | |
virtual void | setInputCloud (const boost::shared_ptr< const pcl::PointCloud< Point > > &cloud) |
sets preprocessed input cloud | |
virtual | ~Segmentation_NURBS () |
destructor | |
Private Attributes | |
double | dump_ |
boost::shared_ptr< const pcl::PointCloud< Point > > | input_ |
int | nurbs_order_ |
std::vector< SHAPE_S > | shapes_ |
a segmentation implementation based on quad-trees and regression
Segmentation::Segmentation_NURBS< Point, PointLabel >::Segmentation_NURBS | ( | ) | [inline] |
virtual Segmentation::Segmentation_NURBS< Point, PointLabel >::~Segmentation_NURBS | ( | ) | [inline, virtual] |
bool Segmentation::Segmentation_NURBS< Point, PointLabel >::compute | ( | ) | [virtual] |
Implements GeneralSegmentation< Point, PointLabel >.
void Segmentation::Segmentation_NURBS< Point, PointLabel >::compute_accuracy | ( | float & | mean, |
float & | var, | ||
size_t & | used, | ||
size_t & | mem, | ||
size_t & | points, | ||
float & | avg_dist | ||
) |
void Segmentation::Segmentation_NURBS< Point, PointLabel >::enableCylinders | ( | const bool | b | ) | [inline] |
void Segmentation::Segmentation_NURBS< Point, PointLabel >::enablePlanes | ( | const bool | b | ) | [inline] |
void Segmentation::Segmentation_NURBS< Point, PointLabel >::enableSpheres | ( | const bool | b | ) | [inline] |
virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > Segmentation::Segmentation_NURBS< Point, PointLabel >::getOutputCloud | ( | ) | [inline, virtual] |
gets preprocessed output cloud
Implements GeneralSegmentation< Point, PointLabel >.
boost::shared_ptr< const pcl::PointCloud< PointLabel > > Segmentation::Segmentation_NURBS< Point, PointLabel >::getReconstructedOutputCloud | ( | ) | [virtual] |
virtual Segmentation::Segmentation_NURBS< Point, PointLabel >::operator cob_3d_mapping_msgs::ShapeArray | ( | ) | const [inline, virtual] |
convert to ROS message
Implements GeneralSegmentation< Point, PointLabel >.
Segmentation::Segmentation_NURBS< Point, PointLabel >::operator visualization_msgs::Marker | ( | ) | const |
convert edges to ROS message
virtual void Segmentation::Segmentation_NURBS< Point, PointLabel >::setInputCloud | ( | const boost::shared_ptr< const pcl::PointCloud< Point > > & | cloud | ) | [inline, virtual] |
sets preprocessed input cloud
Implements GeneralSegmentation< Point, PointLabel >.
double Segmentation::Segmentation_NURBS< Point, PointLabel >::dump_ [private] |
boost::shared_ptr<const pcl::PointCloud<Point> > Segmentation::Segmentation_NURBS< Point, PointLabel >::input_ [private] |
int Segmentation::Segmentation_NURBS< Point, PointLabel >::nurbs_order_ [private] |
std::vector<SHAPE_S> Segmentation::Segmentation_NURBS< Point, PointLabel >::shapes_ [private] |