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> 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);
49 counter_(0), num_threads_(2) {}
52 void callback(
const sensor_msgs::Image::ConstPtr &);
56 #endif // _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_ ros::Subscriber sub_image_
void getIntensity(cv::Mat, cv::Mat, cv::Mat, cv::Mat, bool)
float getMean(cv::Mat, cv::Point2i, int, int)
void mixOnOff(cv::Mat intensityOn, cv::Mat intensityOff, cv::Mat intensity)
void copyImage(cv::Mat, cv::Mat)
void getIntensityScaled(cv::Mat, cv::Mat, cv::Mat, cv::Mat, int)
void callback(const sensor_msgs::Image::ConstPtr &)
ros::Publisher pub_image_
void mixScales(cv::Mat *, cv::Mat, cv::Mat *, cv::Mat, const int)
bool computeSaliencyImpl(cv::Mat, cv::Mat &)
void calcIntensityChannel(cv::Mat, cv::Mat)