Classes | Public Member Functions | Protected Member Functions | Protected Attributes
SphereSegmentation Class Reference

#include <SphereSegmentation.h>

List of all members.

Classes

struct  Parameters

Public Member Functions

void fetchParameters (std::string nameSpace="")
Parameters getParameters ()
void getSphereCluster (sensor_msgs::PointCloud &cluster)
bool segment (const sensor_msgs::PointCloud &cloudMsg, arm_navigation_msgs::CollisionObject &obj)
bool segment (const sensor_msgs::PointCloud2 &cloudMsg, arm_navigation_msgs::CollisionObject &obj)
bool segment (const std::vector< sensor_msgs::PointCloud > &clusters, arm_navigation_msgs::CollisionObject &obj, int &bestClusterIndex)
bool segment (const Cloud3D &cluster, arm_navigation_msgs::CollisionObject &obj)
void setParameters (const Parameters &parameters)
 SphereSegmentation ()
virtual ~SphereSegmentation ()

Protected Member Functions

void concatenateClouds (const std::vector< sensor_msgs::PointCloud > &clusters, Cloud3D &cluster)
void createObject (const pcl::ModelCoefficients &coeffs, arm_navigation_msgs::CollisionObject &obj)
void filterBounds (Cloud3D &cloud)
void filterWithPolygonalPrism (Cloud3D &cloud, pcl::PointXYZ &point, int nSides, double radius, double heightMax, double heightMin)
bool findSphereUsingTopPoint (const Cloud3D &cloud, pcl::ModelCoefficients::Ptr coefficients, pcl::PointIndices::Ptr inliers)
bool findTopCentroid (const Cloud3D &cloud, pcl::PointXYZ &topCentroid)
bool performSphereSegmentation (const Cloud3D &cloud, pcl::ModelCoefficients::Ptr coefficients, pcl::PointIndices::Ptr inliers)

Protected Attributes

pcl::ModelCoefficients _LastCoefficients
pcl::PointIndices _LastIndices
double _LastSegmentationScore
Cloud3D _LastSphereSegCluster
bool _LastSphereSegSuccess
Parameters _Parameters
tf::TransformListener _TfListener

Detailed Description

Definition at line 31 of file SphereSegmentation.h.


Constructor & Destructor Documentation

Definition at line 25 of file SphereSegmentation.cpp.

Definition at line 36 of file SphereSegmentation.cpp.


Member Function Documentation

void SphereSegmentation::concatenateClouds ( const std::vector< sensor_msgs::PointCloud > &  clusters,
Cloud3D cluster 
) [protected]

Definition at line 604 of file SphereSegmentation.cpp.

void SphereSegmentation::createObject ( const pcl::ModelCoefficients &  coeffs,
arm_navigation_msgs::CollisionObject obj 
) [protected]

Definition at line 626 of file SphereSegmentation.cpp.

void SphereSegmentation::fetchParameters ( std::string  nameSpace = "")

Definition at line 50 of file SphereSegmentation.cpp.

void SphereSegmentation::filterBounds ( Cloud3D cloud) [protected]

Definition at line 542 of file SphereSegmentation.cpp.

void SphereSegmentation::filterWithPolygonalPrism ( Cloud3D cloud,
pcl::PointXYZ point,
int  nSides,
double  radius,
double  heightMax,
double  heightMin 
) [protected]

Definition at line 569 of file SphereSegmentation.cpp.

bool SphereSegmentation::findSphereUsingTopPoint ( const Cloud3D cloud,
pcl::ModelCoefficients::Ptr  coefficients,
pcl::PointIndices::Ptr  inliers 
) [protected]

Definition at line 278 of file SphereSegmentation.cpp.

bool SphereSegmentation::findTopCentroid ( const Cloud3D cloud,
pcl::PointXYZ topCentroid 
) [protected]

Definition at line 305 of file SphereSegmentation.cpp.

Definition at line 45 of file SphereSegmentation.cpp.

Definition at line 63 of file SphereSegmentation.cpp.

bool SphereSegmentation::performSphereSegmentation ( const Cloud3D cloud,
pcl::ModelCoefficients::Ptr  coefficients,
pcl::PointIndices::Ptr  inliers 
) [protected]

Definition at line 229 of file SphereSegmentation.cpp.

Definition at line 55 of file SphereSegmentation.cpp.

bool SphereSegmentation::segment ( const sensor_msgs::PointCloud2 &  cloudMsg,
arm_navigation_msgs::CollisionObject obj 
)

Definition at line 74 of file SphereSegmentation.cpp.

bool SphereSegmentation::segment ( const std::vector< sensor_msgs::PointCloud > &  clusters,
arm_navigation_msgs::CollisionObject obj,
int &  bestClusterIndex 
)

Definition at line 85 of file SphereSegmentation.cpp.

Definition at line 128 of file SphereSegmentation.cpp.

void SphereSegmentation::setParameters ( const Parameters parameters)

Definition at line 40 of file SphereSegmentation.cpp.


Member Data Documentation

pcl::ModelCoefficients SphereSegmentation::_LastCoefficients [protected]

Definition at line 148 of file SphereSegmentation.h.

pcl::PointIndices SphereSegmentation::_LastIndices [protected]

Definition at line 147 of file SphereSegmentation.h.

Definition at line 146 of file SphereSegmentation.h.

Definition at line 149 of file SphereSegmentation.h.

Definition at line 150 of file SphereSegmentation.h.

Definition at line 140 of file SphereSegmentation.h.

Definition at line 143 of file SphereSegmentation.h.


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


perception_tools
Author(s): Jnicho
autogenerated on Mon Oct 6 2014 01:01:21