source: trunk/saliency_detection/src/saliencyDetectionItti.cpp @ 23

Last change on this file since 23 was 10, checked in by wcaarls, 12 years ago

Imported saliency_detection at revision 1000

File size: 11.0 KB
RevLine 
[10]1//===================================================================================
2// Name        : saliencyDetectionItti.cpp
3// Author      : Oytun Akman, oytunakman@gmail.com
4// Editor          : Joris van de Weem, joris.vdweem@gmail.com (Conversion to ROS)
5// Version     : 1.1
6// Copyright   : Copyright (c) 2010 LGPL
7// Description : C++ implementation of "A Model of Saliency-Based Visual Attention
8//                               for Rapid Scene Analysis" by Laurent Itti, Christof Koch and Ernst
9//                               Niebur (PAMI 1998).                                                                                             
10//===================================================================================
11// v1.1: Ported to Robot Operating System (ROS) (Joris)
12
13#include <saliency_detection/saliencyDetectionItti.h>
14#include <saliency_detection/cvgabor.h>
15
16void saliencyMapItti::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
17{
18        cv_bridge::CvImagePtr cv_ptr;
19        sensor_msgs::Image salmap_;
20        geometry_msgs::Point salientpoint_;
21
22        Mat image_, saliencymap_;
23        Point pt_salient;
24        double maxVal;
25
26        try
27        {
28                cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
29        }
30        catch (cv_bridge::Exception& e)
31        {
32                ROS_ERROR("cv_bridge exception: %s", e.what());
33        }
34        cv_ptr->image.copyTo(image_);
35
36
37        saliencymap_.create(image_.size(),CV_8UC1);
38        saliencyMapItti::calculateSaliencyMap(&image_, &saliencymap_,1);
39
40        //-- Return most salient point --//
41        cv::minMaxLoc(saliencymap_,NULL,&maxVal,NULL,&pt_salient);
42        salientpoint_.x = pt_salient.x;
43        salientpoint_.y = pt_salient.y;
44
45
46        //      CONVERT FROM CV::MAT TO ROSIMAGE FOR PUBLISHING
47        saliencymap_.convertTo(saliencymap_, CV_8UC1,255);
48        fillImage(salmap_, "mono8",saliencymap_.rows, saliencymap_.cols, saliencymap_.step, const_cast<uint8_t*>(saliencymap_.data));
49
50        saliencymap_pub_.publish(salmap_);
51        point_pub_.publish(salientpoint_);
52
53        return;
54}
55
56void saliencyMapItti::calculateSaliencyMap(const Mat* src, Mat* dst, int scaleBase)
57{
58        createChannels(src);
59
60        createIntensityFeatureMaps();
61        createColorFeatureMaps();
62        createOrientationFeatureMaps(0);
63        createOrientationFeatureMaps(2);
64        createOrientationFeatureMaps(4);
65        createOrientationFeatureMaps(6);
66
67        combineFeatureMaps(scaleBase);
68
69        resize(S, *dst, src->size(), 0, 0, INTER_LINEAR);
70
71        clearBuffers();
72}
73
74void saliencyMapItti::createChannels(const Mat* src)
75{
76        b.create(src->size(),CV_32F);
77        g.create(src->size(),CV_32F);
78        r.create(src->size(),CV_32F);
79        I.create(src->size(),CV_32F);
80        vector<Mat> planes;     
81        split(*src, planes);
82
83        for(int j=0; j<r.rows;j++)
84        for(int i=0; i<r.cols; i++)
85        {
86                        b.at<float>(j,i) = planes[0].at<uchar>(j,i);
87                        g.at<float>(j,i) = planes[1].at<uchar>(j,i);
88                        r.at<float>(j,i) = planes[2].at<uchar>(j,i);
89        }
90       
91        I = r+g+b;
92        I = I/3;
93
94        normalize_rgb();
95        create_RGBY();
96        createScaleSpace(&I, &gaussianPyramid_I, 8);   
97        createScaleSpace(&R, &gaussianPyramid_R, 8);   
98        createScaleSpace(&G, &gaussianPyramid_G, 8);   
99        createScaleSpace(&B, &gaussianPyramid_B, 8);   
100        createScaleSpace(&Y, &gaussianPyramid_Y, 8);   
101}
102
103/*r,g and b channels are normalized by I in order to decouple hue from intensity
104  Because hue variations are not perceivable at very low luminance normalization is only applied at the locations
105  where I is larger than max(I)/10 (other locations yield zero r,g,b)*/
106void saliencyMapItti::normalize_rgb()
107{
108        double minVal,maxVal;   
109        minMaxLoc(I, &minVal, &maxVal);
110        Mat mask_I;
111        threshold(I, mask_I, maxVal/10, 1.0, THRESH_BINARY);
112
113        r = r/I;
114        g = g/I;
115        b = b/I;
116        r = r.mul(mask_I);
117        g = g.mul(mask_I);
118        b = b.mul(mask_I);
119}
120
121void saliencyMapItti::create_RGBY()
122{
123        Mat gb = g+b;
124        Mat rb = r+b;
125        Mat rg = r+g;
126        Mat rg_ = r-g;
127
128        R = r-gb/2;
129        G = g-rb/2;
130        B = b-rg/2;
131        Y = rg/2 - abs(rg_/2) - b;
132
133        Mat mask;
134        threshold(R, mask, 0.0, 1.0, THRESH_BINARY);
135        R = R.mul(mask);
136        threshold(G, mask, 0.0, 1.0, THRESH_BINARY);
137        G = G.mul(mask);
138        threshold(B, mask, 0.0, 1.0, THRESH_BINARY);
139        B = B.mul(mask);
140        threshold(Y, mask, 0.0, 1.0, THRESH_BINARY);
141        Y = Y.mul(mask);
142}
143
144void saliencyMapItti::createScaleSpace(const Mat* src, vector<Mat>* dst, int scale)
145{
146        buildPyramid( *src, *dst, scale);
147}
148
149void saliencyMapItti::createIntensityFeatureMaps()
150{
151        int fineScaleNumber = 3;
152        int scaleDiff = 2;
153        int c[3] = {2,3,4};
154        int delta[2] = {3,4};
155
156        for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
157        {               
158                Mat fineScaleImage = gaussianPyramid_I.at(c[scaleIndex]);
159                Size fineScaleImageSize = fineScaleImage.size();
160
161                for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
162                {
163                        int s = c[scaleIndex] + delta[scaleDiffIndex];
164                        Mat coarseScaleImage = gaussianPyramid_I.at(s);
165                        Mat coarseScaleImageUp;
166                        resize(coarseScaleImage, coarseScaleImageUp, fineScaleImageSize, 0, 0, INTER_LINEAR);
167                        Mat I_cs = abs(fineScaleImage -  coarseScaleImageUp);                   
168                        featureMaps_I.push_back(I_cs);         
169                }
170        }
171}
172
173void saliencyMapItti::createColorFeatureMaps()
174{
175        int fineScaleNumber = 3;
176        int scaleDiff = 2;
177        int c[3] = {2,3,4};
178        int delta[2] = {3,4};
179
180        for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
181        {               
182                Mat fineScaleImageR = gaussianPyramid_R.at(c[scaleIndex]);
183                Mat fineScaleImageG = gaussianPyramid_G.at(c[scaleIndex]);
184                Mat fineScaleImageB = gaussianPyramid_B.at(c[scaleIndex]);
185                Mat fineScaleImageY = gaussianPyramid_Y.at(c[scaleIndex]);
186                Size fineScaleImageSize = fineScaleImageR.size();
187
188                Mat RGc = fineScaleImageR - fineScaleImageG;
189                Mat BYc = fineScaleImageB - fineScaleImageY;
190
191                for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
192                {
193                        int s = c[scaleIndex] + delta[scaleDiffIndex];
194                        Mat coarseScaleImageR = gaussianPyramid_R.at(s);
195                        Mat coarseScaleImageG = gaussianPyramid_G.at(s);
196                        Mat coarseScaleImageB = gaussianPyramid_B.at(s);
197                        Mat coarseScaleImageY = gaussianPyramid_Y.at(s);
198
199                        Mat GRs = coarseScaleImageG - coarseScaleImageR;
200                        Mat YBs = coarseScaleImageY - coarseScaleImageB;
201                        Mat coarseScaleImageUpGRs, coarseScaleImageUpYBs;
202                        resize(GRs, coarseScaleImageUpGRs, fineScaleImageSize, 0, 0, INTER_LINEAR);
203                        resize(YBs, coarseScaleImageUpYBs, fineScaleImageSize, 0, 0, INTER_LINEAR);                     
204                        Mat RG_cs = abs( RGc - coarseScaleImageUpGRs);
205                        Mat BY_cs = abs( BYc - coarseScaleImageUpYBs);
206                       
207                        featureMaps_RG.push_back(RG_cs);
208                        featureMaps_BY.push_back(BY_cs);               
209                }
210        }
211}
212
213void saliencyMapItti::createOrientationFeatureMaps(int orientation)
214{
215        int fineScaleNumber = 3;
216        int scaleDiff = 2;
217        int c[3] = {2,3,4};
218        int delta[2] = {3,4};
219        CvGabor *gabor = new CvGabor(orientation,0);   
220        IplImage* gbr_fineScaleImage, *gbr_coarseScaleImage;
221
222        for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
223        {               
224                Mat fineScaleImage = gaussianPyramid_I.at(c[scaleIndex]);
225                Size fineScaleImageSize = fineScaleImage.size();
226
227                IplImage src_fineScaleImage = IplImage(fineScaleImage);
228                gbr_fineScaleImage = cvCreateImage(fineScaleImage.size(),IPL_DEPTH_8U, 1);                             
229                gabor->conv_img(&src_fineScaleImage,gbr_fineScaleImage,CV_GABOR_REAL);         
230                Mat src_responseImg(gbr_fineScaleImage);               
231
232                for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
233                {
234                        int s = c[scaleIndex] + delta[scaleDiffIndex];
235                        Mat coarseScaleImage = gaussianPyramid_I.at(s);
236                        IplImage src_coarseScaleImage = IplImage(coarseScaleImage);
237                        gbr_coarseScaleImage = cvCreateImage(coarseScaleImage.size(),IPL_DEPTH_8U, 1);                 
238                        gabor->conv_img(&src_coarseScaleImage,gbr_coarseScaleImage,CV_GABOR_REAL);                     
239                        Mat coarse_responseImg(gbr_coarseScaleImage);
240
241                        Mat coarseScaleImageUp;
242                        resize(coarse_responseImg, coarseScaleImageUp, fineScaleImageSize, 0, 0, INTER_LINEAR);                 
243
244                        Mat temp = abs(src_responseImg -  coarseScaleImageUp);
245                        Mat O_cs(temp.size(),CV_32F);
246
247                        for(int j=0; j<temp.rows;j++)
248                        for(int i=0; i<temp.cols; i++)
249                                O_cs.at<float>(j,i) = temp.at<uchar>(j,i);
250
251                        if(orientation == 0)                   
252                                featureMaps_0.push_back(O_cs);
253                        if(orientation == 2)                   
254                                featureMaps_45.push_back(O_cs);
255                        if(orientation == 4)                   
256                                featureMaps_90.push_back(O_cs);
257                        if(orientation == 6)                   
258                                featureMaps_135.push_back(O_cs);
259
260                        cvReleaseImage(&gbr_coarseScaleImage);         
261                }
262                cvReleaseImage(&gbr_fineScaleImage);           
263        }
264}
265
266void saliencyMapItti::combineFeatureMaps(int scale)
267{
268        Size scaleImageSize = gaussianPyramid_I.at(scale).size();
269        conspicuityMap_I.create(scaleImageSize,CV_32F); conspicuityMap_I.setTo(0);
270        conspicuityMap_C.create(scaleImageSize,CV_32F); conspicuityMap_C.setTo(0);
271        conspicuityMap_O.create(scaleImageSize,CV_32F); conspicuityMap_O.setTo(0);
272        Mat ori_0(scaleImageSize,CV_32F); ori_0.setTo(0);
273        Mat ori_45(scaleImageSize,CV_32F); ori_45.setTo(0);
274        Mat ori_90(scaleImageSize,CV_32F); ori_90.setTo(0);
275        Mat ori_135(scaleImageSize,CV_32F); ori_135.setTo(0);
276
277        Mat featureMap, featureMap_scaled, RG, BY, RG_scaled, BY_scaled;
278
279        for (int index=0; index<3*2; index++)
280        {
281                resize(featureMaps_I.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
282                mapNormalization(&featureMap_scaled);
283                conspicuityMap_I = conspicuityMap_I + featureMap_scaled;
284
285                resize(featureMaps_RG.at(index), RG_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
286                resize(featureMaps_BY.at(index), BY_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
287                mapNormalization(&RG_scaled);
288                mapNormalization(&BY_scaled);
289                conspicuityMap_C = conspicuityMap_C + (RG_scaled + BY_scaled);
290                       
291                resize(featureMaps_0.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
292                mapNormalization(&featureMap_scaled);
293                ori_0 = ori_0 + featureMap_scaled;
294                resize(featureMaps_45.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
295                mapNormalization(&featureMap_scaled);
296                ori_45 = ori_45 + featureMap_scaled;   
297                resize(featureMaps_90.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
298                mapNormalization(&featureMap_scaled);
299                ori_90 = ori_90 + featureMap_scaled;
300                resize(featureMaps_135.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
301                mapNormalization(&featureMap_scaled);
302                ori_135 = ori_135 + featureMap_scaled; 
303        }
304
305        mapNormalization(&ori_0);       
306        mapNormalization(&ori_45);
307        mapNormalization(&ori_90);
308        mapNormalization(&ori_135);
309        conspicuityMap_O = ori_0 + ori_45 + ori_90 + ori_135;
310
311        mapNormalization(&conspicuityMap_I);
312        mapNormalization(&conspicuityMap_C);
313        mapNormalization(&conspicuityMap_O);
314
315        S = conspicuityMap_I + conspicuityMap_C + conspicuityMap_O;
316        S = S/3;
317}
318void saliencyMapItti::mapNormalization(Mat* src)
319{
320        double minVal,maxVal;   
321        minMaxLoc(*src, &minVal, &maxVal);
322        *src = *src / (float) maxVal;
323}
324
325void saliencyMapItti::clearBuffers()
326{
327        gaussianPyramid_I.clear();
328        gaussianPyramid_R.clear();
329        gaussianPyramid_G.clear();
330        gaussianPyramid_B.clear();
331        gaussianPyramid_Y.clear();
332        featureMaps_I.clear();
333        featureMaps_RG.clear();
334        featureMaps_BY.clear();
335        featureMaps_0.clear();
336        featureMaps_45.clear();
337        featureMaps_90.clear();
338        featureMaps_135.clear();
339}
340
341int main(int argc, char **argv)
342{
343        ros::init(argc, argv, "saliencymap");
344
345        saliencyMapItti salmapItti;
346
347        ros::spin();
348
349        return 0;
350}
Note: See TracBrowser for help on using the repository browser.