3 #ifndef JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H 4 #define JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H 8 #include <jsk_recognition_msgs/RectArray.h> 9 #include <jsk_recognition_msgs/ClusterPointIndices.h> 10 #include <jsk_perception/SlidingWindowObjectDetectorConfig.h> 12 #include <pcl/point_types.h> 19 #include <boost/foreach.hpp> 24 #include <sensor_msgs/PointCloud2.h> 25 #include <dynamic_reconfigure/server.h> 47 const cv::Mat &,
const cv::Size,
const float,
const int,
const int);
49 const cv::Mat &, std::multimap<
float, cv::Rect_<int> > &,
50 const cv::Size,
const int = 16);
52 cv::Size &,
const float);
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);
59 jsk_perception::SlidingWindowObjectDetectorConfig &, uint32_t);
61 const cv::Mat &,
const cv::Mat &, cv::Mat &,
bool =
true);
63 cv::Mat&, cv::Rect_<int>,
const std::string =
"object");
67 cv::Mat &, cv::Mat &,
const int = 64,
const int = 32,
bool =
true);
71 const sensor_msgs::ImageConstPtr&);
101 #if CV_MAJOR_VERSION >= 3 // http://answers.opencv.org/question/46770/cvknearest-missing-in-300-cvmlknearest-abstract/ 107 jsk_perception::SlidingWindowObjectDetectorConfig> >
srv_;
114 #endif // JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H
void convertCvRectToJSKRectArray(const std::vector< cv::Rect_< int > > &, jsk_recognition_msgs::RectArray &, const int, const cv::Size)
std::string trainer_manifest_filename_
virtual void readTrainingManifestFromDirectory()
virtual void imageCb(const sensor_msgs::ImageConstPtr &)
virtual void loadTrainedDetectorModel()
SlidingWindowObjectDetector()
virtual void unsubscribe()
virtual void setBoundingBoxLabel(cv::Mat &, cv::Rect_< int >, const std::string="object")
virtual void computeHSHistogram(cv::Mat &, cv::Mat &, const int=64, const int=32, bool=true)
virtual void concatenateCVMat(const cv::Mat &, const cv::Mat &, cv::Mat &, bool=true)
boost::shared_ptr< cv::SVM > supportVectorMachine_
virtual std::vector< cv::Rect_< int > > nonMaximumSuppression(std::multimap< float, cv::Rect_< int > > &, const float)
std::string ndataset_path_
boost::shared_ptr< dynamic_reconfigure::Server< jsk_perception::SlidingWindowObjectDetectorConfig > > srv_
virtual std::multimap< float, cv::Rect_< int > > runSlidingWindowDetector(const cv::Mat &, const cv::Size, const float, const int, const int)
std::string nonobject_dataset_filename_
virtual void pyramidialScaling(cv::Size &, const float)
virtual void configCallback(jsk_perception::SlidingWindowObjectDetectorConfig &, uint32_t)
ros::Subscriber sub_image_
ros::Publisher pub_rects_
boost::shared_ptr< rosbag::Bag > rosbag_
std::string dataset_path_
ros::Publisher pub_image_
std::string object_dataset_filename_
virtual void objectRecognizer(const cv::Mat &, std::multimap< float, cv::Rect_< int > > &, const cv::Size, const int=16)
ros::ServiceClient nms_client_