Go to the documentation of this file.00001
00002 #ifndef _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_
00003 #define _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_
00004
00005 #include <ros/ros.h>
00006 #include <ros/console.h>
00007 #include <opencv2/opencv.hpp>
00008
00009 #include <sensor_msgs/Image.h>
00010 #include <sensor_msgs/image_encodings.h>
00011 #include <cv_bridge/cv_bridge.h>
00012 #include <boost/thread/mutex.hpp>
00013
00014 #include <jsk_topic_tools/diagnostic_nodelet.h>
00015
00016 #include <omp.h>
00017 #include <time.h>
00018 #include <sys/time.h>
00019
00020 namespace jsk_perception
00021 {
00022 class SaliencyMapGenerator: public jsk_topic_tools::DiagnosticNodelet
00023 {
00024 private:
00025 void calcIntensityChannel(cv::Mat, cv::Mat);
00026 void copyImage(cv::Mat, cv::Mat);
00027 void getIntensityScaled(cv::Mat, cv::Mat, cv::Mat, cv::Mat, int);
00028 float getMean(cv::Mat, cv::Point2i, int, int);
00029 void mixScales(cv::Mat *, cv::Mat, cv::Mat *, cv::Mat, const int);
00030 void mixOnOff(cv::Mat intensityOn, cv::Mat intensityOff, cv::Mat intensity);
00031 void getIntensity(cv::Mat, cv::Mat, cv::Mat, cv::Mat, bool);
00032
00033 int num_threads_;
00034 bool print_fps_;
00035 double start_;
00036 int counter_;
00037
00038 protected:
00039 boost::mutex lock_;
00040 ros::Subscriber sub_image_;
00041 ros::Publisher pub_image_;
00042
00043 void onInit();
00044 void subscribe();
00045 void unsubscribe();
00046
00047 public:
00048 SaliencyMapGenerator(): DiagnosticNodelet("SaliencyMapGenerator"),
00049 counter_(0), num_threads_(2) {}
00050 bool computeSaliencyImpl(cv::Mat, cv::Mat &);
00051 void setNumThreads(int);
00052 void callback(const sensor_msgs::Image::ConstPtr &);
00053 };
00054 }
00055
00056 #endif // _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_
00057
00058