2 #ifndef _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_
3 #define _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_
7 #include <opencv2/opencv.hpp>
9 #include <sensor_msgs/Image.h>
12 #include <boost/thread/mutex.hpp>
14 #include <jsk_topic_tools/diagnostic_nodelet.h>
28 float getMean(cv::Mat, cv::Point2i,
int,
int);
29 void mixScales(cv::Mat *, cv::Mat, cv::Mat *, cv::Mat,
const int);
30 void mixOnOff(cv::Mat intensityOn, cv::Mat intensityOff, cv::Mat intensity);
31 void getIntensity(cv::Mat, cv::Mat, cv::Mat, cv::Mat,
bool);
52 void callback(
const sensor_msgs::Image::ConstPtr &);
56 #endif // _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_