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 
14 #include <jsk_topic_tools/diagnostic_nodelet.h>
15 
16 #include <omp.h>
17 #include <time.h>
18 #include <sys/time.h>
19 
20 namespace jsk_perception
21 {
22  class SaliencyMapGenerator: public jsk_topic_tools::DiagnosticNodelet
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 
ros::Publisher
image_encodings.h
jsk_perception::SaliencyMapGenerator::pub_image_
ros::Publisher pub_image_
Definition: saliency_map_generator.h:41
jsk_perception::SaliencyMapGenerator::mixOnOff
void mixOnOff(cv::Mat intensityOn, cv::Mat intensityOff, cv::Mat intensity)
Definition: saliency_map_generator_node.cpp:273
ros.h
time.h
jsk_perception::SaliencyMapGenerator::callback
void callback(const sensor_msgs::Image::ConstPtr &)
Definition: saliency_map_generator_node.cpp:31
jsk_perception::SaliencyMapGenerator::getIntensity
void getIntensity(cv::Mat, cv::Mat, cv::Mat, cv::Mat, bool)
jsk_perception::SaliencyMapGenerator::computeSaliencyImpl
bool computeSaliencyImpl(cv::Mat, cv::Mat &)
Definition: saliency_map_generator_node.cpp:69
jsk_perception::SaliencyMapGenerator::setNumThreads
void setNumThreads(int)
Definition: saliency_map_generator_node.cpp:82
console.h
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::SaliencyMapGenerator
Definition: saliency_map_generator.h:22
jsk_perception::SaliencyMapGenerator::unsubscribe
void unsubscribe()
Definition: saliency_map_generator_node.cpp:25
jsk_perception::SaliencyMapGenerator::lock_
boost::mutex lock_
Definition: saliency_map_generator.h:39
jsk_perception::SaliencyMapGenerator::copyImage
void copyImage(cv::Mat, cv::Mat)
Definition: saliency_map_generator_node.cpp:87
jsk_perception::SaliencyMapGenerator::getMean
float getMean(cv::Mat, cv::Point2i, int, int)
Definition: saliency_map_generator_node.cpp:175
jsk_perception::SaliencyMapGenerator::subscribe
void subscribe()
Definition: saliency_map_generator_node.cpp:19
jsk_perception::SaliencyMapGenerator::start_
double start_
Definition: saliency_map_generator.h:35
jsk_perception::SaliencyMapGenerator::counter_
int counter_
Definition: saliency_map_generator.h:36
jsk_perception::SaliencyMapGenerator::SaliencyMapGenerator
SaliencyMapGenerator()
Definition: saliency_map_generator.h:48
cv_bridge.h
jsk_perception::SaliencyMapGenerator::print_fps_
bool print_fps_
Definition: saliency_map_generator.h:34
jsk_perception::SaliencyMapGenerator::calcIntensityChannel
void calcIntensityChannel(cv::Mat, cv::Mat)
Definition: saliency_map_generator_node.cpp:92
jsk_perception::SaliencyMapGenerator::num_threads_
int num_threads_
Definition: saliency_map_generator.h:33
jsk_perception::SaliencyMapGenerator::mixScales
void mixScales(cv::Mat *, cv::Mat, cv::Mat *, cv::Mat, const int)
Definition: saliency_map_generator_node.cpp:213
jsk_perception::SaliencyMapGenerator::onInit
void onInit()
Definition: saliency_map_generator_node.cpp:9
jsk_perception::SaliencyMapGenerator::sub_image_
ros::Subscriber sub_image_
Definition: saliency_map_generator.h:40
ros::Subscriber
jsk_perception::SaliencyMapGenerator::getIntensityScaled
void getIntensityScaled(cv::Mat, cv::Mat, cv::Mat, cv::Mat, int)
Definition: saliency_map_generator_node.cpp:141


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17