#include <sstream>
#include <iostream>
#include <fstream>
#include <tabletop_pushing/shape_features.h>
#include <ros/ros.h>
#include <pcl16/point_cloud.h>
#include <pcl16/point_types.h>
#include <pcl16/io/pcd_io.h>
#include <pcl16_ros/transforms.h>
#include <pcl16/ros/conversions.h>
#include <pcl16/common/pca.h>
#include <tabletop_pushing/VisFeedbackPushTrackingAction.h>
#include <tabletop_pushing/point_cloud_segmentation.h>
#include <cpl_visual_features/helpers.h>
#include <cpl_visual_features/features/kernels.h>
#include <time.h>
#include <libsvm/svm.h>
Go to the source code of this file.
Classes | |
class | TrialStuff |
Defines | |
#define | XY_RES 0.001 |
Typedefs | |
typedef tabletop_pushing::VisFeedbackPushTrackingFeedback | PushTrackerState |
Functions | |
ShapeLocation | chooseFixedGoalPushStartLoc (ProtoObject &cur_obj, PushTrackerState &cur_state, bool new_object, int num_start_loc_pushes_per_sample, int num_start_loc_sample_locs) |
ShapeLocation | chooseFixedGoalPushStartLoc (ProtoObject &cur_obj, PushTrackerState &cur_state, pcl16::PointXYZ start_pt) |
ShapeLocation | chooseLearnedPushStartLoc (ProtoObject &cur_obj, PushTrackerState &cur_state, std::string param_path, float &chosen_score) |
static double | dist (pcl16::PointXYZ a, pcl16::PointXYZ b) |
void | drawScores (std::vector< double > &push_scores, std::string out_file_path) |
void | getMajorMinorBoundaryDists (std::string cloud_path, pcl16::PointXYZ init_loc, pcl16::PointXYZ start_pt, double &major_dist, double &minor_dist) |
ShapeDescriptor | getTrialDescriptor (std::string cloud_path, pcl16::PointXYZ init_loc, double init_theta, bool new_object) |
ShapeDescriptor | getTrialDescriptor (std::string cloud_path, pcl16::PointXYZ init_loc, double init_theta, pcl16::PointXYZ start_pt) |
std::vector< TrialStuff > | getTrialsFromFile (std::string aff_file_name) |
int | main (int argc, char **argv) |
pcl16::PointXYZ | objectPointInWorldFrame (pcl16::PointXYZ obj_pt, PushTrackerState &cur_state) |
int | objLocToIdx (double val, double min_val, double max_val) |
pcl16::PointXYZ | pointClosestToAngle (double major_angle, XYZPointCloud &hull_cloud, Eigen::Vector4f centroid) |
ShapeLocation | predictPushLocation (std::string cloud_path, pcl16::PointXYZ init_loc, double init_theta, pcl16::PointXYZ start_pt, std::string param_path) |
std::vector< double > | readScoreFile (std::string file_path) |
static double | sqrDist (pcl16::PointXYZ a, pcl16::PointXYZ b) |
double | sqrDistXY (pcl16::PointXYZ a, pcl16::PointXYZ b) |
pcl16::PointXYZ | worldPointInObjectFrame (pcl16::PointXYZ world_pt, PushTrackerState &cur_state) |
void | writeNewExampleFile (std::string out_file_name, std::vector< TrialStuff > trials, ShapeDescriptors descriptors, std::vector< double > &push_scores) |
void | writeNewFile (std::string out_file_name, std::vector< TrialStuff > trials, ShapeDescriptors descriptors) |
Variables | |
PushTrackerState | cur_state_ |
XYZPointCloud | hull_cloud_ |
double | point_cloud_hist_res_ = 0.01 |
double | start_loc_arc_length_percent_ |
ShapeLocations | start_loc_history_ |
int | start_loc_push_sample_count_ |
#define XY_RES 0.001 |
Definition at line 26 of file extract_shape_features.cpp.
typedef tabletop_pushing::VisFeedbackPushTrackingFeedback PushTrackerState |
Definition at line 24 of file extract_shape_features.cpp.
ShapeLocation chooseFixedGoalPushStartLoc | ( | ProtoObject & | cur_obj, |
PushTrackerState & | cur_state, | ||
bool | new_object, | ||
int | num_start_loc_pushes_per_sample, | ||
int | num_start_loc_sample_locs | ||
) |
Definition at line 96 of file extract_shape_features.cpp.
ShapeLocation chooseFixedGoalPushStartLoc | ( | ProtoObject & | cur_obj, |
PushTrackerState & | cur_state, | ||
pcl16::PointXYZ | start_pt | ||
) |
Definition at line 212 of file extract_shape_features.cpp.
ShapeLocation chooseLearnedPushStartLoc | ( | ProtoObject & | cur_obj, |
PushTrackerState & | cur_state, | ||
std::string | param_path, | ||
float & | chosen_score | ||
) |
Definition at line 244 of file extract_shape_features.cpp.
static double dist | ( | pcl16::PointXYZ | a, |
pcl16::PointXYZ | b | ||
) | [inline, static] |
Definition at line 80 of file extract_shape_features.cpp.
void drawScores | ( | std::vector< double > & | push_scores, |
std::string | out_file_path | ||
) |
Definition at line 556 of file extract_shape_features.cpp.
void getMajorMinorBoundaryDists | ( | std::string | cloud_path, |
pcl16::PointXYZ | init_loc, | ||
pcl16::PointXYZ | start_pt, | ||
double & | major_dist, | ||
double & | minor_dist | ||
) |
Definition at line 617 of file extract_shape_features.cpp.
ShapeDescriptor getTrialDescriptor | ( | std::string | cloud_path, |
pcl16::PointXYZ | init_loc, | ||
double | init_theta, | ||
bool | new_object | ||
) |
Definition at line 311 of file extract_shape_features.cpp.
ShapeDescriptor getTrialDescriptor | ( | std::string | cloud_path, |
pcl16::PointXYZ | init_loc, | ||
double | init_theta, | ||
pcl16::PointXYZ | start_pt | ||
) |
Definition at line 338 of file extract_shape_features.cpp.
std::vector<TrialStuff> getTrialsFromFile | ( | std::string | aff_file_name | ) |
Definition at line 409 of file extract_shape_features.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 667 of file extract_shape_features.cpp.
pcl16::PointXYZ objectPointInWorldFrame | ( | pcl16::PointXYZ | obj_pt, |
PushTrackerState & | cur_state | ||
) |
Definition at line 63 of file extract_shape_features.cpp.
int objLocToIdx | ( | double | val, |
double | min_val, | ||
double | max_val | ||
) | [inline] |
Definition at line 34 of file extract_shape_features.cpp.
pcl16::PointXYZ pointClosestToAngle | ( | double | major_angle, |
XYZPointCloud & | hull_cloud, | ||
Eigen::Vector4f | centroid | ||
) |
Definition at line 600 of file extract_shape_features.cpp.
ShapeLocation predictPushLocation | ( | std::string | cloud_path, |
pcl16::PointXYZ | init_loc, | ||
double | init_theta, | ||
pcl16::PointXYZ | start_pt, | ||
std::string | param_path | ||
) |
Definition at line 365 of file extract_shape_features.cpp.
std::vector<double> readScoreFile | ( | std::string | file_path | ) |
Definition at line 535 of file extract_shape_features.cpp.
static double sqrDist | ( | pcl16::PointXYZ | a, |
pcl16::PointXYZ | b | ||
) | [inline, static] |
Definition at line 88 of file extract_shape_features.cpp.
double sqrDistXY | ( | pcl16::PointXYZ | a, |
pcl16::PointXYZ | b | ||
) | [inline] |
Definition at line 39 of file extract_shape_features.cpp.
pcl16::PointXYZ worldPointInObjectFrame | ( | pcl16::PointXYZ | world_pt, |
PushTrackerState & | cur_state | ||
) |
Definition at line 46 of file extract_shape_features.cpp.
void writeNewExampleFile | ( | std::string | out_file_name, |
std::vector< TrialStuff > | trials, | ||
ShapeDescriptors | descriptors, | ||
std::vector< double > & | push_scores | ||
) |
Definition at line 515 of file extract_shape_features.cpp.
void writeNewFile | ( | std::string | out_file_name, |
std::vector< TrialStuff > | trials, | ||
ShapeDescriptors | descriptors | ||
) |
Definition at line 501 of file extract_shape_features.cpp.
Definition at line 32 of file extract_shape_features.cpp.
Definition at line 31 of file extract_shape_features.cpp.
double point_cloud_hist_res_ = 0.01 |
Definition at line 33 of file extract_shape_features.cpp.
Definition at line 29 of file extract_shape_features.cpp.
Definition at line 28 of file extract_shape_features.cpp.
Definition at line 30 of file extract_shape_features.cpp.