Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #ifndef _SALIENCYMAPITTI_H_INCLUDED_
00012 #define _SALIENCYMAPITTI_H_INCLUDED_
00013
00014 #include <ros/ros.h>
00015 #include "image_transport/image_transport.h"
00016 #include <cv_bridge/cv_bridge.h>
00017 #include <sensor_msgs/image_encodings.h>
00018 #include <sensor_msgs/fill_image.h>
00019 #include <geometry_msgs/Point.h>
00020
00021
00022 #include "cv.h"
00023 #include "opencv2/highgui/highgui.hpp"
00024
00025 using namespace cv;
00026 using namespace std;
00027 namespace enc = sensor_msgs::image_encodings;
00028
00029 class saliencyMapItti
00030 {
00031 protected:
00032 ros::NodeHandle nh_;
00033 ros::Publisher point_pub_;
00034 image_transport::ImageTransport it_;
00035 image_transport::Subscriber image_sub_;
00036 image_transport::Publisher saliencymap_pub_;
00037
00038 public:
00039 saliencyMapItti() : nh_("~"), it_(nh_)
00040 {
00041 image_sub_ = it_.subscribe("/rgbimage_in", 1, &saliencyMapItti::imageCB, this);
00042 saliencymap_pub_= it_.advertise("/saliency/image", 1);
00043 point_pub_ = nh_.advertise<geometry_msgs::Point>("/saliency/salientpoint", 1);
00044 }
00045
00046
00047 ~saliencyMapItti()
00048 {
00049 nh_.shutdown();
00050 }
00051
00052 void imageCB(const sensor_msgs::ImageConstPtr& msg_ptr);
00053 void calculateSaliencyMap(const Mat* src, Mat* dst, int scaleBase);
00054 void combineFeatureMaps(int scale);
00055
00056 Mat conspicuityMap_I;
00057 Mat conspicuityMap_C;
00058 Mat conspicuityMap_O;
00059 Mat S;
00060
00061 private:
00062 Mat r,g,b,R,G,B,Y,I;
00063 vector<Mat> gaussianPyramid_I;
00064 vector<Mat> gaussianPyramid_R;
00065 vector<Mat> gaussianPyramid_G;
00066 vector<Mat> gaussianPyramid_B;
00067 vector<Mat> gaussianPyramid_Y;
00068
00069 void createChannels(const Mat* src);
00070 void createScaleSpace(const Mat* src, vector<Mat>* dst, int scale);
00071
00072 void normalize_rgb();
00073 void create_RGBY();
00074 void createIntensityFeatureMaps();
00075 void createColorFeatureMaps();
00076 void createOrientationFeatureMaps(int orientation);
00077 void mapNormalization(Mat* src);
00078 void clearBuffers();
00079
00080 vector<Mat> featureMaps_I;
00081 vector<Mat> featureMaps_RG;
00082 vector<Mat> featureMaps_BY;
00083 vector<Mat> featureMaps_0;
00084 vector<Mat> featureMaps_45;
00085 vector<Mat> featureMaps_90;
00086 vector<Mat> featureMaps_135;
00087 };
00088 #endif