Namespaces |
namespace | tabletop_pushing |
Defines |
#define | DRAW_LR_LIMITS 1 |
#define | XY_RES 0.00075 |
Typedefs |
typedef
tabletop_pushing::VisFeedbackPushTrackingFeedback | PushTrackerState |
Functions |
int | tabletop_pushing::closestShapeFeatureCluster (cpl_visual_features::ShapeDescriptor &descriptor, cpl_visual_features::ShapeDescriptors ¢ers, double &min_dist) |
void | tabletop_pushing::clusterShapeFeatures (ShapeLocations &locs, int k, std::vector< int > &cluster_ids, cpl_visual_features::ShapeDescriptors ¢ers, 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::drawSamplePoints (XYZPointCloud &hull, XYZPointCloud &samples, double alpha, pcl16::PointXYZ ¢er_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 | 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) |
ShapeDescriptor | tabletop_pushing::extractGlobalShapeFeatures (XYZPointCloud &hull, ProtoObject &cur_obj, pcl16::PointXYZ sample_pt, int sample_pt_idx, double sample_spread) |
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) |
int | tabletop_pushing::getHistBinIdx (int x_idx, int y_idx, int n_x_bins, int n_y_bins) |
std::vector< int > | tabletop_pushing::getJumpIndices (XYZPointCloud &concave_hull, double alpha) |
XYZPointCloud | tabletop_pushing::getLocalSamples (XYZPointCloud &samples_pcl, ProtoObject &cur_obj, pcl16::PointXYZ sample_loc, double s, double hull_alpha) |
XYZPointCloud | tabletop_pushing::getLocalSamplesNew (XYZPointCloud &hull, ProtoObject &cur_obj, pcl16::PointXYZ sample_pt, double sample_spread, double 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) |
cv::Mat | tabletop_pushing::makeHistogramImage (ShapeDescriptor histogram, int n_x_bins, int n_y_bins, int bin_width_pixels) |
int | tabletop_pushing::objLocToIdx (double val, double min_val, double max_val) |
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) |
int | tabletop_pushing::worldLocToIdx (double val, double min_val, double max_val) |
pcl16::PointXYZ | tabletop_pushing::worldPointInObjectFrame (pcl16::PointXYZ world_pt, PushTrackerState &cur_state) |
cv::Point | tabletop_pushing::worldPtToImgPt (pcl16::PointXYZ world_pt, double min_x, double max_x, double min_y, double max_y) |