#include <random_forest.h>
Public Member Functions | |
| void | classifyCallback (const boost::shared_ptr< SensorPoint > &inst) |
| void | collectVotes (SensorPoint::Ptr inst, map< int, int > &class_votes) |
| void | createCovMat () |
| void | doMahalanobis () |
| void | growForest (vector< SensorPoint::Ptr > *c_dataset, vector< int > *inds, int c_num_trees=100) |
| void | growWriteForest () |
| void | loadCovMat () |
| void | loadDataBag (string &data_bag, int label) |
| void | loadDataset () |
| void | loadForest () |
| double | mahalanobisDist (LDLT< MatrixXd > *cov_inv, VectorXd &means, VectorXd &pt) |
| void | onInit () |
| RandomForest () | |
| void | randomPermuteData () |
| void | setDataset (vector< SensorPoint::Ptr > *datas) |
| void | variableImportance () |
| void | writeForest () |
| void | writeForest (string file) |
| ~RandomForest () | |
Static Public Member Functions | |
| static int | findFirstClass (vector< pair< map< int, int >, float > > *votes_list, int pos_id, float thresh) |
| static int | findFrequentClass (vector< pair< map< int, int >, float > > *votes_list, int pos_id, float thresh) |
| static void | runTenFold (vector< SensorPoint::Ptr > *train_test_data, int roc_id, int num_trees, vector< map< int, int > > &votes_total, bool classify_first=true) |
Protected Attributes | |
| int | classifier_id |
| string | classifier_name |
| ros::Subscriber | classify_sub |
| LDLT< MatrixXd > * | cov_inv |
| vector< SensorPoint::Ptr > * | dataset |
| bool | is_abs |
| vector< int > | labels |
| ros::Publisher | loaded_pub |
| VectorXd | means |
| ros::NodeHandle * | nh |
| ros::NodeHandle * | nh_priv |
| int | num_classes |
| int | num_trees |
| vector< vector< uint32_t > > | oobs |
| ros::Publisher | results_pub |
| boost::thread | setup_thread |
| RandomTree ** | trees |
| bool | trees_loaded |
Definition at line 77 of file random_forest.h.
| collision_detection::RandomForest::RandomForest | ( | ) | [inline] |
Definition at line 79 of file random_forest.h.
Definition at line 446 of file random_forest.cpp.
| void collision_detection::RandomForest::classifyCallback | ( | const boost::shared_ptr< SensorPoint > & | inst | ) |
Definition at line 632 of file random_forest.cpp.
| void collision_detection::RandomForest::collectVotes | ( | SensorPoint::Ptr | inst, |
| map< int, int > & | class_votes | ||
| ) |
Definition at line 619 of file random_forest.cpp.
Definition at line 572 of file random_forest.cpp.
Definition at line 1005 of file random_forest.cpp.
| int collision_detection::RandomForest::findFirstClass | ( | vector< pair< map< int, int >, float > > * | votes_list, |
| int | pos_id, | ||
| float | thresh | ||
| ) | [static] |
Definition at line 661 of file random_forest.cpp.
| int collision_detection::RandomForest::findFrequentClass | ( | vector< pair< map< int, int >, float > > * | votes_list, |
| int | pos_id, | ||
| float | thresh | ||
| ) | [static] |
Definition at line 686 of file random_forest.cpp.
| void collision_detection::RandomForest::growForest | ( | vector< SensorPoint::Ptr > * | c_dataset, |
| vector< int > * | inds, | ||
| int | c_num_trees = 100 |
||
| ) |
Definition at line 417 of file random_forest.cpp.
Definition at line 467 of file random_forest.cpp.
Definition at line 544 of file random_forest.cpp.
| void collision_detection::RandomForest::loadDataBag | ( | string & | data_bag, |
| int | label | ||
| ) |
Definition at line 396 of file random_forest.cpp.
Definition at line 383 of file random_forest.cpp.
Definition at line 517 of file random_forest.cpp.
| double collision_detection::RandomForest::mahalanobisDist | ( | LDLT< MatrixXd > * | cov_inv, |
| VectorXd & | means, | ||
| VectorXd & | pt | ||
| ) |
Definition at line 1001 of file random_forest.cpp.
Definition at line 1086 of file random_forest.cpp.
Definition at line 938 of file random_forest.cpp.
| void collision_detection::RandomForest::runTenFold | ( | vector< SensorPoint::Ptr > * | train_test_data, |
| int | roc_id, | ||
| int | num_trees, | ||
| vector< map< int, int > > & | votes_total, | ||
| bool | classify_first = true |
||
| ) | [static] |
Definition at line 717 of file random_forest.cpp.
| void collision_detection::RandomForest::setDataset | ( | vector< SensorPoint::Ptr > * | datas | ) |
Definition at line 413 of file random_forest.cpp.
Definition at line 890 of file random_forest.cpp.
Definition at line 451 of file random_forest.cpp.
| void collision_detection::RandomForest::writeForest | ( | string | file | ) |
Definition at line 457 of file random_forest.cpp.
int collision_detection::RandomForest::classifier_id [protected] |
Definition at line 119 of file random_forest.h.
string collision_detection::RandomForest::classifier_name [protected] |
Definition at line 118 of file random_forest.h.
Definition at line 127 of file random_forest.h.
LDLT<MatrixXd>* collision_detection::RandomForest::cov_inv [protected] |
Definition at line 123 of file random_forest.h.
vector< SensorPoint::Ptr >* collision_detection::RandomForest::dataset [protected] |
Definition at line 125 of file random_forest.h.
bool collision_detection::RandomForest::is_abs [protected] |
Definition at line 132 of file random_forest.h.
vector<int> collision_detection::RandomForest::labels [protected] |
Definition at line 126 of file random_forest.h.
Definition at line 129 of file random_forest.h.
VectorXd collision_detection::RandomForest::means [protected] |
Definition at line 124 of file random_forest.h.
ros::NodeHandle* collision_detection::RandomForest::nh [protected] |
Definition at line 114 of file random_forest.h.
Definition at line 115 of file random_forest.h.
int collision_detection::RandomForest::num_classes [protected] |
Definition at line 117 of file random_forest.h.
int collision_detection::RandomForest::num_trees [protected] |
Definition at line 117 of file random_forest.h.
vector<vector<uint32_t> > collision_detection::RandomForest::oobs [protected] |
Definition at line 122 of file random_forest.h.
Definition at line 128 of file random_forest.h.
boost::thread collision_detection::RandomForest::setup_thread [protected] |
Definition at line 130 of file random_forest.h.
RandomTree** collision_detection::RandomForest::trees [protected] |
Definition at line 121 of file random_forest.h.
bool collision_detection::RandomForest::trees_loaded [protected] |
Definition at line 131 of file random_forest.h.