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 <opencv2/core/core_c.h>
39 #include <opencv2/ml.hpp>
40 
41 #include <people_msgs/PositionMeasurement.h>
42 #include <sensor_msgs/LaserScan.h>
43 
44 #include <list>
45 #include <string>
46 #include <vector>
47 
49 
51 {
52 public:
55 
56  std::vector< std::vector<float> > pos_data_;
57  std::vector< std::vector<float> > neg_data_;
58  std::vector< std::vector<float> > test_data_;
59 
60  CvRTrees forest;
61 
63 
65 
67  {
68  }
69 
70  void loadData(LoadType load, char* file)
71  {
72  if (load != LOADING_NONE)
73  {
74  switch (load)
75  {
76  case LOADING_POS:
77  printf("Loading positive training data from file: %s\n", file);
78  break;
79  case LOADING_NEG:
80  printf("Loading negative training data from file: %s\n", file);
81  break;
82  case LOADING_TEST:
83  printf("Loading test data from file: %s\n", file);
84  break;
85  default:
86  break;
87  }
88 
89  ros::record::Player p;
90  if (p.open(file, ros::Time()))
91  {
92  mask_.clear();
93  mask_count_ = 0;
94 
95  switch (load)
96  {
97  case LOADING_POS:
98  p.addHandler<sensor_msgs::LaserScan>(std::string("*"), &TrainLegDetector::loadCb, this, &pos_data_);
99  break;
100  case LOADING_NEG:
101  mask_count_ = 1000; // effectively disable masking
102  p.addHandler<sensor_msgs::LaserScan>(std::string("*"), &TrainLegDetector::loadCb, this, &neg_data_);
103  break;
104  case LOADING_TEST:
105  p.addHandler<sensor_msgs::LaserScan>(std::string("*"), &TrainLegDetector::loadCb, this, &test_data_);
106  break;
107  default:
108  break;
109  }
110 
111  while (p.nextMsg())
112  {}
113  }
114  }
115  }
116 
117  void loadCb(std::string name, sensor_msgs::LaserScan* scan, ros::Time t, ros::Time t_no_use, void* n)
118  {
119  std::vector< std::vector<float> >* data = (std::vector< std::vector<float> >*)(n);
120 
121  if (mask_count_++ < 20)
122  {
123  mask_.addScan(*scan);
124  }
125  else
126  {
127  laser_processor::ScanProcessor processor(*scan, mask_);
129  processor.removeLessThan(5);
130 
131  for (std::list<laser_processor::SampleSet*>::iterator i = processor.getClusters().begin();
132  i != processor.getClusters().end();
133  i++)
134  data->push_back(calcLegFeatures(*i, *scan));
135  }
136  }
137 
138  void train()
139  {
140  int sample_size = pos_data_.size() + neg_data_.size();
141  feat_count_ = pos_data_[0].size();
142 
143  CvMat* cv_data = cvCreateMat(sample_size, feat_count_, CV_32FC1);
144  CvMat* cv_resp = cvCreateMat(sample_size, 1, CV_32S);
145 
146  // Put positive data in opencv format.
147  int j = 0;
148  for (std::vector< std::vector<float> >::iterator i = pos_data_.begin();
149  i != pos_data_.end();
150  i++)
151  {
152  float* data_row = reinterpret_cast<float*>(cv_data->data.ptr + cv_data->step * j);
153  for (int k = 0; k < feat_count_; k++)
154  data_row[k] = (*i)[k];
155 
156  cv_resp->data.i[j] = 1;
157  j++;
158  }
159 
160  // Put negative data in opencv format.
161  for (std::vector< std::vector<float> >::iterator i = neg_data_.begin();
162  i != neg_data_.end();
163  i++)
164  {
165  float* data_row = reinterpret_cast<float*>(cv_data->data.ptr + cv_data->step * j);
166  for (int k = 0; k < feat_count_; k++)
167  data_row[k] = (*i)[k];
168 
169  cv_resp->data.i[j] = -1;
170  j++;
171  }
172 
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);
176 
177  float priors[] = {1.0, 1.0};
178 
179  CvRTParams fparam(8, 20, 0, false, 10, priors, false, 5, 50, 0.001f, CV_TERMCRIT_ITER);
180  fparam.term_crit = cvTermCriteria(CV_TERMCRIT_ITER, 100, 0.1);
181 
182  forest.train(cv_data, CV_ROW_SAMPLE, cv_resp, 0, 0, var_type, 0,
183  fparam);
184 
185 
186  cvReleaseMat(&cv_data);
187  cvReleaseMat(&cv_resp);
188  cvReleaseMat(&var_type);
189  }
190 
191  void test()
192  {
193  CvMat* tmp_mat = cvCreateMat(1, feat_count_, CV_32FC1);
194 
195  int pos_right = 0;
196  int pos_total = 0;
197  for (std::vector< std::vector<float> >::iterator i = pos_data_.begin();
198  i != pos_data_.end();
199  i++)
200  {
201  for (int k = 0; k < feat_count_; k++)
202  tmp_mat->data.fl[k] = static_cast<float>((*i)[k]);
203  if (forest.predict(tmp_mat) > 0)
204  pos_right++;
205  pos_total++;
206  }
207 
208  int neg_right = 0;
209  int neg_total = 0;
210  for (std::vector< std::vector<float> >::iterator i = neg_data_.begin();
211  i != neg_data_.end();
212  i++)
213  {
214  for (int k = 0; k < feat_count_; k++)
215  tmp_mat->data.fl[k] = static_cast<float>((*i)[k]);
216  if (forest.predict(tmp_mat) < 0)
217  neg_right++;
218  neg_total++;
219  }
220 
221  int test_right = 0;
222  int test_total = 0;
223  for (std::vector< std::vector<float> >::iterator i = test_data_.begin();
224  i != test_data_.end();
225  i++)
226  {
227  for (int k = 0; k < feat_count_; k++)
228  tmp_mat->data.fl[k] = static_cast<float>((*i)[k]);
229  if (forest.predict(tmp_mat) > 0)
230  test_right++;
231  test_total++;
232  }
233 
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);
237 
238  cvReleaseMat(&tmp_mat);
239  }
240 
241  void save(char* file)
242  {
243  forest.save(file);
244  }
245 };
246 
247 int main(int argc, char **argv)
248 {
249  TrainLegDetector tld;
250 
251  LoadType loading = LOADING_NONE;
252 
253  char save_file[100];
254  save_file[0] = 0;
255 
256  printf("Loading data...\n");
257  for (int i = 1; i < argc; i++)
258  {
259  if (!strcmp(argv[i], "--train"))
260  loading = LOADING_POS;
261  else if (!strcmp(argv[i], "--neg"))
262  loading = LOADING_NEG;
263  else if (!strcmp(argv[i], "--test"))
264  loading = LOADING_TEST;
265  else if (!strcmp(argv[i], "--save"))
266  {
267  if (++i < argc)
268  strncpy(save_file, argv[i], 100);
269  continue;
270  }
271  else
272  tld.loadData(loading, argv[i]);
273  }
274 
275  printf("Training classifier...\n");
276  tld.train();
277 
278  printf("Evlauating classifier...\n");
279  tld.test();
280 
281  if (strlen(save_file) > 0)
282  {
283  printf("Saving classifier as: %s\n", save_file);
284  tld.save(save_file);
285  }
286 }
LOADING_POS
@ LOADING_POS
Definition: train_leg_detector.cpp:80
TrainLegDetector::connected_thresh_
float connected_thresh_
Definition: train_leg_detector.cpp:62
calc_leg_features.h
TrainLegDetector::forest
CvRTrees forest
Definition: train_leg_detector.cpp:60
LoadType
LoadType
Definition: train_leg_detector.cpp:48
laser_processor.h
TrainLegDetector::pos_data_
std::vector< std::vector< float > > pos_data_
Definition: train_leg_detector.cpp:56
TrainLegDetector::TrainLegDetector
TrainLegDetector()
Definition: train_leg_detector.cpp:66
f
f
laser_processor::ScanProcessor::splitConnected
void splitConnected(float thresh)
Definition: laser_processor.cpp:258
main
int main(int argc, char **argv)
Definition: train_leg_detector.cpp:247
calcLegFeatures
std::vector< float > calcLegFeatures(laser_processor::SampleSet *cluster, const sensor_msgs::LaserScan &scan)
Definition: calc_leg_features.cpp:42
TrainLegDetector::train
void train()
Definition: train_leg_detector.cpp:138
TrainLegDetector::test_data_
std::vector< std::vector< float > > test_data_
Definition: train_leg_detector.cpp:58
LOADING_NONE
@ LOADING_NONE
Definition: train_leg_detector.cpp:80
TrainLegDetector::loadData
void loadData(LoadType load, char *file)
Definition: train_leg_detector.cpp:70
TrainLegDetector::loadCb
void loadCb(std::string name, sensor_msgs::LaserScan *scan, ros::Time t, ros::Time t_no_use, void *n)
Definition: train_leg_detector.cpp:117
LOADING_NEG
@ LOADING_NEG
Definition: train_leg_detector.cpp:80
TrainLegDetector::mask_
laser_processor::ScanMask mask_
Definition: train_leg_detector.cpp:53
TrainLegDetector::save
void save(char *file)
Definition: train_leg_detector.cpp:241
laser_processor::ScanMask
A mask for filtering out Samples based on range.
Definition: laser_processor.h:134
laser_processor::ScanMask::addScan
void addScan(sensor_msgs::LaserScan &scan)
Definition: laser_processor.cpp:144
TrainLegDetector::mask_count_
int mask_count_
Definition: train_leg_detector.cpp:54
ros::Time
TrainLegDetector::neg_data_
std::vector< std::vector< float > > neg_data_
Definition: train_leg_detector.cpp:57
TrainLegDetector::test
void test()
Definition: train_leg_detector.cpp:191
TrainLegDetector
Definition: train_leg_detector.cpp:50
TrainLegDetector::feat_count_
int feat_count_
Definition: train_leg_detector.cpp:64
LOADING_TEST
@ LOADING_TEST
Definition: train_leg_detector.cpp:80
laser_processor::ScanMask::clear
void clear()
Definition: laser_processor.h:146
laser_processor::ScanProcessor::removeLessThan
void removeLessThan(uint32_t num)
Definition: laser_processor.cpp:239
laser_processor::ScanProcessor
Definition: laser_processor.h:159
laser_processor::ScanProcessor::getClusters
std::list< SampleSet * > & getClusters()
Definition: laser_processor.h:165


leg_detector
Author(s): Caroline Pantofaru
autogenerated on Wed Mar 2 2022 00:45:14