Namespaces | Classes | Typedefs | Functions
tabletop_pushing Namespace Reference

Namespaces

namespace  position_feedback_push_node
namespace  push_learning
namespace  push_primitives
namespace  rbf_control
namespace  singulation_executive
namespace  tabletop_executive
namespace  tabletop_push_node

Classes

class  ArmObjSegmentation
class  NodeTable
class  ObjectTracker25D
class  PointCloudSegmentation
class  ProtoObject
class  ShapeLocation

Typedefs

typedef Graph< float, float,
float > 
GraphType
typedef pcl16::PointCloud
< pcl16::Normal > 
NormalCloud
typedef std::deque< ProtoObjectProtoObjects
typedef std::vector
< ShapeLocation
ShapeLocations
typedef pcl16::PointCloud
< pcl16::PointXYZ > 
XYZPointCloud

Functions

int closestShapeFeatureCluster (cpl_visual_features::ShapeDescriptor &descriptor, cpl_visual_features::ShapeDescriptors &centers, double &min_dist)
void clusterShapeFeatures (ShapeLocations &locs, int k, std::vector< int > &cluster_ids, cpl_visual_features::ShapeDescriptors &centers, double min_err_change, int max_iter, int num_retries=5)
cpl_visual_features::Path compareBoundaryShapes (XYZPointCloud &hull_a, XYZPointCloud &hull_b, double &min_cost, double epsilon_cost=0.99)
cv::Mat computeChi2Kernel (cpl_visual_features::ShapeDescriptors &sds, std::string feat_path, int local_length, int global_length, double gamma_local, double gamma_global, double mixture_weight)
cv::Mat computeShapeFeatureAffinityMatrix (ShapeLocations &locs, bool use_center=false)
void drawSamplePoints (XYZPointCloud &hull, XYZPointCloud &samples, double alpha, pcl16::PointXYZ &center_pt, pcl16::PointXYZ &sample_pt, pcl16::PointXYZ &approach_pt, pcl16::PointXYZ e_left, pcl16::PointXYZ e_right, pcl16::PointXYZ c_left, pcl16::PointXYZ c_right, pcl16::PointXYZ i_left, pcl16::PointXYZ i_right, double x_res, double y_res, double x_range, double y_range, ProtoObject &cur_obj)
void estimateTransformFromMatches (XYZPointCloud &cloud_t_0, XYZPointCloud &cloud_t_1, cpl_visual_features::Path p, Eigen::Matrix4f &transform, double max_dist=0.3)
void extractBoundingBoxFeatures (XYZPointCloud &samples, cpl_visual_features::ShapeDescriptor &sd)
ShapeDescriptor extractGlobalShapeFeatures (XYZPointCloud &hull, ProtoObject &cur_obj, pcl16::PointXYZ sample_pt, int sample_pt_idx, double sample_spread)
cpl_visual_features::ShapeDescriptors extractLocalAndGlobalShapeFeatures (XYZPointCloud &hull, ProtoObject &cur_obj, double sample_spread, double hull_alpha, double hist_res)
cpl_visual_features::ShapeDescriptor extractLocalAndGlobalShapeFeatures (XYZPointCloud &hull, ProtoObject &cur_obj, pcl16::PointXYZ sample_pt, int sample_pt_idx, double sample_spread, double hull_alpha, double hist_res)
cpl_visual_features::ShapeDescriptor extractLocalShapeFeatures (XYZPointCloud &samples_pcl, ProtoObject &cur_obj, pcl16::PointXYZ sample_loc, double s, double hull_alpha, double hist_res)
ShapeLocations extractObjectShapeContext (ProtoObject &cur_obj, bool use_center=true)
void extractPCAFeaturesXY (XYZPointCloud &samples, cpl_visual_features::ShapeDescriptor &sd)
cpl_visual_features::ShapeDescriptor extractPointHistogramXY (XYZPointCloud &samples, double x_res, double y_res, double x_range, double y_range)
ShapeLocations extractShapeContextFromSamples (XYZPointCloud &samples_pcl, ProtoObject &cur_obj, bool use_center)
void getCovarianceXYFromPoints (XYZPointCloud &pts, cpl_visual_features::ShapeDescriptor &sd)
int getHistBinIdx (int x_idx, int y_idx, int n_x_bins, int n_y_bins)
std::vector< int > getJumpIndices (XYZPointCloud &concave_hull, double alpha)
XYZPointCloud getLocalSamples (XYZPointCloud &samples_pcl, ProtoObject &cur_obj, pcl16::PointXYZ sample_loc, double s, double hull_alpha)
XYZPointCloud getLocalSamplesNew (XYZPointCloud &hull, ProtoObject &cur_obj, pcl16::PointXYZ sample_pt, double sample_spread, double alpha)
void getMaskedPointCloud (XYZPointCloud &input_cloud, cv::Mat &mask, XYZPointCloud &masked_cloud)
XYZPointCloud getObjectBoundarySamples (ProtoObject &cur_obj, double hull_alpha=0.01)
cv::Mat getObjectFootprint (cv::Mat obj_mask, XYZPointCloud &cloud)
void getPointRangesXY (XYZPointCloud &samples, cpl_visual_features::ShapeDescriptor &sd)
cpl_visual_features::ShapeDescriptors loadSVRTrainingFeatures (std::string feature_path, int feat_length)
cv::Mat makeHistogramImage (ShapeDescriptor histogram, int n_x_bins, int n_y_bins, int bin_width_pixels)
int objLocToIdx (double val, double min_val, double max_val)
double shapeFeatureChiSquareDist (cpl_visual_features::ShapeDescriptor &a, cpl_visual_features::ShapeDescriptor &b, double gamma=0.0)
double shapeFeatureSquaredEuclideanDist (cpl_visual_features::ShapeDescriptor &a, cpl_visual_features::ShapeDescriptor &b)
XYZPointCloud transformSamplesIntoSampleLocFrame (XYZPointCloud &samples, ProtoObject &cur_obj, pcl16::PointXYZ sample_pt)
cv::Mat visualizeObjectBoundaryMatches (XYZPointCloud &hull_a, XYZPointCloud &hull_b, tabletop_pushing::VisFeedbackPushTrackingFeedback &cur_state, cpl_visual_features::Path &path)
cv::Mat visualizeObjectBoundarySamples (XYZPointCloud &hull_cloud, tabletop_pushing::VisFeedbackPushTrackingFeedback &cur_state)
cv::Mat visualizeObjectContactLocation (XYZPointCloud &hull_cloud, tabletop_pushing::VisFeedbackPushTrackingFeedback &cur_state, pcl16::PointXYZ &contact_pt, pcl16::PointXYZ &forward_pt)
int worldLocToIdx (double val, double min_val, double max_val)
pcl16::PointXYZ worldPointInObjectFrame (pcl16::PointXYZ world_pt, PushTrackerState &cur_state)
cv::Point worldPtToImgPt (pcl16::PointXYZ world_pt, double min_x, double max_x, double min_y, double max_y)

Typedef Documentation

typedef Graph<float, float, float> tabletop_pushing::GraphType

Definition at line 11 of file arm_obj_segmentation.h.

Definition at line 68 of file point_cloud_segmentation.h.

Definition at line 83 of file point_cloud_segmentation.h.

Definition at line 31 of file shape_features.h.

Definition at line 67 of file point_cloud_segmentation.h.


Function Documentation

int tabletop_pushing::closestShapeFeatureCluster ( ShapeDescriptor descriptor,
ShapeDescriptors centers,
double &  min_dist 
)

Find the nearest cluster center to the given descriptor

Parameters:
descriptorThe query descriptor
centersThe set of cluster centers
Returns:
The cluster id (index) of the nearest center

Definition at line 1375 of file shape_features.cpp.

void tabletop_pushing::clusterShapeFeatures ( ShapeLocations &  locs,
int  k,
std::vector< int > &  cluster_ids,
cpl_visual_features::ShapeDescriptors centers,
double  min_err_change,
int  max_iter,
int  num_retries = 5 
)

Definition at line 1327 of file shape_features.cpp.

cpl_visual_features::Path tabletop_pushing::compareBoundaryShapes ( XYZPointCloud hull_a,
XYZPointCloud hull_b,
double &  min_cost,
double  epsilon_cost = 0.99 
)

Definition at line 100 of file shape_features.cpp.

cv::Mat tabletop_pushing::computeChi2Kernel ( cpl_visual_features::ShapeDescriptors sds,
std::string  feat_path,
int  local_length,
int  global_length,
double  gamma_local,
double  gamma_global,
double  mixture_weight 
)

Definition at line 1441 of file shape_features.cpp.

cv::Mat tabletop_pushing::computeShapeFeatureAffinityMatrix ( ShapeLocations &  locs,
bool  use_center 
)

Create an affinity matrix for a set of ShapeLocations

Parameters:
locsThe vector of ShapeLocation descriptors to compare
Returns:
An upper-triangular matrix of all pairwise distances between descriptors

Definition at line 1227 of file shape_features.cpp.

void tabletop_pushing::drawSamplePoints ( XYZPointCloud hull,
XYZPointCloud samples,
double  alpha,
pcl16::PointXYZ &  center_pt,
pcl16::PointXYZ &  sample_pt,
pcl16::PointXYZ &  approach_pt,
pcl16::PointXYZ  e_left,
pcl16::PointXYZ  e_right,
pcl16::PointXYZ  c_left,
pcl16::PointXYZ  c_right,
pcl16::PointXYZ  i_left,
pcl16::PointXYZ  i_right,
double  x_res,
double  y_res,
double  x_range,
double  y_range,
ProtoObject cur_obj 
)

Definition at line 383 of file shape_features.cpp.

void tabletop_pushing::estimateTransformFromMatches ( XYZPointCloud cloud_t_0,
XYZPointCloud cloud_t_1,
cpl_visual_features::Path  p,
Eigen::Matrix4f &  transform,
double  max_dist = 0.3 
)

Definition at line 129 of file shape_features.cpp.

Definition at line 1010 of file shape_features.cpp.

ShapeDescriptor tabletop_pushing::extractGlobalShapeFeatures ( XYZPointCloud hull,
ProtoObject cur_obj,
pcl16::PointXYZ  sample_pt,
int  sample_pt_idx,
double  sample_spread 
)

Definition at line 1052 of file shape_features.cpp.

ShapeDescriptors tabletop_pushing::extractLocalAndGlobalShapeFeatures ( XYZPointCloud hull,
ProtoObject cur_obj,
double  sample_spread,
double  hull_alpha,
double  hist_res 
)

Definition at line 1085 of file shape_features.cpp.

ShapeDescriptor tabletop_pushing::extractLocalAndGlobalShapeFeatures ( XYZPointCloud hull,
ProtoObject cur_obj,
pcl16::PointXYZ  sample_pt,
int  sample_pt_idx,
double  sample_spread,
double  hull_alpha,
double  hist_res 
)

Definition at line 1099 of file shape_features.cpp.

ShapeDescriptor tabletop_pushing::extractLocalShapeFeatures ( XYZPointCloud samples_pcl,
ProtoObject cur_obj,
pcl16::PointXYZ  sample_loc,
double  s,
double  hull_alpha,
double  hist_res 
)

Definition at line 1026 of file shape_features.cpp.

Definition at line 313 of file shape_features.cpp.

Definition at line 986 of file shape_features.cpp.

ShapeDescriptor tabletop_pushing::extractPointHistogramXY ( XYZPointCloud samples,
double  x_res,
double  y_res,
double  x_range,
double  y_range 
)

Definition at line 878 of file shape_features.cpp.

Definition at line 319 of file shape_features.cpp.

Definition at line 948 of file shape_features.cpp.

int tabletop_pushing::getHistBinIdx ( int  x_idx,
int  y_idx,
int  n_x_bins,
int  n_y_bins 
) [inline]

Definition at line 26 of file shape_features.cpp.

std::vector<int> tabletop_pushing::getJumpIndices ( XYZPointCloud concave_hull,
double  alpha 
)

Definition at line 66 of file shape_features.cpp.

XYZPointCloud tabletop_pushing::getLocalSamples ( XYZPointCloud samples_pcl,
ProtoObject cur_obj,
pcl16::PointXYZ  sample_loc,
double  s,
double  hull_alpha 
)

Definition at line 623 of file shape_features.cpp.

XYZPointCloud tabletop_pushing::getLocalSamplesNew ( XYZPointCloud hull,
ProtoObject cur_obj,
pcl16::PointXYZ  sample_pt,
double  sample_spread,
double  alpha 
)

Definition at line 526 of file shape_features.cpp.

void tabletop_pushing::getMaskedPointCloud ( XYZPointCloud input_cloud,
cv::Mat &  mask,
XYZPointCloud masked_cloud 
)

Definition at line 372 of file point_cloud_segmentation.h.

XYZPointCloud tabletop_pushing::getObjectBoundarySamples ( ProtoObject cur_obj,
double  hull_alpha = 0.01 
)

Definition at line 79 of file shape_features.cpp.

cv::Mat tabletop_pushing::getObjectFootprint ( cv::Mat  obj_mask,
XYZPointCloud cloud 
)

Definition at line 249 of file shape_features.cpp.

Definition at line 915 of file shape_features.cpp.

ShapeDescriptors tabletop_pushing::loadSVRTrainingFeatures ( std::string  feature_path,
int  feat_length 
)

Definition at line 1401 of file shape_features.cpp.

cv::Mat tabletop_pushing::makeHistogramImage ( ShapeDescriptor  histogram,
int  n_x_bins,
int  n_y_bins,
int  bin_width_pixels 
)

Definition at line 342 of file shape_features.cpp.

int tabletop_pushing::objLocToIdx ( double  val,
double  min_val,
double  max_val 
) [inline]

Definition at line 36 of file shape_features.cpp.

Compute the (chi-squared) distance between two ShapeLocation descriptors

Parameters:
aThe first descriptor
bThe second descriptor
gammaOptional scaling value for exponential chi-square kernel
Returns:
The distance between a and b

Definition at line 1286 of file shape_features.cpp.

Compute the squared euclidean distance between two ShapeLocation descriptors

Parameters:
aThe first descriptor
bThe second descriptor
Returns:
The distance between a and b

Definition at line 1316 of file shape_features.cpp.

XYZPointCloud tabletop_pushing::transformSamplesIntoSampleLocFrame ( XYZPointCloud samples,
ProtoObject cur_obj,
pcl16::PointXYZ  sample_pt 
)

Definition at line 859 of file shape_features.cpp.

cv::Mat tabletop_pushing::visualizeObjectBoundaryMatches ( XYZPointCloud hull_a,
XYZPointCloud hull_b,
tabletop_pushing::VisFeedbackPushTrackingFeedback &  cur_state,
cpl_visual_features::Path path 
)

Definition at line 177 of file shape_features.cpp.

cv::Mat tabletop_pushing::visualizeObjectBoundarySamples ( XYZPointCloud hull_cloud,
tabletop_pushing::VisFeedbackPushTrackingFeedback &  cur_state 
)

Definition at line 156 of file shape_features.cpp.

cv::Mat tabletop_pushing::visualizeObjectContactLocation ( XYZPointCloud hull_cloud,
tabletop_pushing::VisFeedbackPushTrackingFeedback &  cur_state,
pcl16::PointXYZ &  contact_pt,
pcl16::PointXYZ &  forward_pt 
)

Definition at line 221 of file shape_features.cpp.

int tabletop_pushing::worldLocToIdx ( double  val,
double  min_val,
double  max_val 
) [inline]

Definition at line 31 of file shape_features.cpp.

pcl16::PointXYZ tabletop_pushing::worldPointInObjectFrame ( pcl16::PointXYZ  world_pt,
PushTrackerState cur_state 
)

Definition at line 49 of file shape_features.cpp.

cv::Point tabletop_pushing::worldPtToImgPt ( pcl16::PointXYZ  world_pt,
double  min_x,
double  max_x,
double  min_y,
double  max_y 
)

Definition at line 41 of file shape_features.cpp.



tabletop_pushing
Author(s): Tucker Hermans
autogenerated on Wed Nov 27 2013 11:59:45