00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014 #include <saliency_detection/saliencyDetectionHou.h>
00015
00016
00017 void saliencyMapHou::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
00018 {
00019 cv_bridge::CvImagePtr cv_ptr;
00020 sensor_msgs::Image salmap_;
00021 geometry_msgs::Point salientpoint_;
00022
00023 Mat image_, saliencymap_;
00024 Point pt_salient;
00025 double maxVal;
00026
00027 try
00028 {
00029 cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
00030 }
00031 catch (cv_bridge::Exception& e)
00032 {
00033 ROS_ERROR("cv_bridge exception: %s", e.what());
00034 }
00035 cv_ptr->image.copyTo(image_);
00036
00037 saliencymap_.create(image_.size(),CV_8UC1);
00038 saliencyMapHou::calculateSaliencyMap(&image_, &saliencymap_);
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
00057 void saliencyMapHou::calculateSaliencyMap(const Mat* src, Mat* dst)
00058 {
00059 Mat grayTemp, grayDown;
00060 vector<Mat> mv;
00061
00062 Size imageSize(64,64);
00063 Mat realImage(imageSize,CV_64F);
00064 Mat imaginaryImage(imageSize,CV_64F); imaginaryImage.setTo(0);
00065 Mat combinedImage(imageSize,CV_64FC2);
00066 Mat imageDFT;
00067 Mat logAmplitude;
00068 Mat angle(imageSize,CV_64F);
00069 Mat magnitude(imageSize,CV_64F);
00070 Mat logAmplitude_blur;
00071
00072 cvtColor(*src, grayTemp, CV_BGR2GRAY);
00073 resize(grayTemp, grayDown, imageSize, 0, 0, INTER_LINEAR);
00074 for(int j=0; j<grayDown.rows;j++)
00075 for(int i=0; i<grayDown.cols; i++)
00076 realImage.at<double>(j,i) = grayDown.at<uchar>(j,i);
00077
00078 mv.push_back(realImage);
00079 mv.push_back(imaginaryImage);
00080 merge(mv,combinedImage);
00081 dft( combinedImage, imageDFT);
00082 split(imageDFT, mv);
00083
00084
00085 cartToPolar(mv.at(0), mv.at(1), magnitude, angle, false);
00086 log(magnitude,logAmplitude);
00087
00088 blur(logAmplitude, logAmplitude_blur, Size(3,3), Point(-1,-1), BORDER_DEFAULT);
00089
00090 exp(logAmplitude - logAmplitude_blur,magnitude);
00091
00092 polarToCart(magnitude, angle, mv.at(0), mv.at(1), false);
00093 merge(mv, imageDFT);
00094 dft( imageDFT, combinedImage, CV_DXT_INVERSE);
00095 split(combinedImage, mv);
00096
00097 cartToPolar(mv.at(0), mv.at(1), magnitude, angle, false);
00098 GaussianBlur(magnitude, magnitude, Size(5,5), 8, 0, BORDER_DEFAULT);
00099 magnitude = magnitude.mul(magnitude);
00100
00101 double minVal,maxVal;
00102 minMaxLoc(magnitude, &minVal, &maxVal);
00103 magnitude = magnitude / maxVal;
00104
00105 Mat tempFloat(imageSize,CV_32F);
00106 for(int j=0; j<magnitude.rows;j++)
00107 for(int i=0; i<magnitude.cols; i++)
00108 tempFloat.at<float>(j,i) = magnitude.at<double>(j,i);
00109
00110 resize(tempFloat, *dst, dst->size(), 0, 0, INTER_LINEAR);
00111 }
00112
00113 int main(int argc, char **argv)
00114 {
00115 ros::init(argc, argv, "saliencymap");
00116
00117 saliencyMapHou salmapHou;
00118
00119 ros::spin();
00120
00121 return 0;
00122 }