saliency_map_generator.h
Go to the documentation of this file.
1 
2 #ifndef _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_
3 #define _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_
4 
5 #include <ros/ros.h>
6 #include <ros/console.h>
7 #include <opencv2/opencv.hpp>
8 
9 #include <sensor_msgs/Image.h>
11 #include <cv_bridge/cv_bridge.h>
12 #include <boost/thread/mutex.hpp>
13 
15 
16 #include <omp.h>
17 #include <time.h>
18 #include <sys/time.h>
19 
20 namespace jsk_perception
21 {
23  {
24  private:
25  void calcIntensityChannel(cv::Mat, cv::Mat);
26  void copyImage(cv::Mat, cv::Mat);
27  void getIntensityScaled(cv::Mat, cv::Mat, cv::Mat, cv::Mat, int);
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);
32 
34  bool print_fps_;
35  double start_;
36  int counter_;
37 
38  protected:
39  boost::mutex lock_;
42 
43  void onInit();
44  void subscribe();
45  void unsubscribe();
46 
47  public:
48  SaliencyMapGenerator(): DiagnosticNodelet("SaliencyMapGenerator"),
49  counter_(0), num_threads_(2) {}
50  bool computeSaliencyImpl(cv::Mat, cv::Mat &);
51  void setNumThreads(int);
52  void callback(const sensor_msgs::Image::ConstPtr &);
53  };
54 }
55 
56 #endif // _JSK_PERCEPTION_SALIENCY_MAP_GENERATOR_H_
57 
58 
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)
DiagnosticNodelet(const std::string &name)
void getIntensityScaled(cv::Mat, cv::Mat, cv::Mat, cv::Mat, int)
void callback(const sensor_msgs::Image::ConstPtr &)
void mixScales(cv::Mat *, cv::Mat, cv::Mat *, cv::Mat, const int)


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27