1 | //===================================================================================
|
---|
2 | // Name : saliencyDetectionHou.h
|
---|
3 | // Author : Oytun Akman, oytunakman@gmail.com
|
---|
4 | // Version : 1.0
|
---|
5 | // Copyright : Copyright (c) 2010 LGPL
|
---|
6 | // Description : C++ implementation of "Saliency Detection: A Spectral Residual
|
---|
7 | // Approach" by Xiaodi Hou and Liqing Zhang (CVPR 2007).
|
---|
8 | //===================================================================================
|
---|
9 |
|
---|
10 | #ifndef _SALIENCYMAPHOU_H_INCLUDED_
|
---|
11 | #define _SALIENCYMAPHOU_H_INCLUDED_
|
---|
12 |
|
---|
13 | // ROS
|
---|
14 | #include <ros/ros.h>
|
---|
15 | #include "image_transport/image_transport.h"
|
---|
16 | #include <cv_bridge/cv_bridge.h>
|
---|
17 | #include <sensor_msgs/image_encodings.h>
|
---|
18 | #include <sensor_msgs/fill_image.h>
|
---|
19 | #include <geometry_msgs/Point.h>
|
---|
20 |
|
---|
21 | // OpenCV
|
---|
22 | #include "cv.h"
|
---|
23 | #include "opencv2/highgui/highgui.hpp"
|
---|
24 |
|
---|
25 | using namespace cv;
|
---|
26 | using namespace std;
|
---|
27 | namespace enc = sensor_msgs::image_encodings;
|
---|
28 |
|
---|
29 | class saliencyMapHou
|
---|
30 | {
|
---|
31 | protected:
|
---|
32 | ros::NodeHandle nh_;
|
---|
33 | ros::Publisher point_pub_;
|
---|
34 | image_transport::ImageTransport it_;
|
---|
35 | image_transport::Subscriber image_sub_;
|
---|
36 | image_transport::Publisher saliencymap_pub_;
|
---|
37 |
|
---|
38 | public:
|
---|
39 | saliencyMapHou() : nh_("~"), it_(nh_)
|
---|
40 | {
|
---|
41 | image_sub_ = it_.subscribe("/rgbimage_in", 1, &saliencyMapHou::imageCB, this);
|
---|
42 | saliencymap_pub_= it_.advertise("/saliency/image", 1);
|
---|
43 | point_pub_ = nh_.advertise<geometry_msgs::Point>("/saliency/salientpoint", 1);
|
---|
44 | }
|
---|
45 |
|
---|
46 |
|
---|
47 | ~saliencyMapHou()
|
---|
48 | {
|
---|
49 | nh_.shutdown();
|
---|
50 | }
|
---|
51 |
|
---|
52 | void imageCB(const sensor_msgs::ImageConstPtr& msg_ptr);
|
---|
53 | void calculateSaliencyMap(const Mat* src, Mat* dst);
|
---|
54 | };
|
---|
55 | #endif
|
---|