source: trunk/saliency_detection/src/saliencyDetectionRudinac.cpp @ 10

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

Imported saliency_detection at revision 1000

File size: 5.1 KB
Line 
1//===================================================================================
2// Name        : saliencyDetectionRudinac.cpp
3// Author      : Joris van de Weem, joris.vdweem@gmail.com
4// Version     : 1.1
5// Copyright   : Copyright (c) 2011 LGPL
6// Description : C++ implementation of "Maja Rudinac, Pieter P. Jonker.
7//                              "Saliency Detection and Object Localization in Indoor Environments".
8//                              ICPR'2010. pp.404~407                                                                                     
9//===================================================================================
10// v1.1: Ported to Robot Operating System (ROS)
11
12#include <saliency_detection/saliencyDetectionRudinac.h>
13
14void saliencyMapRudinac::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
15{
16        cv_bridge::CvImagePtr cv_ptr;
17        sensor_msgs::Image salmap_;
18        geometry_msgs::Point salientpoint_;
19
20        Mat image_, saliencymap_;
21        Point pt_salient;
22        double maxVal;
23
24        try
25        {
26                cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
27        }
28        catch (cv_bridge::Exception& e)
29        {
30                ROS_ERROR("cv_bridge exception: %s", e.what());
31        }
32        cv_ptr->image.copyTo(image_);
33
34
35        saliencymap_.create(image_.size(),CV_8UC1);
36        saliencyMapRudinac::calculateSaliencyMap(&image_, &saliencymap_);
37
38        //-- Return most salient point --//
39        cv::minMaxLoc(saliencymap_,NULL,&maxVal,NULL,&pt_salient);
40        salientpoint_.x = pt_salient.x;
41        salientpoint_.y = pt_salient.y;
42
43
44        //      CONVERT FROM CV::MAT TO ROSIMAGE FOR PUBLISHING
45        saliencymap_.convertTo(saliencymap_, CV_8UC1,255);
46        fillImage(salmap_, "mono8",saliencymap_.rows, saliencymap_.cols, saliencymap_.step, const_cast<uint8_t*>(saliencymap_.data));
47
48        saliencymap_pub_.publish(salmap_);
49        point_pub_.publish(salientpoint_);
50
51        return;
52}
53
54
55void saliencyMapRudinac::calculateSaliencyMap(const Mat* src, Mat* dst)
56{
57        Size imageSize(128,128);
58        Mat srcDown(imageSize,CV_64F);
59        Mat magnitudeI(imageSize,CV_64F);
60        Mat magnitudeRG(imageSize,CV_64F);
61        Mat magnitudeBY(imageSize,CV_64F);
62        Mat magnitude(imageSize,CV_64F);
63       
64        resize(*src, srcDown, imageSize, 0, 0, INTER_LINEAR);
65       
66        createChannels(&srcDown);
67        createSaliencyMap(I,&magnitudeI);
68        createSaliencyMap(RG,&magnitudeRG);
69        createSaliencyMap(BY,&magnitudeBY);
70       
71        magnitude= (magnitudeI + magnitudeRG + magnitudeBY);
72        GaussianBlur(magnitude, magnitude, Size(5,5), 0, 0, BORDER_DEFAULT);
73
74        //-- Scale to domain [0,1] --//
75        double minVal,maxVal;
76        minMaxLoc(magnitude, &minVal, &maxVal);
77        magnitude = magnitude / maxVal;
78
79        resize(magnitude, *dst, dst->size(), 0, 0, INTER_LINEAR);
80}
81
82
83void saliencyMapRudinac::createChannels(const Mat* src)
84{
85       
86        b.create(src->size(),CV_32F);
87        g.create(src->size(),CV_32F);
88        r.create(src->size(),CV_32F);
89        I.create(src->size(),CV_32F);
90        vector<Mat> planes;     
91        split(*src, planes);
92        Mat rgmax(src->size(),CV_32F);
93        Mat rgbmax(src->size(),CV_32F);
94        Mat mask(src->size(),CV_32F);
95
96        for(int j=0; j<r.rows;j++)
97        for(int i=0; i<r.cols; i++)
98        {
99                        b.at<float>(j,i) = planes[0].at<uchar>(j,i);
100                        g.at<float>(j,i) = planes[1].at<uchar>(j,i);
101                        r.at<float>(j,i) = planes[2].at<uchar>(j,i);
102        }
103       
104        I = r+g+b;
105        //threshold(I, I, 255, 255, THRESH_TRUNC); // Saturation as in Matlab?
106        I = I/3;
107               
108        rgmax = max(r,g);
109        rgbmax = max(rgmax,b);
110       
111        //-- Prevent that the lowest value is zero, because you cannot divide by zero.
112        for(int j=0; j<r.rows;j++)
113        for(int i=0; i<r.cols; i++)
114        {
115                        if (rgbmax.at<float>(j,i) == 0) rgbmax.at<float>(j,i) = 1;
116        }
117
118
119        RG = abs(r-g)/rgbmax;
120        BY = abs(b - min(r,g))/rgbmax;
121
122        rgbmax = rgbmax/255;
123        //-- If max(r,g,b)<0.1 all components should be zero to stop large fluctuations of the color opponency values at low luminance --//
124        threshold(rgbmax,mask,.1,1,THRESH_BINARY);
125        RG = RG.mul(mask);
126        BY = BY.mul(mask);
127        I = I.mul(mask);
128}
129
130
131
132void saliencyMapRudinac::createSaliencyMap(const Mat src, Mat* dst)
133{
134        vector<Mat> mv;
135       
136        Mat realImage(src.size(),CV_64F);
137        Mat imaginaryImage(src.size(),CV_64F); imaginaryImage.setTo(0);
138        Mat combinedImage(src.size(),CV_64FC2);
139        Mat image_DFT; 
140        Mat logAmplitude;
141        Mat angle(src.size(),CV_64F);
142        Mat Magnitude(src.size(),CV_64F);
143        Mat logAmplitude_blur;
144       
145        for(int j=0; j<src.rows;j++){
146        for(int i=0; i<src.cols; i++){
147                realImage.at<double>(j,i) = src.at<float>(j,i);
148        }
149        }
150
151                       
152        mv.push_back(realImage);
153        mv.push_back(imaginaryImage);   
154        merge(mv,combinedImage);       
155       
156        dft( combinedImage, image_DFT);
157        split(image_DFT, mv);   
158
159        //-- Get magnitude and phase of frequency spectrum --//
160        cartToPolar(mv.at(0), mv.at(1), Magnitude, angle, false);
161        log(Magnitude,logAmplitude);   
162               
163        //-- Blur log amplitude with averaging filter --//
164        blur(logAmplitude, logAmplitude_blur, Size(3,3), Point(-1,-1), BORDER_DEFAULT);
165        exp(logAmplitude - logAmplitude_blur,Magnitude);
166       
167        polarToCart(Magnitude, angle,mv.at(0), mv.at(1),false);
168        merge(mv,image_DFT);
169        dft(image_DFT,combinedImage,CV_DXT_INVERSE);
170
171        split(combinedImage,mv);
172        cartToPolar(mv.at(0), mv.at(1), Magnitude, angle, false);
173        Magnitude = Magnitude.mul(Magnitude);
174
175        Mat tempFloat(src.size(),CV_32F);
176        for(int j=0; j<Magnitude.rows;j++)
177        for(int i=0; i<Magnitude.cols; i++)
178                tempFloat.at<float>(j,i) = Magnitude.at<double>(j,i);
179       
180        *dst = tempFloat;
181}
182
183
184int main(int argc, char **argv)
185{
186        ros::init(argc, argv, "saliencymap");
187
188        saliencyMapRudinac salmapRudinac;
189
190        ros::spin();
191
192        return 0;
193}
Note: See TracBrowser for help on using the repository browser.