Classes | Namespaces | Typedefs | Functions
shape_features.h File Reference
#include <ros/ros.h>
#include <opencv2/core/core.hpp>
#include <pcl16/point_cloud.h>
#include <pcl16/point_types.h>
#include <cpl_visual_features/features/shape_context.h>
#include <vector>
#include <tabletop_pushing/point_cloud_segmentation.h>
#include <tabletop_pushing/VisFeedbackPushTrackingAction.h>
Include dependency graph for shape_features.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  tabletop_pushing::ShapeLocation

Namespaces

namespace  tabletop_pushing

Typedefs

typedef std::vector
< ShapeLocation > 
tabletop_pushing::ShapeLocations

Functions

int tabletop_pushing::closestShapeFeatureCluster (cpl_visual_features::ShapeDescriptor &descriptor, cpl_visual_features::ShapeDescriptors &centers, double &min_dist)
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)
cpl_visual_features::Path tabletop_pushing::compareBoundaryShapes (XYZPointCloud &hull_a, XYZPointCloud &hull_b, double &min_cost, double epsilon_cost=0.99)
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)
cv::Mat tabletop_pushing::computeShapeFeatureAffinityMatrix (ShapeLocations &locs, bool use_center=false)
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)
void tabletop_pushing::extractBoundingBoxFeatures (XYZPointCloud &samples, cpl_visual_features::ShapeDescriptor &sd)
cpl_visual_features::ShapeDescriptors tabletop_pushing::extractLocalAndGlobalShapeFeatures (XYZPointCloud &hull, ProtoObject &cur_obj, double sample_spread, double hull_alpha, double hist_res)
cpl_visual_features::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)
cpl_visual_features::ShapeDescriptor tabletop_pushing::extractLocalShapeFeatures (XYZPointCloud &samples_pcl, ProtoObject &cur_obj, pcl16::PointXYZ sample_loc, double s, double hull_alpha, double hist_res)
ShapeLocations tabletop_pushing::extractObjectShapeContext (ProtoObject &cur_obj, bool use_center=true)
void tabletop_pushing::extractPCAFeaturesXY (XYZPointCloud &samples, cpl_visual_features::ShapeDescriptor &sd)
cpl_visual_features::ShapeDescriptor tabletop_pushing::extractPointHistogramXY (XYZPointCloud &samples, double x_res, double y_res, double x_range, double y_range)
ShapeLocations tabletop_pushing::extractShapeContextFromSamples (XYZPointCloud &samples_pcl, ProtoObject &cur_obj, bool use_center)
void tabletop_pushing::getCovarianceXYFromPoints (XYZPointCloud &pts, cpl_visual_features::ShapeDescriptor &sd)
XYZPointCloud tabletop_pushing::getLocalSamples (XYZPointCloud &samples_pcl, ProtoObject &cur_obj, pcl16::PointXYZ sample_loc, double s, double hull_alpha)
XYZPointCloud tabletop_pushing::getObjectBoundarySamples (ProtoObject &cur_obj, double hull_alpha=0.01)
cv::Mat tabletop_pushing::getObjectFootprint (cv::Mat obj_mask, XYZPointCloud &cloud)
void tabletop_pushing::getPointRangesXY (XYZPointCloud &samples, cpl_visual_features::ShapeDescriptor &sd)
cpl_visual_features::ShapeDescriptors tabletop_pushing::loadSVRTrainingFeatures (std::string feature_path, int feat_length)
double tabletop_pushing::shapeFeatureChiSquareDist (cpl_visual_features::ShapeDescriptor &a, cpl_visual_features::ShapeDescriptor &b, double gamma=0.0)
double tabletop_pushing::shapeFeatureSquaredEuclideanDist (cpl_visual_features::ShapeDescriptor &a, cpl_visual_features::ShapeDescriptor &b)
XYZPointCloud tabletop_pushing::transformSamplesIntoSampleLocFrame (XYZPointCloud &samples, ProtoObject &cur_obj, pcl16::PointXYZ sample_pt)
cv::Mat tabletop_pushing::visualizeObjectBoundaryMatches (XYZPointCloud &hull_a, XYZPointCloud &hull_b, tabletop_pushing::VisFeedbackPushTrackingFeedback &cur_state, cpl_visual_features::Path &path)
cv::Mat tabletop_pushing::visualizeObjectBoundarySamples (XYZPointCloud &hull_cloud, tabletop_pushing::VisFeedbackPushTrackingFeedback &cur_state)
cv::Mat tabletop_pushing::visualizeObjectContactLocation (XYZPointCloud &hull_cloud, tabletop_pushing::VisFeedbackPushTrackingFeedback &cur_state, pcl16::PointXYZ &contact_pt, pcl16::PointXYZ &forward_pt)


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