provides a framework to train and test an ANN for image recognition More...
#include <ImageRecognizer.h>
Public Member Functions | |
void | calculateAndSaveFeatures () |
ImageRecognizer () | |
Constructor. | |
void | loadImageRecognizer () |
Loads a saved set of BOWs and ANN for image recognition. | |
void | recognizeObject (const rail_manipulation_msgs::SegmentedObject object, std::vector< std::pair< float, std::string > > &recognitionResults) |
Recognize a given segmented object. | |
void | testImageRecognizer () |
Tests image recognition with the images in the test directory. | |
void | trainImageRecognizer () |
Trains the BOWs and the ANN using the images in the images directory. | |
Private Member Functions | |
void | colorAndHSVDescriptors (cv::Mat colorInput, cv::Mat &result_hist) |
Calculates the RGB and HSV values. Places results in Mat. | |
void | detectExtractComputeFeatures (cv::Mat colorInput, cv::Mat &response_hist) |
Detects, extracts and computes the feature vector to be used in the ANN. | |
void | detectExtractFeatures (cv::Mat &input, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptor, cv::Ptr< cv::DescriptorExtractor > extractor, cv::Ptr< cv::FeatureDetector > detector) |
Detects and extracts keypoints and a descriptor. | |
void | getFeatures (cv::Mat &featuresUnclustered, cv::Ptr< cv::DescriptorExtractor > extractor, cv::Ptr< cv::FeatureDetector > detector, std::vector< std::string > &FileNames) |
Gets the image files and classes from the images directory. | |
void | getFilesAndClasses (std::vector< std::string > &classes_names, std::vector< std::string > &FileNames) |
Gets the image files and classes from the images directory. | |
void | normalizeFeatureVector (cv::Mat &featureVector, int numPixels) |
void | objectListCallBack (const rail_manipulation_msgs::SegmentedObjectList msg) |
Callback for the new segmented objects list. | |
void | testImage (cv::Mat colorInput, std::vector< std::pair< float, std::string > > &testResults) |
Attempts to recognize a given image. | |
void | trainNN (cv::Mat &inputData, std::map< std::string, cv::Mat > &classesTrainingData, int numClasses) |
Trains the ANN. | |
void | trainVocabulary (std::string featureName, cv::Mat featuresUnclustered, cv::Mat &vocabulary) |
Train the vocabulary of a BOW for a given feature set. | |
Private Attributes | |
cv::Ptr< cv::DescriptorMatcher > | bfMatcher |
cv::Ptr< CvANN_MLP > | classifier |
std::vector< std::string > | classLegend |
int | dictionarySize |
cv::Ptr< cv::DescriptorMatcher > | flannMatcher |
int | histSize |
std::string | imagesDirPath |
std::string | newImagesDirPath |
ros::NodeHandle | node |
int | numResponses |
ros::NodeHandle | pnh |
std::string | savedDataDirPath |
bool | saveNewImages |
ros::Subscriber | sub |
std::string | testImagesDirPath |
provides a framework to train and test an ANN for image recognition
ImageRecognizer creates a ROS node that provides methods for loading, training and testing a neural network using OpenCV's built in CvANN_MLP class and multiple features that are also implemented in OpenCV
Definition at line 47 of file ImageRecognizer.h.
Constructor.
Definition at line 25 of file ImageRecognizer.cpp.
Definition at line 84 of file ImageRecognizer.cpp.
void ImageRecognizer::colorAndHSVDescriptors | ( | cv::Mat | colorInput, |
cv::Mat & | result_hist | ||
) | [private] |
Calculates the RGB and HSV values. Places results in Mat.
Calculates the RGB, hue, saturation values for the provided color image and builds a feature vector in a Mat object which is part of the input for an ANN.
colorInput | A color image for which to calculate RGB and HSV features |
result_hist | A pointer to a Mat object to store the calculate features |
Compute the histograms:
Normalize the results
Definition at line 500 of file ImageRecognizer.cpp.
void ImageRecognizer::detectExtractComputeFeatures | ( | cv::Mat | colorInput, |
cv::Mat & | response_hist | ||
) | [private] |
Detects, extracts and computes the feature vector to be used in the ANN.
Performs recognition on each of the images in the list and will save them to the specified directory when the save option is set.
colorInput | The RGB_8 color image that we want the feature vector for |
response_hist | A pointer to a Mat object to store the feature vector of the image. |
Definition at line 324 of file ImageRecognizer.cpp.
void ImageRecognizer::detectExtractFeatures | ( | cv::Mat & | input, |
std::vector< cv::KeyPoint > & | keypoints, | ||
cv::Mat & | descriptor, | ||
cv::Ptr< cv::DescriptorExtractor > | extractor, | ||
cv::Ptr< cv::FeatureDetector > | detector | ||
) | [private] |
Detects and extracts keypoints and a descriptor.
input | The gray image to use for destection |
keypoints | A pointer to a keypoint vector to store the found keypoints. |
extractor | A pointer to the extractor to use. |
detector | A pointer to the detector to use. |
Definition at line 308 of file ImageRecognizer.cpp.
void ImageRecognizer::getFeatures | ( | cv::Mat & | featuresUnclustered, |
cv::Ptr< cv::DescriptorExtractor > | extractor, | ||
cv::Ptr< cv::FeatureDetector > | detector, | ||
std::vector< std::string > & | FileNames | ||
) | [private] |
Gets the image files and classes from the images directory.
Loops throught the images directory finding all the different class folders and then all the files for each class recoding both.
featuresUnclustered | A pointer to a Mat object to store the the features to train the BOW with in each row |
extractor | A pointer to the DescriptorExtractor to be used to calculate the descripto of each file |
detector | A pointer to the FeatureDetector to be used to detect any features in each file. |
FileNames | A pointer to a location containing the File paths for all the class images. |
Definition at line 348 of file ImageRecognizer.cpp.
void ImageRecognizer::getFilesAndClasses | ( | std::vector< std::string > & | classes_names, |
std::vector< std::string > & | FileNames | ||
) | [private] |
Gets the image files and classes from the images directory.
Loops throught the images directory finding all the different class folders and then all the files for each class recoding both.
classes_names | A pointer to a location to store all the class names for each file. |
FileNames | A pointer to a location to store the File paths for all the class images. |
Definition at line 374 of file ImageRecognizer.cpp.
void ImageRecognizer::loadImageRecognizer | ( | ) |
Loads a saved set of BOWs and ANN for image recognition.
Definition at line 65 of file ImageRecognizer.cpp.
void ImageRecognizer::normalizeFeatureVector | ( | cv::Mat & | featureVector, |
int | numPixels | ||
) | [private] |
Definition at line 551 of file ImageRecognizer.cpp.
void ImageRecognizer::objectListCallBack | ( | const rail_manipulation_msgs::SegmentedObjectList | msg | ) | [private] |
Callback for the new segmented objects list.
Performs recognition on each of the images in the list and will save them to the specified directory when the save option is set.
msg | The published segmented objects list being received. |
Definition at line 569 of file ImageRecognizer.cpp.
void ImageRecognizer::recognizeObject | ( | const rail_manipulation_msgs::SegmentedObject | object, |
std::vector< std::pair< float, std::string > > & | recognitionResults | ||
) |
Recognize a given segmented object.
object | an unrecognized segmented object |
recognitionResults | vector in which to store the result candidates in descending order of confidence |
Definition at line 603 of file ImageRecognizer.cpp.
void ImageRecognizer::testImage | ( | cv::Mat | colorInput, |
std::vector< std::pair< float, std::string > > & | testResults | ||
) | [private] |
Attempts to recognize a given image.
Tests the given image by calculating its feature vector and then using the ANN to predict.
colorInput | The color image that is to be tested |
testResults | A pointer to a vector in which to store the prediction results |
Definition at line 629 of file ImageRecognizer.cpp.
void ImageRecognizer::testImageRecognizer | ( | ) |
Tests image recognition with the images in the test directory.
Definition at line 189 of file ImageRecognizer.cpp.
Trains the BOWs and the ANN using the images in the images directory.
Definition at line 143 of file ImageRecognizer.cpp.
void ImageRecognizer::trainNN | ( | cv::Mat & | inputData, |
std::map< std::string, cv::Mat > & | classesTrainingData, | ||
int | numClasses | ||
) | [private] |
Trains the ANN.
Trains the ANN using the given training data and number of classes
inputData | An example training sample (probably not needed) |
classesTrainingData | A map containing the features vector for all images of each class. |
numClasses | An int specifying how many classes there are. |
Definition at line 449 of file ImageRecognizer.cpp.
void ImageRecognizer::trainVocabulary | ( | std::string | featureName, |
cv::Mat | featuresUnclustered, | ||
cv::Mat & | vocabulary | ||
) | [private] |
Train the vocabulary of a BOW for a given feature set.
Trains a BOW based on the given matrix of features and then saves that trained bag file.
featureName | A string with the name of the feature bag being trained |
featuresUnclustered | A Mat object containing the the features to train the BOW with in each row |
vocabulary | A Mat object containing the vocabulary fot the trained BOW |
Definition at line 420 of file ImageRecognizer.cpp.
cv::Ptr<cv::DescriptorMatcher> ImageRecognizer::bfMatcher [private] |
Definition at line 196 of file ImageRecognizer.h.
cv::Ptr<CvANN_MLP> ImageRecognizer::classifier [private] |
CvANN_MLP ptr for the ANN classifier
Definition at line 197 of file ImageRecognizer.h.
std::vector<std::string> ImageRecognizer::classLegend [private] |
vector of object class names that are in the same order as the ANN
Definition at line 199 of file ImageRecognizer.h.
int ImageRecognizer::dictionarySize [private] |
the numbers of words in each BOW
Definition at line 201 of file ImageRecognizer.h.
cv::Ptr<cv::DescriptorMatcher> ImageRecognizer::flannMatcher [private] |
DescriptorMatcher ptrs for brute force and flann matchers
Definition at line 196 of file ImageRecognizer.h.
int ImageRecognizer::histSize [private] |
number of groups in RGB/HSV histograms
Definition at line 202 of file ImageRecognizer.h.
std::string ImageRecognizer::imagesDirPath [private] |
directory for training images
Definition at line 210 of file ImageRecognizer.h.
std::string ImageRecognizer::newImagesDirPath [private] |
path to save new images at
Definition at line 207 of file ImageRecognizer.h.
ros::NodeHandle ImageRecognizer::node [private] |
Definition at line 192 of file ImageRecognizer.h.
int ImageRecognizer::numResponses [private] |
number of responses to return
Definition at line 204 of file ImageRecognizer.h.
ros::NodeHandle ImageRecognizer::pnh [private] |
a handle for this ROS node
Definition at line 192 of file ImageRecognizer.h.
std::string ImageRecognizer::savedDataDirPath [private] |
directory for saving data
Definition at line 209 of file ImageRecognizer.h.
bool ImageRecognizer::saveNewImages [private] |
if new segmented objects should be saved for training
Definition at line 206 of file ImageRecognizer.h.
ros::Subscriber ImageRecognizer::sub [private] |
subscriber handle for the segmented objects list topic
Definition at line 194 of file ImageRecognizer.h.
std::string ImageRecognizer::testImagesDirPath [private] |
directory for testing images
Definition at line 211 of file ImageRecognizer.h.