saliencyDetectionRudinac.cpp
Go to the documentation of this file.
00001 //===================================================================================
00002 // Name        : saliencyDetectionRudinac.cpp
00003 // Author      : Joris van de Weem, joris.vdweem@gmail.com
00004 // Version     : 1.1
00005 // Copyright   : Copyright (c) 2011 LGPL
00006 // Description : C++ implementation of "Maja Rudinac, Pieter P. Jonker. 
00007 //                              "Saliency Detection and Object Localization in Indoor Environments". 
00008 //                              ICPR'2010. pp.404~407                                                                                     
00009 //===================================================================================
00010 // v1.1: Ported to Robot Operating System (ROS)
00011 
00012 #include <saliency_detection/saliencyDetectionRudinac.h>
00013 
00014 void saliencyMapRudinac::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
00015 {
00016         cv_bridge::CvImagePtr cv_ptr;
00017         sensor_msgs::Image salmap_;
00018         geometry_msgs::Point salientpoint_;
00019 
00020         Mat image_, saliencymap_;
00021         Point pt_salient;
00022         double maxVal;
00023 
00024         try
00025         {
00026                 cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
00027         }
00028         catch (cv_bridge::Exception& e)
00029         {
00030                 ROS_ERROR("cv_bridge exception: %s", e.what());
00031         }
00032         cv_ptr->image.copyTo(image_);
00033 
00034 
00035         saliencymap_.create(image_.size(),CV_8UC1);
00036         saliencyMapRudinac::calculateSaliencyMap(&image_, &saliencymap_);
00037 
00038         //-- Return most salient point --//
00039         cv::minMaxLoc(saliencymap_,NULL,&maxVal,NULL,&pt_salient);
00040         salientpoint_.x = pt_salient.x;
00041         salientpoint_.y = pt_salient.y;
00042 
00043 
00044         //      CONVERT FROM CV::MAT TO ROSIMAGE FOR PUBLISHING
00045         saliencymap_.convertTo(saliencymap_, CV_8UC1,255);
00046         fillImage(salmap_, "mono8",saliencymap_.rows, saliencymap_.cols, saliencymap_.step, const_cast<uint8_t*>(saliencymap_.data));
00047 
00048         saliencymap_pub_.publish(salmap_);
00049         point_pub_.publish(salientpoint_);
00050 
00051         return;
00052 }
00053 
00054 
00055 void saliencyMapRudinac::calculateSaliencyMap(const Mat* src, Mat* dst)
00056 {
00057         Size imageSize(128,128);
00058         Mat srcDown(imageSize,CV_64F);
00059         Mat magnitudeI(imageSize,CV_64F);
00060         Mat magnitudeRG(imageSize,CV_64F);
00061         Mat magnitudeBY(imageSize,CV_64F);
00062         Mat magnitude(imageSize,CV_64F);
00063         
00064         resize(*src, srcDown, imageSize, 0, 0, INTER_LINEAR);
00065         
00066         createChannels(&srcDown);
00067         createSaliencyMap(I,&magnitudeI);
00068         createSaliencyMap(RG,&magnitudeRG);
00069         createSaliencyMap(BY,&magnitudeBY);
00070         
00071         magnitude= (magnitudeI + magnitudeRG + magnitudeBY);
00072         GaussianBlur(magnitude, magnitude, Size(5,5), 0, 0, BORDER_DEFAULT);
00073 
00074         //-- Scale to domain [0,1] --//
00075         double minVal,maxVal;
00076         minMaxLoc(magnitude, &minVal, &maxVal);
00077         magnitude = magnitude / maxVal;
00078 
00079         resize(magnitude, *dst, dst->size(), 0, 0, INTER_LINEAR);
00080 }
00081 
00082 
00083 void saliencyMapRudinac::createChannels(const Mat* src)
00084 {
00085         
00086         b.create(src->size(),CV_32F);
00087         g.create(src->size(),CV_32F);
00088         r.create(src->size(),CV_32F);
00089         I.create(src->size(),CV_32F);
00090         vector<Mat> planes;     
00091         split(*src, planes);
00092         Mat rgmax(src->size(),CV_32F);
00093         Mat rgbmax(src->size(),CV_32F);
00094         Mat mask(src->size(),CV_32F);
00095 
00096         for(int j=0; j<r.rows;j++)
00097         for(int i=0; i<r.cols; i++)
00098         {
00099                         b.at<float>(j,i) = planes[0].at<uchar>(j,i);
00100                         g.at<float>(j,i) = planes[1].at<uchar>(j,i);
00101                         r.at<float>(j,i) = planes[2].at<uchar>(j,i);
00102         }
00103         
00104         I = r+g+b;
00105         //threshold(I, I, 255, 255, THRESH_TRUNC); // Saturation as in Matlab?
00106         I = I/3;
00107                 
00108         rgmax = max(r,g);
00109         rgbmax = max(rgmax,b);
00110         
00111         //-- Prevent that the lowest value is zero, because you cannot divide by zero.
00112         for(int j=0; j<r.rows;j++)
00113         for(int i=0; i<r.cols; i++)
00114         {
00115                         if (rgbmax.at<float>(j,i) == 0) rgbmax.at<float>(j,i) = 1;
00116         }
00117 
00118 
00119         RG = abs(r-g)/rgbmax;
00120         BY = abs(b - min(r,g))/rgbmax;
00121 
00122         rgbmax = rgbmax/255;
00123         //-- If max(r,g,b)<0.1 all components should be zero to stop large fluctuations of the color opponency values at low luminance --//
00124         threshold(rgbmax,mask,.1,1,THRESH_BINARY);
00125         RG = RG.mul(mask);
00126         BY = BY.mul(mask);
00127         I = I.mul(mask);
00128 }
00129 
00130 
00131 
00132 void saliencyMapRudinac::createSaliencyMap(const Mat src, Mat* dst)
00133 {
00134         vector<Mat> mv; 
00135         
00136         Mat realImage(src.size(),CV_64F);
00137         Mat imaginaryImage(src.size(),CV_64F); imaginaryImage.setTo(0);
00138         Mat combinedImage(src.size(),CV_64FC2);
00139         Mat image_DFT;  
00140         Mat logAmplitude;
00141         Mat angle(src.size(),CV_64F);
00142         Mat Magnitude(src.size(),CV_64F);
00143         Mat logAmplitude_blur;
00144         
00145         for(int j=0; j<src.rows;j++){
00146         for(int i=0; i<src.cols; i++){
00147                 realImage.at<double>(j,i) = src.at<float>(j,i);
00148         }
00149         }
00150 
00151                         
00152         mv.push_back(realImage);
00153         mv.push_back(imaginaryImage);   
00154         merge(mv,combinedImage);        
00155         
00156         dft( combinedImage, image_DFT);
00157         split(image_DFT, mv);   
00158 
00159         //-- Get magnitude and phase of frequency spectrum --//
00160         cartToPolar(mv.at(0), mv.at(1), Magnitude, angle, false);
00161         log(Magnitude,logAmplitude);    
00162                 
00163         //-- Blur log amplitude with averaging filter --//
00164         blur(logAmplitude, logAmplitude_blur, Size(3,3), Point(-1,-1), BORDER_DEFAULT);
00165         exp(logAmplitude - logAmplitude_blur,Magnitude);
00166         
00167         polarToCart(Magnitude, angle,mv.at(0), mv.at(1),false);
00168         merge(mv,image_DFT);
00169         dft(image_DFT,combinedImage,CV_DXT_INVERSE);
00170 
00171         split(combinedImage,mv);
00172         cartToPolar(mv.at(0), mv.at(1), Magnitude, angle, false);
00173         Magnitude = Magnitude.mul(Magnitude);
00174 
00175         Mat tempFloat(src.size(),CV_32F);
00176         for(int j=0; j<Magnitude.rows;j++)
00177         for(int i=0; i<Magnitude.cols; i++)
00178                 tempFloat.at<float>(j,i) = Magnitude.at<double>(j,i);
00179         
00180         *dst = tempFloat;
00181 }
00182 
00183 
00184 int main(int argc, char **argv)
00185 {
00186         ros::init(argc, argv, "saliencymap");
00187 
00188         saliencyMapRudinac salmapRudinac;
00189 
00190         ros::spin();
00191 
00192         return 0;
00193 }


saliency_detection
Author(s): Joris van de Weem
autogenerated on Sun Jan 5 2014 11:07:22