sliding_window_object_detector_trainer.h
Go to the documentation of this file.
00001 #ifndef _SLIDING_WINDOW_OBJECT_DETECTOR_TRAINER_H_
00002 #define _SLIDING_WINDOW_OBJECT_DETECTOR_TRAINER_H_
00003 
00004 #include <jsk_perception/histogram_of_oriented_gradients.h>
00005 
00006 #include <ros/ros.h>
00007 #include <ros/console.h>
00008 #include <rosbag/bag.h>
00009 #include <rosbag/view.h>
00010 
00011 #include <boost/foreach.hpp>
00012 #include <opencv2/opencv.hpp>
00013 
00014 #include <sensor_msgs/Image.h>
00015 #include <sensor_msgs/CameraInfo.h>
00016 #include <sensor_msgs/image_encodings.h>
00017 #include <image_transport/image_transport.h>
00018 #include <cv_bridge/cv_bridge.h>
00019 
00020 #include <vector>
00021 #include <string>
00022 #include <fstream>
00023 
00024 namespace jsk_perception
00025 {
00026    class SlidingWindowObjectDetectorTrainer: public HOGFeatureDescriptor
00027                                              // public LocalBinaryPatterns
00028    {
00029     private:
00030       ros::NodeHandle nh_;
00031       
00032       int swindow_x_;
00033       int swindow_y_;
00034       int hist_hbin_;
00035       int hist_sbin_;
00036       
00037       std::string dataset_path_;
00038 
00039       std::string object_dataset_filename_;
00040       std::string nonobject_dataset_filename_;
00041       std::string trained_classifier_name_;
00042 
00043       boost::shared_ptr<rosbag::Bag> rosbag_;
00044 #if CV_MAJOR_VERSION >= 3 // http://answers.opencv.org/question/46770/cvknearest-missing-in-300-cvmlknearest-abstract/
00045       cv::Ptr<cv::ml::SVM> supportVectorMachine_;
00046 #else
00047       boost::shared_ptr<cv::SVM> supportVectorMachine_;
00048 #endif
00049       void writeTrainingManifestToDirectory(cv::FileStorage &);
00050       virtual void concatenateCVMat(
00051          const cv::Mat &, const cv::Mat &, cv::Mat &, bool = true);
00052 
00053     public:
00054       SlidingWindowObjectDetectorTrainer();
00055       // :DiagnosticNodelet("SlidingWindowObjectDetectorTrainer");
00056       
00057       virtual void trainObjectClassifier(
00058          std::string, std::string);
00059       virtual void readDataset(
00060          std::string, std::string, cv::Mat &,
00061          cv::Mat &, bool = false, const int = 0);
00062       virtual void extractFeatures(
00063          cv::Mat &, cv::Mat &);
00064       virtual void trainBinaryClassSVM(
00065          const cv::Mat &, const cv::Mat &);
00066 
00067       // temp placed here
00068       virtual void computeHSHistogram(
00069          cv::Mat &, cv::Mat &, const int = 64, const int = 32, bool = true);
00070   
00071    };
00072 }
00073 
00074 #endif  // _SLIDING_WINDOW_OBJECT_DETECTOR_TRAINER_H_


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:15