saliencyDetectionHou.h
Go to the documentation of this file.
00001 //===================================================================================
00002 // Name        : saliencyDetectionHou.h
00003 // Author      : Oytun Akman, oytunakman@gmail.com
00004 // Version     : 1.0
00005 // Copyright   : Copyright (c) 2010 LGPL
00006 // Description : C++ implementation of "Saliency Detection: A Spectral Residual 
00007 //                               Approach" by Xiaodi Hou and Liqing Zhang (CVPR 2007).                                                                                            
00008 //===================================================================================
00009 
00010 #ifndef _SALIENCYMAPHOU_H_INCLUDED_
00011 #define _SALIENCYMAPHOU_H_INCLUDED_
00012 
00013 // ROS
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 // OpenCV
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 saliencyMapHou
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         saliencyMapHou() : nh_("~"), it_(nh_)
00040         {
00041                 image_sub_ = it_.subscribe("/rgbimage_in", 1, &saliencyMapHou::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         ~saliencyMapHou()
00048         {
00049                 nh_.shutdown();
00050         }
00051 
00052         void imageCB(const sensor_msgs::ImageConstPtr& msg_ptr);
00053         void calculateSaliencyMap(const Mat* src, Mat* dst);
00054 };
00055 #endif


saliency_detection
Author(s): Joris van de Weem
autogenerated on Sun Jan 5 2014 11:07:22