Public Member Functions | Private Attributes | List of all members
CylindricalShell Class Reference

CylindricalShell represents a cylindrical shell that consists of two colinear cylinders. A shell consists of an inner and an outer cylinder. The portion of the object to be grasped must fit inside the inner cylinder, and the radius of that cylinder must be no larger than the maximum hand aperture. The gap between the inner and outer cylinder must be free of obstacles and wide enough to be able to contain the robot fingers. More...

#include <cylindrical_shell.h>

Public Member Functions

void fitCylinder (const PointCloud::Ptr &cloud, const std::vector< int > &indices, const Eigen::Vector3d &normal, const Eigen::Vector3d &curvature_axis)
 Fit a cylinder to a set of points in the cloud, using their indices, and the normal and the curvature axis given by the quadric fitting (see curvature_estimation_taubin.h). The fitted cylinder is the inner cylinder of the cylindrical shell. More...
 
Eigen::Vector3d getCentroid () const
 Get the centroid of the cylindrical shell. More...
 
Eigen::Vector3d getCurvatureAxis () const
 Get the curvature axis of the cylindrical shell. More...
 
double getExtent () const
 Get the extent of the cylindrical shell. More...
 
int getNeighborhoodCentroidIndex () const
 Get the index of the centroid of the neighborhood associated with the cylindrical shell. More...
 
Eigen::Vector3d getNormal () const
 Get the normal axis of the cylindrical shell. More...
 
double getRadius () const
 Get the radius of the cylindrical shell. More...
 
bool hasClearance (const PointCloud::Ptr &cloud, const std::vector< int > &nn_indices, double maxHandAperture, double handleGap)
 Check whether the gap between the inner and outer cylinder of the shell is free of obstacles and wide enough to be able to contain the robot fingers. More...
 
void setExtent (double extent)
 Set the extent of the cylindrical shell. More...
 
void setNeighborhoodCentroidIndex (int index)
 Set the index of the centroid of the neighborhood associated with the cylindrical shell. More...
 

Private Attributes

Eigen::Vector3d centroid
 
Eigen::Vector3d curvature_axis
 
double extent
 
int neighborhood_centroid_index
 
Eigen::Vector3d normal
 
double radius
 

Detailed Description

CylindricalShell represents a cylindrical shell that consists of two colinear cylinders. A shell consists of an inner and an outer cylinder. The portion of the object to be grasped must fit inside the inner cylinder, and the radius of that cylinder must be no larger than the maximum hand aperture. The gap between the inner and outer cylinder must be free of obstacles and wide enough to be able to contain the robot fingers.

Author
Andreas ten Pas

Definition at line 49 of file cylindrical_shell.h.

Member Function Documentation

void CylindricalShell::fitCylinder ( const PointCloud::Ptr &  cloud,
const std::vector< int > &  indices,
const Eigen::Vector3d &  normal,
const Eigen::Vector3d &  curvature_axis 
)

Fit a cylinder to a set of points in the cloud, using their indices, and the normal and the curvature axis given by the quadric fitting (see curvature_estimation_taubin.h). The fitted cylinder is the inner cylinder of the cylindrical shell.

Parameters
cloudthe point cloud
indicesthe indices of the set of points in the cloud
normalthe normal given by quadric fitting
curvature_axisthe curvature axis given by quadric fitting

Definition at line 3 of file cylindrical_shell.cpp.

Eigen::Vector3d CylindricalShell::getCentroid ( ) const
inline

Get the centroid of the cylindrical shell.

Definition at line 121 of file cylindrical_shell.h.

Eigen::Vector3d CylindricalShell::getCurvatureAxis ( ) const
inline

Get the curvature axis of the cylindrical shell.

Definition at line 129 of file cylindrical_shell.h.

double CylindricalShell::getExtent ( ) const
inline

Get the extent of the cylindrical shell.

Definition at line 77 of file cylindrical_shell.h.

int CylindricalShell::getNeighborhoodCentroidIndex ( ) const
inline

Get the index of the centroid of the neighborhood associated with the cylindrical shell.

Definition at line 103 of file cylindrical_shell.h.

Eigen::Vector3d CylindricalShell::getNormal ( ) const
inline

Get the normal axis of the cylindrical shell.

Definition at line 137 of file cylindrical_shell.h.

double CylindricalShell::getRadius ( ) const
inline

Get the radius of the cylindrical shell.

Definition at line 94 of file cylindrical_shell.h.

bool CylindricalShell::hasClearance ( const PointCloud::Ptr &  cloud,
const std::vector< int > &  nn_indices,
double  maxHandAperture,
double  handleGap 
)

Check whether the gap between the inner and outer cylinder of the shell is free of obstacles and wide enough to be able to contain the robot fingers.

Parameters
cloudthe point cloud
maxHandAperturethe maximum robot hand aperture
handleGapthe required size of the gap around the handle

Definition at line 49 of file cylindrical_shell.cpp.

void CylindricalShell::setExtent ( double  extent)
inline

Set the extent of the cylindrical shell.

Parameters
extentthe extent

Definition at line 86 of file cylindrical_shell.h.

void CylindricalShell::setNeighborhoodCentroidIndex ( int  index)
inline

Set the index of the centroid of the neighborhood associated with the cylindrical shell.

Parameters
indexthe index of the centroid

Definition at line 113 of file cylindrical_shell.h.

Member Data Documentation

Eigen::Vector3d CylindricalShell::centroid
private

Definition at line 141 of file cylindrical_shell.h.

Eigen::Vector3d CylindricalShell::curvature_axis
private

Definition at line 146 of file cylindrical_shell.h.

double CylindricalShell::extent
private

Definition at line 147 of file cylindrical_shell.h.

int CylindricalShell::neighborhood_centroid_index
private

Definition at line 150 of file cylindrical_shell.h.

Eigen::Vector3d CylindricalShell::normal
private

Definition at line 149 of file cylindrical_shell.h.

double CylindricalShell::radius
private

Definition at line 148 of file cylindrical_shell.h.


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


handle_detector
Author(s):
autogenerated on Mon Jun 10 2019 13:29:00