| Public Member Functions | |
| void | loadBackground (sensor_msgs::LaserScan *scan) | 
| void | loadCb (sensor_msgs::LaserScan *scan, vector< vector< float > > *data) | 
| void | loadCbBackgroundremoved (sensor_msgs::LaserScan *scan, vector< vector< float > > *data) | 
| void | loadData (LoadType load, char *file) | 
| void | save (char *file) | 
| void | test () | 
| void | traincl () | 
| TrainLegDetector () | |
| Public Attributes | |
| Background | background_ | 
| float | connected_thresh_ | 
| int | feat_count_ | 
| CvRTrees | forest | 
| ScanMask | mask_ | 
| int | mask_count_ | 
| vector< vector< float > > | neg_data_ | 
| vector< vector< float > > | pos_data_ | 
| vector< vector< float > > | test_data_ | 
Definition at line 61 of file train_leg_detector.cpp.
| TrainLegDetector::TrainLegDetector | ( | ) |  [inline] | 
Definition at line 79 of file train_leg_detector.cpp.
| void TrainLegDetector::loadBackground | ( | sensor_msgs::LaserScan * | scan | ) |  [inline] | 
Definition at line 159 of file train_leg_detector.cpp.
| void TrainLegDetector::loadCb | ( | sensor_msgs::LaserScan * | scan, | 
| vector< vector< float > > * | data | ||
| ) |  [inline] | 
Definition at line 165 of file train_leg_detector.cpp.
| void TrainLegDetector::loadCbBackgroundremoved | ( | sensor_msgs::LaserScan * | scan, | 
| vector< vector< float > > * | data | ||
| ) |  [inline] | 
Definition at line 186 of file train_leg_detector.cpp.
| void TrainLegDetector::loadData | ( | LoadType | load, | 
| char * | file | ||
| ) |  [inline] | 
Definition at line 83 of file train_leg_detector.cpp.
| void TrainLegDetector::save | ( | char * | file | ) |  [inline] | 
Definition at line 330 of file train_leg_detector.cpp.
| void TrainLegDetector::test | ( | ) |  [inline] | 
Definition at line 279 of file train_leg_detector.cpp.
| void TrainLegDetector::traincl | ( | ) |  [inline] | 
Definition at line 208 of file train_leg_detector.cpp.
Definition at line 65 of file train_leg_detector.cpp.
Definition at line 75 of file train_leg_detector.cpp.
Definition at line 77 of file train_leg_detector.cpp.
| CvRTrees TrainLegDetector::forest | 
Definition at line 73 of file train_leg_detector.cpp.
Definition at line 64 of file train_leg_detector.cpp.
Definition at line 67 of file train_leg_detector.cpp.
| vector< vector<float> > TrainLegDetector::neg_data_ | 
Definition at line 70 of file train_leg_detector.cpp.
| vector< vector<float> > TrainLegDetector::pos_data_ | 
Definition at line 69 of file train_leg_detector.cpp.
| vector< vector<float> > TrainLegDetector::test_data_ | 
Definition at line 71 of file train_leg_detector.cpp.