38 #include <opencv2/core/core_c.h>
39 #include <opencv2/ml.hpp>
41 #include <people_msgs/PositionMeasurement.h>
42 #include <sensor_msgs/LaserScan.h>
77 printf(
"Loading positive training data from file: %s\n", file);
80 printf(
"Loading negative training data from file: %s\n", file);
83 printf(
"Loading test data from file: %s\n", file);
89 ros::record::Player p;
119 std::vector< std::vector<float> >* data = (std::vector< std::vector<float> >*)(n);
131 for (std::list<laser_processor::SampleSet*>::iterator i = processor.
getClusters().begin();
143 CvMat* cv_data = cvCreateMat(sample_size,
feat_count_, CV_32FC1);
144 CvMat* cv_resp = cvCreateMat(sample_size, 1, CV_32S);
148 for (std::vector< std::vector<float> >::iterator i =
pos_data_.begin();
152 float* data_row =
reinterpret_cast<float*
>(cv_data->data.ptr + cv_data->step * j);
154 data_row[k] = (*i)[k];
156 cv_resp->data.i[j] = 1;
161 for (std::vector< std::vector<float> >::iterator i =
neg_data_.begin();
165 float* data_row =
reinterpret_cast<float*
>(cv_data->data.ptr + cv_data->step * j);
167 data_row[k] = (*i)[k];
169 cv_resp->data.i[j] = -1;
173 CvMat* var_type = cvCreateMat(1,
feat_count_ + 1, CV_8U);
174 cvSet(var_type, cvScalarAll(CV_VAR_ORDERED));
175 cvSetReal1D(var_type,
feat_count_, CV_VAR_CATEGORICAL);
177 float priors[] = {1.0, 1.0};
179 CvRTParams fparam(8, 20, 0,
false, 10, priors,
false, 5, 50, 0.001
f, CV_TERMCRIT_ITER);
180 fparam.term_crit = cvTermCriteria(CV_TERMCRIT_ITER, 100, 0.1);
182 forest.train(cv_data, CV_ROW_SAMPLE, cv_resp, 0, 0, var_type, 0,
186 cvReleaseMat(&cv_data);
187 cvReleaseMat(&cv_resp);
188 cvReleaseMat(&var_type);
193 CvMat* tmp_mat = cvCreateMat(1,
feat_count_, CV_32FC1);
197 for (std::vector< std::vector<float> >::iterator i =
pos_data_.begin();
202 tmp_mat->data.fl[k] =
static_cast<float>((*i)[k]);
203 if (
forest.predict(tmp_mat) > 0)
210 for (std::vector< std::vector<float> >::iterator i =
neg_data_.begin();
215 tmp_mat->data.fl[k] =
static_cast<float>((*i)[k]);
216 if (
forest.predict(tmp_mat) < 0)
223 for (std::vector< std::vector<float> >::iterator i =
test_data_.begin();
228 tmp_mat->data.fl[k] =
static_cast<float>((*i)[k]);
229 if (
forest.predict(tmp_mat) > 0)
234 printf(
" Pos train set: %d/%d %g\n", pos_right, pos_total,
static_cast<float>(pos_right) / pos_total);
235 printf(
" Neg train set: %d/%d %g\n", neg_right, neg_total,
static_cast<float>(neg_right) / neg_total);
236 printf(
" Test set: %d/%d %g\n", test_right, test_total,
static_cast<float>(test_right) / test_total);
238 cvReleaseMat(&tmp_mat);
247 int main(
int argc,
char **argv)
256 printf(
"Loading data...\n");
257 for (
int i = 1; i < argc; i++)
259 if (!strcmp(argv[i],
"--train"))
261 else if (!strcmp(argv[i],
"--neg"))
263 else if (!strcmp(argv[i],
"--test"))
265 else if (!strcmp(argv[i],
"--save"))
268 strncpy(save_file, argv[i], 100);
275 printf(
"Training classifier...\n");
278 printf(
"Evlauating classifier...\n");
281 if (strlen(save_file) > 0)
283 printf(
"Saving classifier as: %s\n", save_file);