37 #include <opencv/cxcore.h> 38 #include <opencv/cv.h> 44 std::vector<float> features;
47 int num_points = cluster->size();
53 std::vector<float> x_median_set;
54 std::vector<float> y_median_set;
55 for (laser_processor::SampleSet::iterator i = cluster->begin();
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);
66 std::sort(x_median_set.begin(), x_median_set.end());
67 std::sort(y_median_set.begin(), y_median_set.end());
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));
74 double sum_std_diff = 0.0;
75 double sum_med_diff = 0.0;
78 for (laser_processor::SampleSet::iterator i = cluster->begin();
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));
87 float std =
sqrt(1.0 / (num_points - 1.0) * sum_std_diff);
88 float avg_median_dev = sum_med_diff / num_points;
90 features.push_back(std);
91 features.push_back(avg_median_dev);
95 laser_processor::SampleSet::iterator first = cluster->begin();
96 laser_processor::SampleSet::iterator last = cluster->end();
100 int prev_ind = (*first)->index - 1;
101 int next_ind = (*last)->index + 1;
111 prev_jump =
sqrt(
pow((*first)->x - prev->
x, 2) +
pow((*first)->y - prev->
y, 2));
116 if (next_ind < static_cast<int>(scan.ranges.size()))
121 next_jump =
sqrt(
pow((*last)->x - next->
x, 2) +
pow((*last)->y - next->
y, 2));
126 features.push_back(prev_jump);
127 features.push_back(next_jump);
130 float width =
sqrt(
pow((*first)->x - (*last)->x, 2) +
pow((*first)->y - (*last)->y, 2));
131 features.push_back(width);
135 CvMat* points = cvCreateMat(num_points, 2, CV_64FC1);
138 for (laser_processor::SampleSet::iterator i = cluster->begin();
142 cvmSet(points, j, 0, (*i)->x - x_mean);
143 cvmSet(points, j, 1, (*i)->y - y_mean);
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);
153 CvMat* rot_points = cvCreateMat(num_points, 2, CV_64FC1);
154 cvMatMul(U, W, rot_points);
156 float linearity = 0.0;
157 for (
int i = 0; i < num_points; i++)
159 linearity +=
pow(cvmGet(rot_points, i, 1), 2);
162 cvReleaseMat(&points);
170 cvReleaseMat(&rot_points);
173 features.push_back(linearity);
176 CvMat* A = cvCreateMat(num_points, 3, CV_64FC1);
177 CvMat* B = cvCreateMat(num_points, 1, CV_64FC1);
180 for (laser_processor::SampleSet::iterator i = cluster->begin();
187 cvmSet(A, j, 0, -2.0 * x);
188 cvmSet(A, j, 1, -2.0 * y);
191 cvmSet(B, j, 0, -
pow(x, 2) -
pow(y, 2));
195 CvMat* sol = cvCreateMat(3, 1, CV_64FC1);
197 cvSolve(A, B, sol, CV_SVD);
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));
210 float circularity = 0.0;
211 for (laser_processor::SampleSet::iterator i = cluster->begin();
215 circularity +=
pow(rc -
sqrt(
pow(xc - (*i)->x, 2) +
pow(yc - (*i)->y, 2)), 2);
218 features.push_back(circularity);
223 features.push_back(radius);
226 float mean_curvature = 0.0;
229 float boundary_length = 0.0;
230 float last_boundary_seg = 0.0;
232 float boundary_regularity = 0.0;
233 double sum_boundary_reg_sq = 0.0;
236 laser_processor::SampleSet::iterator left = cluster->begin();
239 laser_processor::SampleSet::iterator mid = cluster->begin();
241 laser_processor::SampleSet::iterator right = cluster->begin();
243 float ang_diff = 0.0;
245 while (left != cluster->end())
247 float mlx = (*left)->x - (*mid)->x;
248 float mly = (*left)->y - (*mid)->y;
249 float L_ml =
sqrt(mlx * mlx + mly * mly);
251 float mrx = (*right)->x - (*mid)->x;
252 float mry = (*right)->y - (*mid)->y;
253 float L_mr =
sqrt(mrx * mrx + mry * mry);
255 float lrx = (*left)->x - (*right)->x;
256 float lry = (*left)->y - (*right)->y;
257 float L_lr =
sqrt(lrx * lrx + lry * lry);
259 boundary_length += L_mr;
260 sum_boundary_reg_sq += L_mr * L_mr;
261 last_boundary_seg = L_ml;
263 float A = (mlx * mrx + mly * mry) /
pow(L_mr, 2);
264 float B = (mlx * mry - mly * mrx) /
pow(L_mr, 2);
266 float th =
atan2(B, A);
271 ang_diff += th / num_points;
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));
277 mean_curvature += 4 * (area) / (L_ml * L_mr * L_lr * num_points);
279 mean_curvature -= 4 * (area) / (L_ml * L_mr * L_lr * num_points);
286 boundary_length += last_boundary_seg;
287 sum_boundary_reg_sq += last_boundary_seg * last_boundary_seg;
289 boundary_regularity =
sqrt((sum_boundary_reg_sq -
pow(boundary_length, 2) / num_points) / (num_points - 1));
291 features.push_back(boundary_length);
292 features.push_back(ang_diff);
293 features.push_back(mean_curvature);
295 features.push_back(boundary_regularity);
299 first = cluster->begin();
300 mid = cluster->begin();
302 last = cluster->end();
305 double sum_iav = 0.0;
306 double sum_iav_sq = 0.0;
310 float mlx = (*first)->x - (*mid)->x;
311 float mly = (*first)->y - (*mid)->y;
314 float mrx = (*last)->x - (*mid)->x;
315 float mry = (*last)->y - (*mid)->y;
316 float L_mr =
sqrt(mrx * mrx + mry * mry);
322 float A = (mlx * mrx + mly * mry) /
pow(L_mr, 2);
323 float B = (mlx * mry - mly * mrx) /
pow(L_mr, 2);
325 float th =
atan2(B, A);
331 sum_iav_sq += th * th;
336 float iav = sum_iav / num_points;
337 float std_iav =
sqrt((sum_iav_sq -
pow(sum_iav, 2) / num_points) / (num_points - 1));
339 features.push_back(iav);
340 features.push_back(std_iav);
TFSIMD_FORCE_INLINE const tfScalar & y() const
static Sample * Extract(int ind, const sensor_msgs::LaserScan &scan)
An ordered set of Samples.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
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)