00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #include <saliency_detection/saliencyDetectionItti.h>
00014 #include <saliency_detection/cvgabor.h>
00015
00016 void saliencyMapItti::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
00017 {
00018 cv_bridge::CvImagePtr cv_ptr;
00019 sensor_msgs::Image salmap_;
00020 geometry_msgs::Point salientpoint_;
00021
00022 Mat image_, saliencymap_;
00023 Point pt_salient;
00024 double maxVal;
00025
00026 try
00027 {
00028 cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
00029 }
00030 catch (cv_bridge::Exception& e)
00031 {
00032 ROS_ERROR("cv_bridge exception: %s", e.what());
00033 }
00034 cv_ptr->image.copyTo(image_);
00035
00036
00037 saliencymap_.create(image_.size(),CV_8UC1);
00038 saliencyMapItti::calculateSaliencyMap(&image_, &saliencymap_,1);
00039
00040
00041 cv::minMaxLoc(saliencymap_,NULL,&maxVal,NULL,&pt_salient);
00042 salientpoint_.x = pt_salient.x;
00043 salientpoint_.y = pt_salient.y;
00044
00045
00046
00047 saliencymap_.convertTo(saliencymap_, CV_8UC1,255);
00048 fillImage(salmap_, "mono8",saliencymap_.rows, saliencymap_.cols, saliencymap_.step, const_cast<uint8_t*>(saliencymap_.data));
00049
00050 saliencymap_pub_.publish(salmap_);
00051 point_pub_.publish(salientpoint_);
00052
00053 return;
00054 }
00055
00056 void saliencyMapItti::calculateSaliencyMap(const Mat* src, Mat* dst, int scaleBase)
00057 {
00058 createChannels(src);
00059
00060 createIntensityFeatureMaps();
00061 createColorFeatureMaps();
00062 createOrientationFeatureMaps(0);
00063 createOrientationFeatureMaps(2);
00064 createOrientationFeatureMaps(4);
00065 createOrientationFeatureMaps(6);
00066
00067 combineFeatureMaps(scaleBase);
00068
00069 resize(S, *dst, src->size(), 0, 0, INTER_LINEAR);
00070
00071 clearBuffers();
00072 }
00073
00074 void saliencyMapItti::createChannels(const Mat* src)
00075 {
00076 b.create(src->size(),CV_32F);
00077 g.create(src->size(),CV_32F);
00078 r.create(src->size(),CV_32F);
00079 I.create(src->size(),CV_32F);
00080 vector<Mat> planes;
00081 split(*src, planes);
00082
00083 for(int j=0; j<r.rows;j++)
00084 for(int i=0; i<r.cols; i++)
00085 {
00086 b.at<float>(j,i) = planes[0].at<uchar>(j,i);
00087 g.at<float>(j,i) = planes[1].at<uchar>(j,i);
00088 r.at<float>(j,i) = planes[2].at<uchar>(j,i);
00089 }
00090
00091 I = r+g+b;
00092 I = I/3;
00093
00094 normalize_rgb();
00095 create_RGBY();
00096 createScaleSpace(&I, &gaussianPyramid_I, 8);
00097 createScaleSpace(&R, &gaussianPyramid_R, 8);
00098 createScaleSpace(&G, &gaussianPyramid_G, 8);
00099 createScaleSpace(&B, &gaussianPyramid_B, 8);
00100 createScaleSpace(&Y, &gaussianPyramid_Y, 8);
00101 }
00102
00103
00104
00105
00106 void saliencyMapItti::normalize_rgb()
00107 {
00108 double minVal,maxVal;
00109 minMaxLoc(I, &minVal, &maxVal);
00110 Mat mask_I;
00111 threshold(I, mask_I, maxVal/10, 1.0, THRESH_BINARY);
00112
00113 r = r/I;
00114 g = g/I;
00115 b = b/I;
00116 r = r.mul(mask_I);
00117 g = g.mul(mask_I);
00118 b = b.mul(mask_I);
00119 }
00120
00121 void saliencyMapItti::create_RGBY()
00122 {
00123 Mat gb = g+b;
00124 Mat rb = r+b;
00125 Mat rg = r+g;
00126 Mat rg_ = r-g;
00127
00128 R = r-gb/2;
00129 G = g-rb/2;
00130 B = b-rg/2;
00131 Y = rg/2 - abs(rg_/2) - b;
00132
00133 Mat mask;
00134 threshold(R, mask, 0.0, 1.0, THRESH_BINARY);
00135 R = R.mul(mask);
00136 threshold(G, mask, 0.0, 1.0, THRESH_BINARY);
00137 G = G.mul(mask);
00138 threshold(B, mask, 0.0, 1.0, THRESH_BINARY);
00139 B = B.mul(mask);
00140 threshold(Y, mask, 0.0, 1.0, THRESH_BINARY);
00141 Y = Y.mul(mask);
00142 }
00143
00144 void saliencyMapItti::createScaleSpace(const Mat* src, vector<Mat>* dst, int scale)
00145 {
00146 buildPyramid( *src, *dst, scale);
00147 }
00148
00149 void saliencyMapItti::createIntensityFeatureMaps()
00150 {
00151 int fineScaleNumber = 3;
00152 int scaleDiff = 2;
00153 int c[3] = {2,3,4};
00154 int delta[2] = {3,4};
00155
00156 for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
00157 {
00158 Mat fineScaleImage = gaussianPyramid_I.at(c[scaleIndex]);
00159 Size fineScaleImageSize = fineScaleImage.size();
00160
00161 for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
00162 {
00163 int s = c[scaleIndex] + delta[scaleDiffIndex];
00164 Mat coarseScaleImage = gaussianPyramid_I.at(s);
00165 Mat coarseScaleImageUp;
00166 resize(coarseScaleImage, coarseScaleImageUp, fineScaleImageSize, 0, 0, INTER_LINEAR);
00167 Mat I_cs = abs(fineScaleImage - coarseScaleImageUp);
00168 featureMaps_I.push_back(I_cs);
00169 }
00170 }
00171 }
00172
00173 void saliencyMapItti::createColorFeatureMaps()
00174 {
00175 int fineScaleNumber = 3;
00176 int scaleDiff = 2;
00177 int c[3] = {2,3,4};
00178 int delta[2] = {3,4};
00179
00180 for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
00181 {
00182 Mat fineScaleImageR = gaussianPyramid_R.at(c[scaleIndex]);
00183 Mat fineScaleImageG = gaussianPyramid_G.at(c[scaleIndex]);
00184 Mat fineScaleImageB = gaussianPyramid_B.at(c[scaleIndex]);
00185 Mat fineScaleImageY = gaussianPyramid_Y.at(c[scaleIndex]);
00186 Size fineScaleImageSize = fineScaleImageR.size();
00187
00188 Mat RGc = fineScaleImageR - fineScaleImageG;
00189 Mat BYc = fineScaleImageB - fineScaleImageY;
00190
00191 for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
00192 {
00193 int s = c[scaleIndex] + delta[scaleDiffIndex];
00194 Mat coarseScaleImageR = gaussianPyramid_R.at(s);
00195 Mat coarseScaleImageG = gaussianPyramid_G.at(s);
00196 Mat coarseScaleImageB = gaussianPyramid_B.at(s);
00197 Mat coarseScaleImageY = gaussianPyramid_Y.at(s);
00198
00199 Mat GRs = coarseScaleImageG - coarseScaleImageR;
00200 Mat YBs = coarseScaleImageY - coarseScaleImageB;
00201 Mat coarseScaleImageUpGRs, coarseScaleImageUpYBs;
00202 resize(GRs, coarseScaleImageUpGRs, fineScaleImageSize, 0, 0, INTER_LINEAR);
00203 resize(YBs, coarseScaleImageUpYBs, fineScaleImageSize, 0, 0, INTER_LINEAR);
00204 Mat RG_cs = abs( RGc - coarseScaleImageUpGRs);
00205 Mat BY_cs = abs( BYc - coarseScaleImageUpYBs);
00206
00207 featureMaps_RG.push_back(RG_cs);
00208 featureMaps_BY.push_back(BY_cs);
00209 }
00210 }
00211 }
00212
00213 void saliencyMapItti::createOrientationFeatureMaps(int orientation)
00214 {
00215 int fineScaleNumber = 3;
00216 int scaleDiff = 2;
00217 int c[3] = {2,3,4};
00218 int delta[2] = {3,4};
00219 CvGabor *gabor = new CvGabor(orientation,0);
00220 IplImage* gbr_fineScaleImage, *gbr_coarseScaleImage;
00221
00222 for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
00223 {
00224 Mat fineScaleImage = gaussianPyramid_I.at(c[scaleIndex]);
00225 Size fineScaleImageSize = fineScaleImage.size();
00226
00227 IplImage src_fineScaleImage = IplImage(fineScaleImage);
00228 gbr_fineScaleImage = cvCreateImage(fineScaleImage.size(),IPL_DEPTH_8U, 1);
00229 gabor->conv_img(&src_fineScaleImage,gbr_fineScaleImage,CV_GABOR_REAL);
00230 Mat src_responseImg(gbr_fineScaleImage);
00231
00232 for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
00233 {
00234 int s = c[scaleIndex] + delta[scaleDiffIndex];
00235 Mat coarseScaleImage = gaussianPyramid_I.at(s);
00236 IplImage src_coarseScaleImage = IplImage(coarseScaleImage);
00237 gbr_coarseScaleImage = cvCreateImage(coarseScaleImage.size(),IPL_DEPTH_8U, 1);
00238 gabor->conv_img(&src_coarseScaleImage,gbr_coarseScaleImage,CV_GABOR_REAL);
00239 Mat coarse_responseImg(gbr_coarseScaleImage);
00240
00241 Mat coarseScaleImageUp;
00242 resize(coarse_responseImg, coarseScaleImageUp, fineScaleImageSize, 0, 0, INTER_LINEAR);
00243
00244 Mat temp = abs(src_responseImg - coarseScaleImageUp);
00245 Mat O_cs(temp.size(),CV_32F);
00246
00247 for(int j=0; j<temp.rows;j++)
00248 for(int i=0; i<temp.cols; i++)
00249 O_cs.at<float>(j,i) = temp.at<uchar>(j,i);
00250
00251 if(orientation == 0)
00252 featureMaps_0.push_back(O_cs);
00253 if(orientation == 2)
00254 featureMaps_45.push_back(O_cs);
00255 if(orientation == 4)
00256 featureMaps_90.push_back(O_cs);
00257 if(orientation == 6)
00258 featureMaps_135.push_back(O_cs);
00259
00260 cvReleaseImage(&gbr_coarseScaleImage);
00261 }
00262 cvReleaseImage(&gbr_fineScaleImage);
00263 }
00264 }
00265
00266 void saliencyMapItti::combineFeatureMaps(int scale)
00267 {
00268 Size scaleImageSize = gaussianPyramid_I.at(scale).size();
00269 conspicuityMap_I.create(scaleImageSize,CV_32F); conspicuityMap_I.setTo(0);
00270 conspicuityMap_C.create(scaleImageSize,CV_32F); conspicuityMap_C.setTo(0);
00271 conspicuityMap_O.create(scaleImageSize,CV_32F); conspicuityMap_O.setTo(0);
00272 Mat ori_0(scaleImageSize,CV_32F); ori_0.setTo(0);
00273 Mat ori_45(scaleImageSize,CV_32F); ori_45.setTo(0);
00274 Mat ori_90(scaleImageSize,CV_32F); ori_90.setTo(0);
00275 Mat ori_135(scaleImageSize,CV_32F); ori_135.setTo(0);
00276
00277 Mat featureMap, featureMap_scaled, RG, BY, RG_scaled, BY_scaled;
00278
00279 for (int index=0; index<3*2; index++)
00280 {
00281 resize(featureMaps_I.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
00282 mapNormalization(&featureMap_scaled);
00283 conspicuityMap_I = conspicuityMap_I + featureMap_scaled;
00284
00285 resize(featureMaps_RG.at(index), RG_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
00286 resize(featureMaps_BY.at(index), BY_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
00287 mapNormalization(&RG_scaled);
00288 mapNormalization(&BY_scaled);
00289 conspicuityMap_C = conspicuityMap_C + (RG_scaled + BY_scaled);
00290
00291 resize(featureMaps_0.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
00292 mapNormalization(&featureMap_scaled);
00293 ori_0 = ori_0 + featureMap_scaled;
00294 resize(featureMaps_45.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
00295 mapNormalization(&featureMap_scaled);
00296 ori_45 = ori_45 + featureMap_scaled;
00297 resize(featureMaps_90.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
00298 mapNormalization(&featureMap_scaled);
00299 ori_90 = ori_90 + featureMap_scaled;
00300 resize(featureMaps_135.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
00301 mapNormalization(&featureMap_scaled);
00302 ori_135 = ori_135 + featureMap_scaled;
00303 }
00304
00305 mapNormalization(&ori_0);
00306 mapNormalization(&ori_45);
00307 mapNormalization(&ori_90);
00308 mapNormalization(&ori_135);
00309 conspicuityMap_O = ori_0 + ori_45 + ori_90 + ori_135;
00310
00311 mapNormalization(&conspicuityMap_I);
00312 mapNormalization(&conspicuityMap_C);
00313 mapNormalization(&conspicuityMap_O);
00314
00315 S = conspicuityMap_I + conspicuityMap_C + conspicuityMap_O;
00316 S = S/3;
00317 }
00318 void saliencyMapItti::mapNormalization(Mat* src)
00319 {
00320 double minVal,maxVal;
00321 minMaxLoc(*src, &minVal, &maxVal);
00322 *src = *src / (float) maxVal;
00323 }
00324
00325 void saliencyMapItti::clearBuffers()
00326 {
00327 gaussianPyramid_I.clear();
00328 gaussianPyramid_R.clear();
00329 gaussianPyramid_G.clear();
00330 gaussianPyramid_B.clear();
00331 gaussianPyramid_Y.clear();
00332 featureMaps_I.clear();
00333 featureMaps_RG.clear();
00334 featureMaps_BY.clear();
00335 featureMaps_0.clear();
00336 featureMaps_45.clear();
00337 featureMaps_90.clear();
00338 featureMaps_135.clear();
00339 }
00340
00341 int main(int argc, char **argv)
00342 {
00343 ros::init(argc, argv, "saliencymap");
00344
00345 saliencyMapItti salmapItti;
00346
00347 ros::spin();
00348
00349 return 0;
00350 }