#include <sliding_window_object_detector_trainer.h>

Public Member Functions | |
| virtual void | computeHSHistogram (cv::Mat &, cv::Mat &, const int=64, const int=32, bool=true) |
| virtual void | extractFeatures (cv::Mat &, cv::Mat &) |
| virtual void | readDataset (std::string, std::string, cv::Mat &, cv::Mat &, bool=false, const int=0) |
| SlidingWindowObjectDetectorTrainer () | |
| virtual void | trainBinaryClassSVM (const cv::Mat &, const cv::Mat &) |
| virtual void | trainObjectClassifier (std::string, std::string) |
Private Member Functions | |
| virtual void | concatenateCVMat (const cv::Mat &, const cv::Mat &, cv::Mat &, bool=true) |
| void | writeTrainingManifestToDirectory (cv::FileStorage &) |
Private Attributes | |
| std::string | dataset_path_ |
| int | hist_hbin_ |
| int | hist_sbin_ |
| ros::NodeHandle | nh_ |
| std::string | nonobject_dataset_filename_ |
| std::string | object_dataset_filename_ |
| boost::shared_ptr< rosbag::Bag > | rosbag_ |
| boost::shared_ptr< cv::SVM > | supportVectorMachine_ |
| int | swindow_x_ |
| int | swindow_y_ |
| std::string | trained_classifier_name_ |
Definition at line 26 of file sliding_window_object_detector_trainer.h.
Definition at line 7 of file sliding_window_object_detector_trainer_node.cpp.
| void jsk_perception::SlidingWindowObjectDetectorTrainer::computeHSHistogram | ( | cv::Mat & | src, |
| cv::Mat & | hist, | ||
| const int | hBin = 64, |
||
| const int | sBin = 32, |
||
| bool | is_norm = true |
||
| ) | [virtual] |
Definition at line 237 of file sliding_window_object_detector_trainer_node.cpp.
| void jsk_perception::SlidingWindowObjectDetectorTrainer::concatenateCVMat | ( | const cv::Mat & | mat_1, |
| const cv::Mat & | mat_2, | ||
| cv::Mat & | featureMD, | ||
| bool | iscolwise = true |
||
| ) | [private, virtual] |
Definition at line 182 of file sliding_window_object_detector_trainer_node.cpp.
| void jsk_perception::SlidingWindowObjectDetectorTrainer::extractFeatures | ( | cv::Mat & | img, |
| cv::Mat & | featureMD | ||
| ) | [virtual] |
currently programmed using fixed sized image
Definition at line 100 of file sliding_window_object_detector_trainer_node.cpp.
| void jsk_perception::SlidingWindowObjectDetectorTrainer::readDataset | ( | std::string | filename, |
| std::string | topic_name, | ||
| cv::Mat & | featureMD, | ||
| cv::Mat & | labelMD, | ||
| bool | is_usr_label = false, |
||
| const int | usr_label = 0 |
||
| ) | [virtual] |
Definition at line 62 of file sliding_window_object_detector_trainer_node.cpp.
| void jsk_perception::SlidingWindowObjectDetectorTrainer::trainBinaryClassSVM | ( | const cv::Mat & | featureMD, |
| const cv::Mat & | labelMD | ||
| ) | [virtual] |
Definition at line 117 of file sliding_window_object_detector_trainer_node.cpp.
| void jsk_perception::SlidingWindowObjectDetectorTrainer::trainObjectClassifier | ( | std::string | pfilename, |
| std::string | nfilename | ||
| ) | [virtual] |
Definition at line 39 of file sliding_window_object_detector_trainer_node.cpp.
| void jsk_perception::SlidingWindowObjectDetectorTrainer::writeTrainingManifestToDirectory | ( | cv::FileStorage & | fs | ) | [private] |
Definition at line 209 of file sliding_window_object_detector_trainer_node.cpp.
Definition at line 37 of file sliding_window_object_detector_trainer.h.
Definition at line 34 of file sliding_window_object_detector_trainer.h.
Definition at line 35 of file sliding_window_object_detector_trainer.h.
Definition at line 30 of file sliding_window_object_detector_trainer.h.
std::string jsk_perception::SlidingWindowObjectDetectorTrainer::nonobject_dataset_filename_ [private] |
Definition at line 40 of file sliding_window_object_detector_trainer.h.
Definition at line 39 of file sliding_window_object_detector_trainer.h.
boost::shared_ptr<rosbag::Bag> jsk_perception::SlidingWindowObjectDetectorTrainer::rosbag_ [private] |
Definition at line 43 of file sliding_window_object_detector_trainer.h.
boost::shared_ptr<cv::SVM> jsk_perception::SlidingWindowObjectDetectorTrainer::supportVectorMachine_ [private] |
Definition at line 47 of file sliding_window_object_detector_trainer.h.
Definition at line 32 of file sliding_window_object_detector_trainer.h.
Definition at line 33 of file sliding_window_object_detector_trainer.h.
Definition at line 41 of file sliding_window_object_detector_trainer.h.