Go to the documentation of this file.
    3 #ifndef JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H 
    4 #define JSK_PERCEPTION_SLIDING_WINDOW_OBJECT_DETECTOR_H 
    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> 
   12 #include <pcl/point_types.h> 
   19 #include <boost/foreach.hpp> 
   24 #include <sensor_msgs/PointCloud2.h> 
   25 #include <dynamic_reconfigure/server.h> 
   42          DiagnosticNodelet(
"SlidingWindowObjectDetector") {}
 
   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 
  
SlidingWindowObjectDetector()
std::string ndataset_path_
std::string dataset_path_
virtual void setBoundingBoxLabel(cv::Mat &, cv::Rect_< int >, const std::string="object")
std::string object_dataset_filename_
virtual void objectRecognizer(const cv::Mat &, std::multimap< float, cv::Rect_< int > > &, const cv::Size, const int=16)
boost::shared_ptr< cv::SVM > supportVectorMachine_
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)
ros::ServiceClient nms_client_
std::string nonobject_dataset_filename_
ros::Publisher pub_image_
boost::shared_ptr< rosbag::Bag > rosbag_
virtual void readTrainingManifestFromDirectory()
virtual void imageCb(const sensor_msgs::ImageConstPtr &)
virtual void computeHSHistogram(cv::Mat &, cv::Mat &, const int=64, const int=32, bool=true)
std::string trainer_manifest_filename_
void convertCvRectToJSKRectArray(const std::vector< cv::Rect_< int > > &, jsk_recognition_msgs::RectArray &, const int, const cv::Size)
virtual void configCallback(jsk_perception::SlidingWindowObjectDetectorConfig &, uint32_t)
virtual std::vector< cv::Rect_< int > > nonMaximumSuppression(std::multimap< float, cv::Rect_< int > > &, const float)
virtual void unsubscribe()
virtual void pyramidialScaling(cv::Size &, const float)
ros::Publisher pub_rects_
ros::Subscriber sub_image_
virtual void loadTrainedDetectorModel()
virtual void concatenateCVMat(const cv::Mat &, const cv::Mat &, cv::Mat &, bool=true)
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda 
autogenerated on Fri May 16 2025 03:11:17