Go to the documentation of this file.00001
00002
00003 #ifndef JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H
00004 #define JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H
00005
00006 #include <jsk_topic_tools/diagnostic_nodelet.h>
00007 #include <jsk_perception/histogram_of_oriented_gradients.h>
00008 #include <jsk_recognition_msgs/RectArray.h>
00009 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00010 #include <jsk_perception/SlidingWindowObjectDetectorConfig.h>
00011
00012 #include <pcl/point_types.h>
00013
00014 #include <ros/ros.h>
00015 #include <ros/console.h>
00016 #include <rosbag/bag.h>
00017 #include <rosbag/view.h>
00018
00019 #include <boost/foreach.hpp>
00020
00021 #include <image_transport/image_transport.h>
00022 #include <cv_bridge/cv_bridge.h>
00023 #include <sensor_msgs/image_encodings.h>
00024 #include <sensor_msgs/PointCloud2.h>
00025 #include <dynamic_reconfigure/server.h>
00026
00027 #include <iostream>
00028 #include <vector>
00029 #include <string>
00030 #include <fstream>
00031 #include <map>
00032 #include <algorithm>
00033 #include <utility>
00034
00035 namespace jsk_perception
00036 {
00037 class SlidingWindowObjectDetector: public jsk_topic_tools::DiagnosticNodelet,
00038 public HOGFeatureDescriptor
00039 {
00040 public:
00041 SlidingWindowObjectDetector():
00042 DiagnosticNodelet("SlidingWindowObjectDetector") {}
00043
00044 virtual void readTrainingManifestFromDirectory();
00045 virtual void loadTrainedDetectorModel();
00046 virtual std::multimap<float, cv::Rect_<int> > runSlidingWindowDetector(
00047 const cv::Mat &, const cv::Size, const float, const int, const int);
00048 virtual void objectRecognizer(
00049 const cv::Mat &, std::multimap<float, cv::Rect_<int> > &,
00050 const cv::Size, const int = 16);
00051 virtual void pyramidialScaling(
00052 cv::Size &, const float);
00053 virtual std::vector<cv::Rect_<int> > nonMaximumSuppression(
00054 std::multimap<float, cv::Rect_<int> > &, const float);
00055 void convertCvRectToJSKRectArray(
00056 const std::vector<cv::Rect_<int> > &,
00057 jsk_recognition_msgs::RectArray &, const int, const cv::Size);
00058 virtual void configCallback(
00059 jsk_perception::SlidingWindowObjectDetectorConfig &, uint32_t);
00060 virtual void concatenateCVMat(
00061 const cv::Mat &, const cv::Mat &, cv::Mat &, bool = true);
00062 virtual void setBoundingBoxLabel(
00063 cv::Mat&, cv::Rect_<int>, const std::string = "object");
00064
00065
00066 virtual void computeHSHistogram(
00067 cv::Mat &, cv::Mat &, const int = 64, const int = 32, bool = true);
00068
00069 protected:
00070 virtual void imageCb(
00071 const sensor_msgs::ImageConstPtr&);
00072
00073 virtual void onInit();
00074 virtual void subscribe();
00075 virtual void unsubscribe();
00076
00077 boost::mutex mutex_;
00078 ros::Subscriber sub_image_;
00079 ros::Publisher pub_image_;
00080 ros::Publisher pub_rects_;
00081 ros::ServiceClient nms_client_;
00082
00083 int swindow_x;
00084 int swindow_y;
00085 float scale_;
00086 int stack_size_;
00087 int incrementor_;
00088 int downsize_;
00089
00090 std::string run_type_;
00091 std::string trainer_manifest_filename_;
00092 std::string object_dataset_filename_;
00093 std::string nonobject_dataset_filename_;
00094 std::string ndataset_path_;
00095
00096 std::string model_name_;
00097 std::string dataset_path_;
00098 #if CV_MAJOR_VERSION >= 3 // http://answers.opencv.org/question/46770/cvknearest-missing-in-300-cvmlknearest-abstract/
00099 cv::Ptr<cv::ml::SVM> supportVectorMachine_;
00100 #else
00101 boost::shared_ptr<cv::SVM> supportVectorMachine_;
00102 #endif
00103 boost::shared_ptr<dynamic_reconfigure::Server<
00104 jsk_perception::SlidingWindowObjectDetectorConfig> > srv_;
00105 boost::shared_ptr<rosbag::Bag> rosbag_;
00106 };
00107
00108 }
00109
00110
00111 #endif // JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H