[10] | 1 | //===================================================================================
|
---|
| 2 | // Name : saliencyDetectionHou.cpp
|
---|
| 3 | // Author : Oytun Akman, oytunakman@gmail.com
|
---|
| 4 | // Editor : Joris van de Weem, joris.vdweem@gmail.com (Conversion to ROS)
|
---|
| 5 | // Version : 1.2
|
---|
| 6 | // Copyright : Copyright (c) 2010 LGPL
|
---|
| 7 | // Description : C++ implementation of "Saliency Detection: A Spectral Residual
|
---|
| 8 | // Approach" by Xiaodi Hou and Liqing Zhang (CVPR 2007).
|
---|
| 9 | //===================================================================================
|
---|
| 10 | // v1.1: Changed Gaussianblur of logamplitude to averaging blur and gaussian kernel of saliency map to sigma = 8, kernelsize = 5
|
---|
| 11 | // for better consistency with the paper. (Joris)
|
---|
| 12 | // v1.2: Ported to Robot Operating System (ROS) (Joris)
|
---|
| 13 |
|
---|
| 14 | #include <saliency_detection/saliencyDetectionHou.h>
|
---|
| 15 |
|
---|
| 16 |
|
---|
| 17 | void saliencyMapHou::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
|
---|
| 18 | {
|
---|
| 19 | cv_bridge::CvImagePtr cv_ptr;
|
---|
| 20 | sensor_msgs::Image salmap_;
|
---|
| 21 | geometry_msgs::Point salientpoint_;
|
---|
| 22 |
|
---|
| 23 | Mat image_, saliencymap_;
|
---|
| 24 | Point pt_salient;
|
---|
| 25 | double maxVal;
|
---|
| 26 |
|
---|
| 27 | try
|
---|
| 28 | {
|
---|
| 29 | cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
|
---|
| 30 | }
|
---|
| 31 | catch (cv_bridge::Exception& e)
|
---|
| 32 | {
|
---|
| 33 | ROS_ERROR("cv_bridge exception: %s", e.what());
|
---|
| 34 | }
|
---|
| 35 | cv_ptr->image.copyTo(image_);
|
---|
| 36 |
|
---|
| 37 | saliencymap_.create(image_.size(),CV_8UC1);
|
---|
| 38 | saliencyMapHou::calculateSaliencyMap(&image_, &saliencymap_);
|
---|
| 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 |
|
---|
| 56 |
|
---|
| 57 | void saliencyMapHou::calculateSaliencyMap(const Mat* src, Mat* dst)
|
---|
| 58 | {
|
---|
| 59 | Mat grayTemp, grayDown;
|
---|
| 60 | vector<Mat> mv;
|
---|
| 61 | //Size imageSize(160,120);
|
---|
| 62 | Size imageSize(64,64);
|
---|
| 63 | Mat realImage(imageSize,CV_64F);
|
---|
| 64 | Mat imaginaryImage(imageSize,CV_64F); imaginaryImage.setTo(0);
|
---|
| 65 | Mat combinedImage(imageSize,CV_64FC2);
|
---|
| 66 | Mat imageDFT;
|
---|
| 67 | Mat logAmplitude;
|
---|
| 68 | Mat angle(imageSize,CV_64F);
|
---|
| 69 | Mat magnitude(imageSize,CV_64F);
|
---|
| 70 | Mat logAmplitude_blur;
|
---|
| 71 |
|
---|
| 72 | cvtColor(*src, grayTemp, CV_BGR2GRAY);
|
---|
| 73 | resize(grayTemp, grayDown, imageSize, 0, 0, INTER_LINEAR);
|
---|
| 74 | for(int j=0; j<grayDown.rows;j++)
|
---|
| 75 | for(int i=0; i<grayDown.cols; i++)
|
---|
| 76 | realImage.at<double>(j,i) = grayDown.at<uchar>(j,i);
|
---|
| 77 |
|
---|
| 78 | mv.push_back(realImage);
|
---|
| 79 | mv.push_back(imaginaryImage);
|
---|
| 80 | merge(mv,combinedImage);
|
---|
| 81 | dft( combinedImage, imageDFT);
|
---|
| 82 | split(imageDFT, mv);
|
---|
| 83 |
|
---|
| 84 | //-- Get magnitude and phase of frequency spectrum --//
|
---|
| 85 | cartToPolar(mv.at(0), mv.at(1), magnitude, angle, false);
|
---|
| 86 | log(magnitude,logAmplitude);
|
---|
| 87 | //-- Blur log amplitude with averaging filter --//
|
---|
| 88 | blur(logAmplitude, logAmplitude_blur, Size(3,3), Point(-1,-1), BORDER_DEFAULT);
|
---|
| 89 |
|
---|
| 90 | exp(logAmplitude - logAmplitude_blur,magnitude);
|
---|
| 91 | //-- Back to cartesian frequency domain --//
|
---|
| 92 | polarToCart(magnitude, angle, mv.at(0), mv.at(1), false);
|
---|
| 93 | merge(mv, imageDFT);
|
---|
| 94 | dft( imageDFT, combinedImage, CV_DXT_INVERSE);
|
---|
| 95 | split(combinedImage, mv);
|
---|
| 96 |
|
---|
| 97 | cartToPolar(mv.at(0), mv.at(1), magnitude, angle, false);
|
---|
| 98 | GaussianBlur(magnitude, magnitude, Size(5,5), 8, 0, BORDER_DEFAULT);
|
---|
| 99 | magnitude = magnitude.mul(magnitude);
|
---|
| 100 |
|
---|
| 101 | double minVal,maxVal;
|
---|
| 102 | minMaxLoc(magnitude, &minVal, &maxVal);
|
---|
| 103 | magnitude = magnitude / maxVal;
|
---|
| 104 |
|
---|
| 105 | Mat tempFloat(imageSize,CV_32F);
|
---|
| 106 | for(int j=0; j<magnitude.rows;j++)
|
---|
| 107 | for(int i=0; i<magnitude.cols; i++)
|
---|
| 108 | tempFloat.at<float>(j,i) = magnitude.at<double>(j,i);
|
---|
| 109 |
|
---|
| 110 | resize(tempFloat, *dst, dst->size(), 0, 0, INTER_LINEAR);
|
---|
| 111 | }
|
---|
| 112 |
|
---|
| 113 | int main(int argc, char **argv)
|
---|
| 114 | {
|
---|
| 115 | ros::init(argc, argv, "saliencymap");
|
---|
| 116 |
|
---|
| 117 | saliencyMapHou salmapHou;
|
---|
| 118 |
|
---|
| 119 | ros::spin();
|
---|
| 120 |
|
---|
| 121 | return 0;
|
---|
| 122 | }
|
---|