sliding_window_object_detector.h
Go to the documentation of this file.
1 // @author Krishneel Chaudhary, JSK
2 
3 #ifndef JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H
4 #define JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H
5 
6 #include <jsk_topic_tools/diagnostic_nodelet.h>
8 #include <jsk_recognition_msgs/RectArray.h>
9 #include <jsk_recognition_msgs/ClusterPointIndices.h>
10 #include <jsk_perception/SlidingWindowObjectDetectorConfig.h>
11 
12 #include <pcl/point_types.h>
13 
14 #include <ros/ros.h>
15 #include <ros/console.h>
16 #include <rosbag/bag.h>
17 #include <rosbag/view.h>
18 
19 #include <boost/foreach.hpp>
20 
22 #include <cv_bridge/cv_bridge.h>
24 #include <sensor_msgs/PointCloud2.h>
25 #include <dynamic_reconfigure/server.h>
26 
27 #include <iostream>
28 #include <vector>
29 #include <string>
30 #include <fstream>
31 #include <map>
32 #include <algorithm>
33 #include <utility>
34 
35 namespace jsk_perception
36 {
37  class SlidingWindowObjectDetector: public jsk_topic_tools::DiagnosticNodelet,
39  {
40  public:
42  DiagnosticNodelet("SlidingWindowObjectDetector") {}
43 
44  virtual void readTrainingManifestFromDirectory();
45  virtual void loadTrainedDetectorModel();
46  virtual std::multimap<float, cv::Rect_<int> > runSlidingWindowDetector(
47  const cv::Mat &, const cv::Size, const float, const int, const int);
48  virtual void objectRecognizer(
49  const cv::Mat &, std::multimap<float, cv::Rect_<int> > &,
50  const cv::Size, const int = 16);
51  virtual void pyramidialScaling(
52  cv::Size &, const float);
53  virtual std::vector<cv::Rect_<int> > nonMaximumSuppression(
54  std::multimap<float, cv::Rect_<int> > &, const float);
56  const std::vector<cv::Rect_<int> > &,
57  jsk_recognition_msgs::RectArray &, const int, const cv::Size);
58  virtual void configCallback(
59  jsk_perception::SlidingWindowObjectDetectorConfig &, uint32_t);
60  virtual void concatenateCVMat(
61  const cv::Mat &, const cv::Mat &, cv::Mat &, bool = true);
62  virtual void setBoundingBoxLabel(
63  cv::Mat&, cv::Rect_<int>, const std::string = "object");
64 
65  // temp placed here
66  virtual void computeHSHistogram(
67  cv::Mat &, cv::Mat &, const int = 64, const int = 32, bool = true);
68 
69  protected:
70  virtual void imageCb(
71  const sensor_msgs::ImageConstPtr&);
72 
73  virtual void onInit();
74  virtual void subscribe();
75  virtual void unsubscribe();
76 
77  boost::mutex mutex_;
82 
83  int swindow_x;
84  int swindow_y;
85  float scale_;
88  int downsize_;
89 
90  std::string run_type_;
94  std::string ndataset_path_;
95 
96  std::string model_name_;
97  std::string dataset_path_;
98 
100 
101 #if CV_MAJOR_VERSION >= 3 // http://answers.opencv.org/question/46770/cvknearest-missing-in-300-cvmlknearest-abstract/
102  cv::Ptr<cv::ml::SVM> supportVectorMachine_;
103 #else
105 #endif
106  boost::shared_ptr<dynamic_reconfigure::Server<
107  jsk_perception::SlidingWindowObjectDetectorConfig> > srv_;
109  };
110 
111 } // namespace jsk_perception
112 
113 
114 #endif // JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H
jsk_perception::SlidingWindowObjectDetector::SlidingWindowObjectDetector
SlidingWindowObjectDetector()
Definition: sliding_window_object_detector.h:41
jsk_perception::SlidingWindowObjectDetector::onInit
virtual void onInit()
Definition: sliding_window_object_detector.cpp:14
jsk_perception::SlidingWindowObjectDetector::ndataset_path_
std::string ndataset_path_
Definition: sliding_window_object_detector.h:94
ros::Publisher
image_encodings.h
jsk_perception::SlidingWindowObjectDetector::dataset_path_
std::string dataset_path_
Definition: sliding_window_object_detector.h:97
boost::shared_ptr< cv::SVM >
jsk_perception::SlidingWindowObjectDetector::setBoundingBoxLabel
virtual void setBoundingBoxLabel(cv::Mat &, cv::Rect_< int >, const std::string="object")
Definition: sliding_window_object_detector.cpp:391
jsk_perception::SlidingWindowObjectDetector::object_dataset_filename_
std::string object_dataset_filename_
Definition: sliding_window_object_detector.h:92
ros.h
jsk_perception::SlidingWindowObjectDetector::objectRecognizer
virtual void objectRecognizer(const cv::Mat &, std::multimap< float, cv::Rect_< int > > &, const cv::Size, const int=16)
Definition: sliding_window_object_detector.cpp:180
jsk_perception::SlidingWindowObjectDetector::supportVectorMachine_
boost::shared_ptr< cv::SVM > supportVectorMachine_
Definition: sliding_window_object_detector.h:104
jsk_perception::SlidingWindowObjectDetector::srv_
boost::shared_ptr< dynamic_reconfigure::Server< jsk_perception::SlidingWindowObjectDetectorConfig > > srv_
Definition: sliding_window_object_detector.h:107
jsk_perception::SlidingWindowObjectDetector::runSlidingWindowDetector
virtual std::multimap< float, cv::Rect_< int > > runSlidingWindowDetector(const cv::Mat &, const cv::Size, const float, const int, const int)
Definition: sliding_window_object_detector.cpp:160
jsk_perception::SlidingWindowObjectDetector::nms_client_
ros::ServiceClient nms_client_
Definition: sliding_window_object_detector.h:81
jsk_perception::SlidingWindowObjectDetector::swindow_y
int swindow_y
Definition: sliding_window_object_detector.h:84
jsk_perception::SlidingWindowObjectDetector::nonobject_dataset_filename_
std::string nonobject_dataset_filename_
Definition: sliding_window_object_detector.h:93
jsk_perception::SlidingWindowObjectDetector::pub_image_
ros::Publisher pub_image_
Definition: sliding_window_object_detector.h:79
jsk_perception::SlidingWindowObjectDetector::swindow_x
int swindow_x
Definition: sliding_window_object_detector.h:83
bag.h
jsk_perception::SlidingWindowObjectDetector::rosbag_
boost::shared_ptr< rosbag::Bag > rosbag_
Definition: sliding_window_object_detector.h:108
jsk_perception::SlidingWindowObjectDetector
Definition: sliding_window_object_detector.h:37
jsk_perception::SlidingWindowObjectDetector::stack_size_
int stack_size_
Definition: sliding_window_object_detector.h:86
console.h
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::SlidingWindowObjectDetector::model_name_
std::string model_name_
Definition: sliding_window_object_detector.h:96
jsk_perception::SlidingWindowObjectDetector::subscribe
virtual void subscribe()
Definition: sliding_window_object_detector.cpp:70
jsk_perception::SlidingWindowObjectDetector::readTrainingManifestFromDirectory
virtual void readTrainingManifestFromDirectory()
Definition: sliding_window_object_detector.cpp:348
jsk_perception::SlidingWindowObjectDetector::incrementor_
int incrementor_
Definition: sliding_window_object_detector.h:87
jsk_perception::SlidingWindowObjectDetector::imageCb
virtual void imageCb(const sensor_msgs::ImageConstPtr &)
Definition: sliding_window_object_detector.cpp:85
ros::ServiceClient
jsk_perception::SlidingWindowObjectDetector::run_type_
std::string run_type_
Definition: sliding_window_object_detector.h:90
jsk_perception::SlidingWindowObjectDetector::downsize_
int downsize_
Definition: sliding_window_object_detector.h:88
jsk_perception::SlidingWindowObjectDetector::override_manifest_
bool override_manifest_
Definition: sliding_window_object_detector.h:99
image_transport.h
view.h
histogram_of_oriented_gradients.h
jsk_perception::SlidingWindowObjectDetector::computeHSHistogram
virtual void computeHSHistogram(cv::Mat &, cv::Mat &, const int=64, const int=32, bool=true)
Definition: sliding_window_object_detector.cpp:219
HOGFeatureDescriptor
Definition: histogram_of_oriented_gradients.h:16
jsk_perception::SlidingWindowObjectDetector::trainer_manifest_filename_
std::string trainer_manifest_filename_
Definition: sliding_window_object_detector.h:91
jsk_perception::SlidingWindowObjectDetector::convertCvRectToJSKRectArray
void convertCvRectToJSKRectArray(const std::vector< cv::Rect_< int > > &, jsk_recognition_msgs::RectArray &, const int, const cv::Size)
Definition: sliding_window_object_detector.cpp:314
cv_bridge.h
jsk_perception::SlidingWindowObjectDetector::configCallback
virtual void configCallback(jsk_perception::SlidingWindowObjectDetectorConfig &, uint32_t)
Definition: sliding_window_object_detector.cpp:409
jsk_perception::SlidingWindowObjectDetector::nonMaximumSuppression
virtual std::vector< cv::Rect_< int > > nonMaximumSuppression(std::multimap< float, cv::Rect_< int > > &, const float)
Definition: sliding_window_object_detector.cpp:250
jsk_perception::SlidingWindowObjectDetector::unsubscribe
virtual void unsubscribe()
Definition: sliding_window_object_detector.cpp:79
jsk_perception::SlidingWindowObjectDetector::pyramidialScaling
virtual void pyramidialScaling(cv::Size &, const float)
Definition: sliding_window_object_detector.cpp:239
jsk_perception::SlidingWindowObjectDetector::pub_rects_
ros::Publisher pub_rects_
Definition: sliding_window_object_detector.h:80
jsk_perception::SlidingWindowObjectDetector::sub_image_
ros::Subscriber sub_image_
Definition: sliding_window_object_detector.h:78
jsk_perception::SlidingWindowObjectDetector::mutex_
boost::mutex mutex_
Definition: sliding_window_object_detector.h:77
jsk_perception::SlidingWindowObjectDetector::loadTrainedDetectorModel
virtual void loadTrainedDetectorModel()
Definition: sliding_window_object_detector.cpp:330
ros::Subscriber
jsk_perception::SlidingWindowObjectDetector::concatenateCVMat
virtual void concatenateCVMat(const cv::Mat &, const cv::Mat &, cv::Mat &, bool=true)
Definition: sliding_window_object_detector.cpp:287
jsk_perception::SlidingWindowObjectDetector::scale_
float scale_
Definition: sliding_window_object_detector.h:85


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