histogram_segmentation_unit_test.cpp
Go to the documentation of this file.
00001 #include <gtest/gtest.h>
00002 #include <ros/ros.h>
00003 #include <ros/package.h>
00004 
00005 #include <opencv2/core/core.hpp>
00006 #include <opencv2/highgui/highgui.hpp>
00007 
00008 
00009 #include <pal_vision_segmentation/histogram.h>
00010 
00011 bool isInteractive;
00012 
00013 void backProjectionTest(const std::string& imageFileName,
00014                         const std::string& templateFileName,
00015                         int dilateIterations, int dilateSize,
00016                         int erodeIterations, int erodeSize,
00017                         cv::Mat& mask)
00018 {
00019   cv::Mat templateImg;
00020 
00021   std::cout << "Trying to read image from file: " << imageFileName << std::endl;
00022   std::cout << "Trying to read template from file: " << templateFileName << std::endl;
00023 
00024   templateImg = cv::imread(templateFileName, 1);
00025 
00026   cv::Mat image;
00027   image = cv::imread(imageFileName, 1);
00028 
00029   cv::MatND hist;
00030   pal_vision_util::calcHSVHist(templateImg, hist);
00031   cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX, -1, cv::Mat()); //set histogram bin values in [0, 255]
00032   cv::threshold(hist, hist, 128, 255, cv::THRESH_BINARY);            //all those bin values > threshold are set to 255, otherwise 0
00033 
00034   if ( isInteractive )
00035     pal_vision_util::showHist(hist, false);
00036 
00037   int threshold = 254;
00038   pal_vision_util::backProject(image,
00039                                hist,
00040                                threshold,
00041                                mask,
00042                                dilateIterations, dilateSize, //dilate iterations and size
00043                                erodeIterations, erodeSize);
00044 
00045   if ( isInteractive )
00046   {
00047     cv::Mat imgMasked;
00048     image.copyTo(imgMasked, mask);
00049 
00050     cv::namedWindow("image");
00051     cv::imshow("image", image);
00052 
00053     cv::namedWindow("back-projection");
00054     cv::imshow("back-projection", mask);
00055 
00056     cv::namedWindow("image masked");
00057     cv::imshow("image masked", imgMasked);
00058 
00059     cv::waitKey(5000);
00060   }
00061 
00062   bool ok = true;
00063   EXPECT_TRUE( ok );
00064 }
00065 
00066 
00067 TEST(histogram, test_back_projection)
00068 {
00069   cv::Mat mask;
00070 
00072   // Synthetic example
00074   backProjectionTest(ros::package::getPath("pal_vision_segmentation") + "/test/etc/histogram_segmentation_sample.jpg",
00075                      ros::package::getPath("pal_vision_segmentation") + "/test/etc/histogram_segmentation_blue_template.jpg",
00076                      0, 3, 0, 3,
00077                      mask);
00078 
00079   //check some pixels of the resulting mask
00080   EXPECT_TRUE( mask.at<unsigned char>(45, 54)   == 0 );
00081   EXPECT_TRUE( mask.at<unsigned char>(52, 208)  == 0 );
00082   EXPECT_TRUE( mask.at<unsigned char>(165, 90)  == 0 );
00083   EXPECT_TRUE( mask.at<unsigned char>(158, 230) == 255 );
00084 
00086   // Real example
00088   backProjectionTest(ros::package::getPath("pal_vision_segmentation") + "/test/etc/pringles_frame.jpg",
00089                      ros::package::getPath("pal_vision_segmentation") + "/test/etc/pringles_template2.png",
00090                      9, 5, 0, 3,
00091                      mask);
00092 
00093   //check some pixels of the resulting mask
00094   EXPECT_TRUE( mask.at<unsigned char>(55, 55)   == 0 );
00095   EXPECT_TRUE( mask.at<unsigned char>(221, 246) == 255 );
00096   EXPECT_TRUE( mask.at<unsigned char>(460, 630) == 255 );
00097   EXPECT_TRUE( mask.at<unsigned char>(240, 450) == 0 );
00098   EXPECT_TRUE( mask.at<unsigned char>(365, 8)   == 255 );
00099   EXPECT_TRUE( mask.at<unsigned char>(208, 142) == 255 );
00100   EXPECT_TRUE( mask.at<unsigned char>(220, 140) == 255 );
00101   EXPECT_TRUE( mask.at<unsigned char>(20, 220) == 255 );
00102 
00103 }
00104 
00105 // Run all the tests that were declared with TEST()
00106 int main(int argc, char **argv)
00107 {
00108     testing::InitGoogleTest(&argc, argv);
00109     
00110     isInteractive = argc > 1 && std::string(argv[1]) == "interactive";
00111     
00112     return RUN_ALL_TESTS();
00113 }


pal_vision_segmentation
Author(s): Bence Magyar
autogenerated on Fri Aug 28 2015 11:57:00