calc_leg_features.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 
36 
37 #include <opencv/cxcore.h>
38 #include <opencv/cv.h>
39 #include <algorithm>
40 #include <vector>
41 
42 std::vector<float> calcLegFeatures(laser_processor::SampleSet* cluster, const sensor_msgs::LaserScan& scan)
43 {
44  std::vector<float> features;
45 
46  // Number of points
47  int num_points = cluster->size();
48  // features.push_back(num_points);
49 
50  // Compute mean and median points for future use
51  float x_mean = 0.0;
52  float y_mean = 0.0;
53  std::vector<float> x_median_set;
54  std::vector<float> y_median_set;
55  for (laser_processor::SampleSet::iterator i = cluster->begin();
56  i != cluster->end();
57  i++)
58 
59  {
60  x_mean += ((*i)->x) / num_points;
61  y_mean += ((*i)->y) / num_points;
62  x_median_set.push_back((*i)->x);
63  y_median_set.push_back((*i)->y);
64  }
65 
66  std::sort(x_median_set.begin(), x_median_set.end());
67  std::sort(y_median_set.begin(), y_median_set.end());
68 
69  float x_median = 0.5 * (*(x_median_set.begin() + (num_points - 1) / 2) + * (x_median_set.begin() + num_points / 2));
70  float y_median = 0.5 * (*(y_median_set.begin() + (num_points - 1) / 2) + * (y_median_set.begin() + num_points / 2));
71 
72  // Compute std and avg diff from median
73 
74  double sum_std_diff = 0.0;
75  double sum_med_diff = 0.0;
76 
77 
78  for (laser_processor::SampleSet::iterator i = cluster->begin();
79  i != cluster->end();
80  i++)
81 
82  {
83  sum_std_diff += pow((*i)->x - x_mean, 2) + pow((*i)->y - y_mean, 2);
84  sum_med_diff += sqrt(pow((*i)->x - x_median, 2) + pow((*i)->y - y_median, 2));
85  }
86 
87  float std = sqrt(1.0 / (num_points - 1.0) * sum_std_diff);
88  float avg_median_dev = sum_med_diff / num_points;
89 
90  features.push_back(std);
91  features.push_back(avg_median_dev);
92 
93 
94  // Take first at last
95  laser_processor::SampleSet::iterator first = cluster->begin();
96  laser_processor::SampleSet::iterator last = cluster->end();
97  last--;
98 
99  // Compute Jump distance
100  int prev_ind = (*first)->index - 1;
101  int next_ind = (*last)->index + 1;
102 
103  float prev_jump = 0;
104  float next_jump = 0;
105 
106  if (prev_ind >= 0)
107  {
109  if (prev)
110  {
111  prev_jump = sqrt(pow((*first)->x - prev->x, 2) + pow((*first)->y - prev->y, 2));
112  delete prev;
113  }
114  }
115 
116  if (next_ind < static_cast<int>(scan.ranges.size()))
117  {
119  if (next)
120  {
121  next_jump = sqrt(pow((*last)->x - next->x, 2) + pow((*last)->y - next->y, 2));
122  delete next;
123  }
124  }
125 
126  features.push_back(prev_jump);
127  features.push_back(next_jump);
128 
129  // Compute Width
130  float width = sqrt(pow((*first)->x - (*last)->x, 2) + pow((*first)->y - (*last)->y, 2));
131  features.push_back(width);
132 
133  // Compute Linearity
134 
135  CvMat* points = cvCreateMat(num_points, 2, CV_64FC1);
136  {
137  int j = 0;
138  for (laser_processor::SampleSet::iterator i = cluster->begin();
139  i != cluster->end();
140  i++)
141  {
142  cvmSet(points, j, 0, (*i)->x - x_mean);
143  cvmSet(points, j, 1, (*i)->y - y_mean);
144  j++;
145  }
146  }
147 
148  CvMat* W = cvCreateMat(2, 2, CV_64FC1);
149  CvMat* U = cvCreateMat(num_points, 2, CV_64FC1);
150  CvMat* V = cvCreateMat(2, 2, CV_64FC1);
151  cvSVD(points, W, U, V);
152 
153  CvMat* rot_points = cvCreateMat(num_points, 2, CV_64FC1);
154  cvMatMul(U, W, rot_points);
155 
156  float linearity = 0.0;
157  for (int i = 0; i < num_points; i++)
158  {
159  linearity += pow(cvmGet(rot_points, i, 1), 2);
160  }
161 
162  cvReleaseMat(&points);
163  points = 0;
164  cvReleaseMat(&W);
165  W = 0;
166  cvReleaseMat(&U);
167  U = 0;
168  cvReleaseMat(&V);
169  V = 0;
170  cvReleaseMat(&rot_points);
171  rot_points = 0;
172 
173  features.push_back(linearity);
174 
175  // Compute Circularity
176  CvMat* A = cvCreateMat(num_points, 3, CV_64FC1);
177  CvMat* B = cvCreateMat(num_points, 1, CV_64FC1);
178  {
179  int j = 0;
180  for (laser_processor::SampleSet::iterator i = cluster->begin();
181  i != cluster->end();
182  i++)
183  {
184  float x = (*i)->x;
185  float y = (*i)->y;
186 
187  cvmSet(A, j, 0, -2.0 * x);
188  cvmSet(A, j, 1, -2.0 * y);
189  cvmSet(A, j, 2, 1);
190 
191  cvmSet(B, j, 0, -pow(x, 2) - pow(y, 2));
192  j++;
193  }
194  }
195  CvMat* sol = cvCreateMat(3, 1, CV_64FC1);
196 
197  cvSolve(A, B, sol, CV_SVD);
198 
199  float xc = cvmGet(sol, 0, 0);
200  float yc = cvmGet(sol, 1, 0);
201  float rc = sqrt(pow(xc, 2) + pow(yc, 2) - cvmGet(sol, 2, 0));
202 
203  cvReleaseMat(&A);
204  A = 0;
205  cvReleaseMat(&B);
206  B = 0;
207  cvReleaseMat(&sol);
208  sol = 0;
209 
210  float circularity = 0.0;
211  for (laser_processor::SampleSet::iterator i = cluster->begin();
212  i != cluster->end();
213  i++)
214  {
215  circularity += pow(rc - sqrt(pow(xc - (*i)->x, 2) + pow(yc - (*i)->y, 2)), 2);
216  }
217 
218  features.push_back(circularity);
219 
220  // Radius
221  float radius = rc;
222 
223  features.push_back(radius);
224 
225  // Curvature:
226  float mean_curvature = 0.0;
227 
228  // Boundary length:
229  float boundary_length = 0.0;
230  float last_boundary_seg = 0.0;
231 
232  float boundary_regularity = 0.0;
233  double sum_boundary_reg_sq = 0.0;
234 
235  // Mean angular difference
236  laser_processor::SampleSet::iterator left = cluster->begin();
237  left++;
238  left++;
239  laser_processor::SampleSet::iterator mid = cluster->begin();
240  mid++;
241  laser_processor::SampleSet::iterator right = cluster->begin();
242 
243  float ang_diff = 0.0;
244 
245  while (left != cluster->end())
246  {
247  float mlx = (*left)->x - (*mid)->x;
248  float mly = (*left)->y - (*mid)->y;
249  float L_ml = sqrt(mlx * mlx + mly * mly);
250 
251  float mrx = (*right)->x - (*mid)->x;
252  float mry = (*right)->y - (*mid)->y;
253  float L_mr = sqrt(mrx * mrx + mry * mry);
254 
255  float lrx = (*left)->x - (*right)->x;
256  float lry = (*left)->y - (*right)->y;
257  float L_lr = sqrt(lrx * lrx + lry * lry);
258 
259  boundary_length += L_mr;
260  sum_boundary_reg_sq += L_mr * L_mr;
261  last_boundary_seg = L_ml;
262 
263  float A = (mlx * mrx + mly * mry) / pow(L_mr, 2);
264  float B = (mlx * mry - mly * mrx) / pow(L_mr, 2);
265 
266  float th = atan2(B, A);
267 
268  if (th < 0)
269  th += 2 * M_PI;
270 
271  ang_diff += th / num_points;
272 
273  float s = 0.5 * (L_ml + L_mr + L_lr);
274  float area = sqrt(s * (s - L_ml) * (s - L_mr) * (s - L_lr));
275 
276  if (th > 0)
277  mean_curvature += 4 * (area) / (L_ml * L_mr * L_lr * num_points);
278  else
279  mean_curvature -= 4 * (area) / (L_ml * L_mr * L_lr * num_points);
280 
281  left++;
282  mid++;
283  right++;
284  }
285 
286  boundary_length += last_boundary_seg;
287  sum_boundary_reg_sq += last_boundary_seg * last_boundary_seg;
288 
289  boundary_regularity = sqrt((sum_boundary_reg_sq - pow(boundary_length, 2) / num_points) / (num_points - 1));
290 
291  features.push_back(boundary_length);
292  features.push_back(ang_diff);
293  features.push_back(mean_curvature);
294 
295  features.push_back(boundary_regularity);
296 
297 
298  // Mean angular difference
299  first = cluster->begin();
300  mid = cluster->begin();
301  mid++;
302  last = cluster->end();
303  last--;
304 
305  double sum_iav = 0.0;
306  double sum_iav_sq = 0.0;
307 
308  while (mid != last)
309  {
310  float mlx = (*first)->x - (*mid)->x;
311  float mly = (*first)->y - (*mid)->y;
312  // float L_ml = sqrt(mlx*mlx + mly*mly);
313 
314  float mrx = (*last)->x - (*mid)->x;
315  float mry = (*last)->y - (*mid)->y;
316  float L_mr = sqrt(mrx * mrx + mry * mry);
317 
318  // float lrx = (*first)->x - (*last)->x;
319  // float lry = (*first)->y - (*last)->y;
320  // float L_lr = sqrt(lrx*lrx + lry*lry);
321 
322  float A = (mlx * mrx + mly * mry) / pow(L_mr, 2);
323  float B = (mlx * mry - mly * mrx) / pow(L_mr, 2);
324 
325  float th = atan2(B, A);
326 
327  if (th < 0)
328  th += 2 * M_PI;
329 
330  sum_iav += th;
331  sum_iav_sq += th * th;
332 
333  mid++;
334  }
335 
336  float iav = sum_iav / num_points;
337  float std_iav = sqrt((sum_iav_sq - pow(sum_iav, 2) / num_points) / (num_points - 1));
338 
339  features.push_back(iav);
340  features.push_back(std_iav);
341 
342  return features;
343 }
344 
XmlRpcServer s
TFSIMD_FORCE_INLINE const tfScalar & y() const
static Sample * Extract(int ind, const sensor_msgs::LaserScan &scan)
#define M_PI
An ordered set of Samples.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
x
A struct representing a single sample from the laser.
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
std::vector< float > calcLegFeatures(laser_processor::SampleSet *cluster, const sensor_msgs::LaserScan &scan)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)


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