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


pal_vision_segmentation
Author(s): Created by Bence Magyar. Maintained by Jordi Pages
autogenerated on Thu Jan 2 2014 11:36:22