train_leg_detector.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
37 
38 #include <opencv/cxcore.h>
39 #include <opencv/cv.h>
40 #include <opencv/ml.h>
41 
42 #include <people_msgs/PositionMeasurement.h>
43 #include <sensor_msgs/LaserScan.h>
44 
45 #include <list>
46 #include <string>
47 #include <vector>
48 
50 
52 {
53 public:
56 
57  std::vector< std::vector<float> > pos_data_;
58  std::vector< std::vector<float> > neg_data_;
59  std::vector< std::vector<float> > test_data_;
60 
61  CvRTrees forest;
62 
64 
66 
67  TrainLegDetector() : mask_count_(0), connected_thresh_(0.06), feat_count_(0)
68  {
69  }
70 
71  void loadData(LoadType load, char* file)
72  {
73  if (load != LOADING_NONE)
74  {
75  switch (load)
76  {
77  case LOADING_POS:
78  printf("Loading positive training data from file: %s\n", file);
79  break;
80  case LOADING_NEG:
81  printf("Loading negative training data from file: %s\n", file);
82  break;
83  case LOADING_TEST:
84  printf("Loading test data from file: %s\n", file);
85  break;
86  default:
87  break;
88  }
89 
90  ros::record::Player p;
91  if (p.open(file, ros::Time()))
92  {
93  mask_.clear();
94  mask_count_ = 0;
95 
96  switch (load)
97  {
98  case LOADING_POS:
99  p.addHandler<sensor_msgs::LaserScan>(std::string("*"), &TrainLegDetector::loadCb, this, &pos_data_);
100  break;
101  case LOADING_NEG:
102  mask_count_ = 1000; // effectively disable masking
103  p.addHandler<sensor_msgs::LaserScan>(std::string("*"), &TrainLegDetector::loadCb, this, &neg_data_);
104  break;
105  case LOADING_TEST:
106  p.addHandler<sensor_msgs::LaserScan>(std::string("*"), &TrainLegDetector::loadCb, this, &test_data_);
107  break;
108  default:
109  break;
110  }
111 
112  while (p.nextMsg())
113  {}
114  }
115  }
116  }
117 
118  void loadCb(std::string name, sensor_msgs::LaserScan* scan, ros::Time t, ros::Time t_no_use, void* n)
119  {
120  std::vector< std::vector<float> >* data = (std::vector< std::vector<float> >*)(n);
121 
122  if (mask_count_++ < 20)
123  {
124  mask_.addScan(*scan);
125  }
126  else
127  {
128  laser_processor::ScanProcessor processor(*scan, mask_);
129  processor.splitConnected(connected_thresh_);
130  processor.removeLessThan(5);
131 
132  for (std::list<laser_processor::SampleSet*>::iterator i = processor.getClusters().begin();
133  i != processor.getClusters().end();
134  i++)
135  data->push_back(calcLegFeatures(*i, *scan));
136  }
137  }
138 
139  void train()
140  {
141  int sample_size = pos_data_.size() + neg_data_.size();
142  feat_count_ = pos_data_[0].size();
143 
144  CvMat* cv_data = cvCreateMat(sample_size, feat_count_, CV_32FC1);
145  CvMat* cv_resp = cvCreateMat(sample_size, 1, CV_32S);
146 
147  // Put positive data in opencv format.
148  int j = 0;
149  for (std::vector< std::vector<float> >::iterator i = pos_data_.begin();
150  i != pos_data_.end();
151  i++)
152  {
153  float* data_row = reinterpret_cast<float*>(cv_data->data.ptr + cv_data->step * j);
154  for (int k = 0; k < feat_count_; k++)
155  data_row[k] = (*i)[k];
156 
157  cv_resp->data.i[j] = 1;
158  j++;
159  }
160 
161  // Put negative data in opencv format.
162  for (std::vector< std::vector<float> >::iterator i = neg_data_.begin();
163  i != neg_data_.end();
164  i++)
165  {
166  float* data_row = reinterpret_cast<float*>(cv_data->data.ptr + cv_data->step * j);
167  for (int k = 0; k < feat_count_; k++)
168  data_row[k] = (*i)[k];
169 
170  cv_resp->data.i[j] = -1;
171  j++;
172  }
173 
174  CvMat* var_type = cvCreateMat(1, feat_count_ + 1, CV_8U);
175  cvSet(var_type, cvScalarAll(CV_VAR_ORDERED));
176  cvSetReal1D(var_type, feat_count_, CV_VAR_CATEGORICAL);
177 
178  float priors[] = {1.0, 1.0};
179 
180  CvRTParams fparam(8, 20, 0, false, 10, priors, false, 5, 50, 0.001f, CV_TERMCRIT_ITER);
181  fparam.term_crit = cvTermCriteria(CV_TERMCRIT_ITER, 100, 0.1);
182 
183  forest.train(cv_data, CV_ROW_SAMPLE, cv_resp, 0, 0, var_type, 0,
184  fparam);
185 
186 
187  cvReleaseMat(&cv_data);
188  cvReleaseMat(&cv_resp);
189  cvReleaseMat(&var_type);
190  }
191 
192  void test()
193  {
194  CvMat* tmp_mat = cvCreateMat(1, feat_count_, CV_32FC1);
195 
196  int pos_right = 0;
197  int pos_total = 0;
198  for (std::vector< std::vector<float> >::iterator i = pos_data_.begin();
199  i != pos_data_.end();
200  i++)
201  {
202  for (int k = 0; k < feat_count_; k++)
203  tmp_mat->data.fl[k] = static_cast<float>((*i)[k]);
204  if (forest.predict(tmp_mat) > 0)
205  pos_right++;
206  pos_total++;
207  }
208 
209  int neg_right = 0;
210  int neg_total = 0;
211  for (std::vector< std::vector<float> >::iterator i = neg_data_.begin();
212  i != neg_data_.end();
213  i++)
214  {
215  for (int k = 0; k < feat_count_; k++)
216  tmp_mat->data.fl[k] = static_cast<float>((*i)[k]);
217  if (forest.predict(tmp_mat) < 0)
218  neg_right++;
219  neg_total++;
220  }
221 
222  int test_right = 0;
223  int test_total = 0;
224  for (std::vector< std::vector<float> >::iterator i = test_data_.begin();
225  i != test_data_.end();
226  i++)
227  {
228  for (int k = 0; k < feat_count_; k++)
229  tmp_mat->data.fl[k] = static_cast<float>((*i)[k]);
230  if (forest.predict(tmp_mat) > 0)
231  test_right++;
232  test_total++;
233  }
234 
235  printf(" Pos train set: %d/%d %g\n", pos_right, pos_total, static_cast<float>(pos_right) / pos_total);
236  printf(" Neg train set: %d/%d %g\n", neg_right, neg_total, static_cast<float>(neg_right) / neg_total);
237  printf(" Test set: %d/%d %g\n", test_right, test_total, static_cast<float>(test_right) / test_total);
238 
239  cvReleaseMat(&tmp_mat);
240  }
241 
242  void save(char* file)
243  {
244  forest.save(file);
245  }
246 };
247 
248 int main(int argc, char **argv)
249 {
250  TrainLegDetector tld;
251 
252  LoadType loading = LOADING_NONE;
253 
254  char save_file[100];
255  save_file[0] = 0;
256 
257  printf("Loading data...\n");
258  for (int i = 1; i < argc; i++)
259  {
260  if (!strcmp(argv[i], "--train"))
261  loading = LOADING_POS;
262  else if (!strcmp(argv[i], "--neg"))
263  loading = LOADING_NEG;
264  else if (!strcmp(argv[i], "--test"))
265  loading = LOADING_TEST;
266  else if (!strcmp(argv[i], "--save"))
267  {
268  if (++i < argc)
269  strncpy(save_file, argv[i], 100);
270  continue;
271  }
272  else
273  tld.loadData(loading, argv[i]);
274  }
275 
276  printf("Training classifier...\n");
277  tld.train();
278 
279  printf("Evlauating classifier...\n");
280  tld.test();
281 
282  if (strlen(save_file) > 0)
283  {
284  printf("Saving classifier as: %s\n", save_file);
285  tld.save(save_file);
286  }
287 }
f
std::vector< std::vector< float > > test_data_
std::vector< std::vector< float > > neg_data_
std::vector< float > calcLegFeatures(laser_processor::SampleSet *cluster, const sensor_msgs::LaserScan &scan)
void loadCb(std::string name, sensor_msgs::LaserScan *scan, ros::Time t, ros::Time t_no_use, void *n)
laser_processor::ScanMask mask_
void save(char *file)
std::list< SampleSet * > & getClusters()
int main(int argc, char **argv)
void loadData(LoadType load, char *file)
A mask for filtering out Samples based on range.
void addScan(sensor_msgs::LaserScan &scan)
std::vector< std::vector< float > > pos_data_


leg_detector
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:50