learning.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, Andreas ten Pas
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *
00018  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  *  POSSIBILITY OF SUCH DAMAGE.
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 /* LEARNING_H_ */


agile_grasp
Author(s): Andreas ten Pas
autogenerated on Sat Jun 8 2019 20:08:27