ImageRecognizer.h
Go to the documentation of this file.
00001 //
00002 // Created by bhetherman on 3/30/15.
00003 //
00004 
00005 #ifndef PROJECT_IMAGE_RECOGNIZER_H
00006 #define PROJECT_IMAGE_RECOGNIZER_H
00007 
00008 //ROS
00009 #include <ros/ros.h>
00010 #include <ros/package.h>
00011 #include <time.h>
00012 #include <stdio.h>
00013 #include <sensor_msgs/JointState.h>
00014 #include <iostream>
00015 #include <fstream>
00016 #include <string>
00017 #include <dirent.h>
00018 #include <std_srvs/Empty.h>
00019 #include <sys/stat.h>
00020 #include <map>
00021 
00022 #include <rail_manipulation_msgs/SegmentedObjectList.h>
00023 #include <sensor_msgs/Image.h>
00024 
00025 //OpenCV
00026 #include <opencv2/opencv.hpp>
00027 #include <cv_bridge/cv_bridge.h>
00028 #include <sensor_msgs/image_encodings.h>
00029 #include <opencv2/core/core.hpp>
00030 #include <opencv2/features2d/features2d.hpp>
00031 #include <opencv2/highgui/highgui.hpp>
00032 #include <opencv2/ml/ml.hpp>
00033 
00034 //CPP
00035 #include <boost/filesystem.hpp>
00036 #include <iostream>
00037 #include <fstream>
00038 
00047 class ImageRecognizer
00048 {
00049 public:
00053   ImageRecognizer();
00054 
00058   void testImageRecognizer();
00059 
00060   void calculateAndSaveFeatures();
00061 
00065   void trainImageRecognizer();
00066 
00070   void loadImageRecognizer();
00071 
00077   void recognizeObject(const rail_manipulation_msgs::SegmentedObject object, std::vector<std::pair< float, std::string> > &recognitionResults);
00078 
00079 private:
00080 
00090   void objectListCallBack(const rail_manipulation_msgs::SegmentedObjectList msg);
00091 
00101   void detectExtractFeatures(cv::Mat &input, std::vector<cv::KeyPoint> &keypoints, cv::Mat &descriptor,
00102                              cv::Ptr<cv::DescriptorExtractor> extractor, cv::Ptr<cv::FeatureDetector> detector);
00103 
00114   void detectExtractComputeFeatures(cv::Mat colorInput, cv::Mat &response_hist);
00115 
00126   void getFilesAndClasses(std::vector<std::string> &classes_names, std::vector<std::string> &FileNames);
00127 
00140   void getFeatures(cv::Mat &featuresUnclustered, cv::Ptr<cv::DescriptorExtractor> extractor,
00141                    cv::Ptr<cv::FeatureDetector> detector, std::vector<std::string> &FileNames);
00142 
00153   void trainVocabulary(std::string featureName, cv::Mat featuresUnclustered, cv::Mat &vocabulary);
00154 
00165   void colorAndHSVDescriptors(cv::Mat colorInput, cv::Mat &result_hist);
00166 
00177   void trainNN(cv::Mat &inputData, std::map<std::string,cv::Mat> &classesTrainingData, int numClasses);
00178 
00188   void testImage(cv::Mat colorInput, std::vector<std::pair<float, std::string> > &testResults);
00189 
00190   void normalizeFeatureVector(cv::Mat &featureVector, int numPixels);
00191 
00192   ros::NodeHandle node, pnh; 
00194   ros::Subscriber sub; 
00196   cv::Ptr<cv::DescriptorMatcher> bfMatcher, flannMatcher;
00197   cv::Ptr<CvANN_MLP> classifier;
00199   std::vector<std::string> classLegend;
00201   int dictionarySize;
00202   int histSize;
00204   int numResponses;
00206   bool saveNewImages;
00207   std::string newImagesDirPath;
00209   std::string savedDataDirPath; 
00210   std::string imagesDirPath;
00211   std::string testImagesDirPath;
00213 };
00214 
00222 int main(int argc, char **argv);
00223 #endif //PROJECT_IMAGE_RECOGNIZER_H


rail_recognition
Author(s): David Kent , Russell Toris , bhetherman
autogenerated on Sun Mar 6 2016 11:39:13