Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef LEARNING_H_
00033 #define LEARNING_H_
00034
00035 #include <Eigen/Dense>
00036 #include <iostream>
00037 #include <opencv2/core/core.hpp>
00038 #include <opencv2/highgui/highgui.hpp>
00039 #include <opencv2/ml/ml.hpp>
00040 #include <opencv2/objdetect/objdetect.hpp>
00041 #include <set>
00042 #include <sys/stat.h>
00043 #include <vector>
00044
00045 #include <agile_grasp/rotating_hand.h>
00046
00056 class Learning
00057 {
00058 public:
00059
00063 Learning() :
00064 num_horizontal_cells_(100), num_vertical_cells_(80), num_threads_(1)
00065 {
00066 }
00067
00071 Learning(int num_threads) :
00072 num_horizontal_cells_(100), num_vertical_cells_(80), num_threads_(num_threads)
00073 {
00074 }
00075
00087 void trainBalanced(const std::vector<GraspHypothesis>& hands_list, const std::vector<int>& sizes,
00088 const std::string& file_name, const Eigen::Matrix3Xd& cam_pos, int max_positive = 1000000000,
00089 bool is_plotting = false);
00090
00101 void train(const std::vector<GraspHypothesis>& hands_list, const std::vector<int> & sizes,
00102 const std::string& file_name, const Eigen::Matrix3Xd& cam_pos, int max_positive = 1000000000,
00103 bool is_plotting = false);
00104
00112 void train(const std::vector<GraspHypothesis>& hands_list, const std::string& file_name,
00113 const Eigen::Matrix3Xd& cam_pos, bool is_plotting = false);
00114
00122 std::vector<GraspHypothesis> classify(const std::vector<GraspHypothesis>& hands_list,
00123 const std::string& svm_filename, const Eigen::Matrix3Xd& cam_pos, bool is_plotting = false);
00124
00125 private:
00126
00130 struct Instance
00131 {
00132 Eigen::Matrix3Xd pts;
00133 Eigen::Vector3d binormal;
00134 Eigen::Vector3d source_to_center;
00135 bool label;
00136 };
00137
00141 struct UniqueVectorComparator
00142 {
00149 bool operator ()(const Eigen::Vector2i& a, const Eigen::Vector2i& b)
00150 {
00151 for (int i = 0; i < a.size(); i++)
00152 {
00153 if (a(i) != b(i))
00154 {
00155 return a(i) < b(i);
00156 }
00157 }
00158
00159 return false;
00160 }
00161 };
00162
00170 Instance createInstance(const GraspHypothesis& h,
00171 const Eigen::Matrix3Xd& cam_pos, int cam = -1);
00172
00180 void convertData(const std::vector<Instance>& instances,
00181 const std::string& file_name, bool is_plotting = false,
00182 bool uses_linear_kernel = false);
00183
00189 cv::Mat convertToImage(const Instance& ins);
00190
00196 Eigen::VectorXi floorVector(const Eigen::VectorXd& a);
00197
00198 int num_horizontal_cells_;
00199 int num_vertical_cells_;
00200 int num_threads_;
00201 };
00202
00203 #endif