calc_leg_features.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <cob_leg_detection/calc_leg_features.h>
00036 
00037 #include <opencv2/opencv.hpp>
00038 
00039 using namespace laser_processor;
00040 using namespace std;
00041 
00042 vector<float> calcLegFeatures(SampleSet* cluster, const sensor_msgs::LaserScan& scan)
00043 {
00044 
00045   vector<float> features;
00046 
00047   // Number of points
00048   int num_points = cluster->size();
00049   //  features.push_back(num_points);
00050 
00051   // Compute mean and median points for future use
00052   float x_mean = 0.0;
00053   float y_mean = 0.0;
00054   vector<float> x_median_set;
00055   vector<float> y_median_set;
00056   for (SampleSet::iterator i = cluster->begin();
00057        i != cluster->end();
00058        i++)
00059 
00060   {
00061     x_mean += ((*i)->x)/num_points;
00062     y_mean += ((*i)->y)/num_points;
00063     x_median_set.push_back((*i)->x);
00064     y_median_set.push_back((*i)->y);
00065   }
00066 
00067   std::sort(x_median_set.begin(), x_median_set.end());
00068   std::sort(y_median_set.begin(), y_median_set.end());
00069 
00070   float x_median = 0.5 * ( *(x_median_set.begin() + (num_points-1)/2) + *(x_median_set.begin() + num_points/2) );
00071   float y_median = 0.5 * ( *(y_median_set.begin() + (num_points-1)/2) + *(y_median_set.begin() + num_points/2) );
00072 
00073   //Compute std and avg diff from median
00074 
00075   double sum_std_diff = 0.0;
00076   double sum_med_diff = 0.0;
00077 
00078 
00079   for (SampleSet::iterator i = cluster->begin();
00080        i != cluster->end();
00081        i++)
00082 
00083   {
00084     sum_std_diff += pow( (*i)->x - x_mean, 2) + pow((*i)->y - y_mean, 2);
00085     sum_med_diff += sqrt(pow( (*i)->x - x_median, 2) + pow((*i)->y - y_median, 2));
00086   }
00087 
00088   float std = sqrt( 1.0/(num_points - 1.0) * sum_std_diff);
00089   float avg_median_dev = sum_med_diff / num_points;
00090 
00091   features.push_back(std);
00092   features.push_back(avg_median_dev);
00093 
00094 
00095   // Take first at last
00096   SampleSet::iterator first = cluster->begin();
00097   SampleSet::iterator last = cluster->end();
00098   last--;
00099 
00100   // Compute Jump distance
00101   int prev_ind = (*first)->index - 1;
00102   int next_ind = (*last)->index + 1;
00103 
00104   float prev_jump = 0;
00105   float next_jump = 0;
00106 
00107   if (prev_ind >= 0)
00108   {
00109     Sample* prev = Sample::Extract(prev_ind, scan);
00110     if (prev)
00111     {
00112       prev_jump = sqrt( pow( (*first)->x - prev->x, 2) + pow((*first)->y - prev->y, 2));
00113       delete prev;
00114     }
00115 
00116   }
00117 
00118   if (next_ind < (int)scan.ranges.size())
00119   {
00120     Sample* next = Sample::Extract(next_ind, scan);
00121     if (next)
00122     {
00123       next_jump = sqrt( pow( (*last)->x - next->x, 2) + pow((*last)->y - next->y, 2));
00124       delete next;
00125     }
00126   }
00127 
00128   features.push_back(prev_jump);
00129   features.push_back(next_jump);
00130 
00131   // Compute Width
00132   float width = sqrt( pow( (*first)->x - (*last)->x, 2) + pow((*first)->y - (*last)->y, 2));
00133   features.push_back(width);
00134 
00135   // Compute Linearity
00136 
00137   CvMat* points = cvCreateMat( num_points, 2, CV_64FC1);
00138   {
00139     int j = 0;
00140     for (SampleSet::iterator i = cluster->begin();
00141          i != cluster->end();
00142          i++)
00143     {
00144       cvmSet(points, j, 0, (*i)->x - x_mean);
00145       cvmSet(points, j, 1, (*i)->y - y_mean);
00146       j++;
00147     }
00148   }
00149 
00150   CvMat* W = cvCreateMat( 2, 2, CV_64FC1);
00151   CvMat* U = cvCreateMat( num_points, 2, CV_64FC1);
00152   CvMat* V = cvCreateMat( 2, 2, CV_64FC1);
00153   cvSVD(points, W, U, V);
00154 
00155   CvMat* rot_points = cvCreateMat(num_points, 2, CV_64FC1);
00156   cvMatMul(U,W,rot_points);
00157 
00158   float linearity = 0.0;
00159   for (int i = 0; i < num_points; i++)
00160   {
00161     linearity += pow(cvmGet(rot_points, i, 1), 2);
00162   }
00163 
00164   cvReleaseMat(&points); points = 0;
00165   cvReleaseMat(&W); W = 0;
00166   cvReleaseMat(&U); U = 0;
00167   cvReleaseMat(&V); V = 0;
00168   cvReleaseMat(&rot_points); rot_points = 0;
00169 
00170   features.push_back(linearity);
00171 
00172   // Compute Circularity
00173   CvMat* A = cvCreateMat( num_points, 3, CV_64FC1);
00174   CvMat* B = cvCreateMat( num_points, 1, CV_64FC1);
00175   {
00176     int j = 0;
00177     for (SampleSet::iterator i = cluster->begin();
00178          i != cluster->end();
00179          i++)
00180     {
00181       float x = (*i)->x;
00182       float y = (*i)->y;
00183 
00184       cvmSet(A, j, 0, -2.0*x);
00185       cvmSet(A, j, 1, -2.0*y);
00186       cvmSet(A, j, 2, 1);
00187 
00188       cvmSet(B, j, 0, -pow(x,2)-pow(y,2));
00189       j++;
00190     }
00191   }
00192   CvMat* sol = cvCreateMat( 3, 1, CV_64FC1);
00193 
00194   cvSolve(A, B, sol, CV_SVD);
00195 
00196   float xc = cvmGet(sol, 0, 0);
00197   float yc = cvmGet(sol, 1, 0);
00198   float rc = sqrt(pow(xc,2) + pow(yc,2) - cvmGet(sol, 2, 0));
00199 
00200   cvReleaseMat(&A); A = 0;
00201   cvReleaseMat(&B); B = 0;
00202   cvReleaseMat(&sol); sol = 0;
00203 
00204   float circularity = 0.0;
00205   for (SampleSet::iterator i = cluster->begin();
00206        i != cluster->end();
00207        i++)
00208   {
00209     circularity += pow( rc - sqrt( pow(xc - (*i)->x, 2) + pow( yc - (*i)->y, 2) ), 2);
00210   }
00211 
00212   features.push_back(circularity);
00213 
00214   // Radius
00215   float radius = rc;
00216 
00217   features.push_back(radius);
00218 
00219   //Curvature:
00220   float mean_curvature = 0.0;
00221 
00222   //Boundary length:
00223   float boundary_length = 0.0;
00224   float last_boundary_seg = 0.0;
00225 
00226   float boundary_regularity = 0.0;
00227   double sum_boundary_reg_sq = 0.0;
00228 
00229   // Mean angular difference
00230   SampleSet::iterator left = cluster->begin();
00231   left++;
00232   left++;
00233   SampleSet::iterator mid = cluster->begin();
00234   mid++;
00235   SampleSet::iterator right = cluster->begin();
00236 
00237   float ang_diff = 0.0;
00238 
00239   while (left != cluster->end())
00240   {
00241     float mlx = (*left)->x - (*mid)->x;
00242     float mly = (*left)->y - (*mid)->y;
00243     float L_ml = sqrt(mlx*mlx + mly*mly);
00244 
00245     float mrx = (*right)->x - (*mid)->x;
00246     float mry = (*right)->y - (*mid)->y;
00247     float L_mr = sqrt(mrx*mrx + mry*mry);
00248 
00249     float lrx = (*left)->x - (*right)->x;
00250     float lry = (*left)->y - (*right)->y;
00251     float L_lr = sqrt(lrx*lrx + lry*lry);
00252 
00253     boundary_length += L_mr;
00254     sum_boundary_reg_sq += L_mr*L_mr;
00255     last_boundary_seg = L_ml;
00256 
00257     float A = (mlx*mrx + mly*mry) / pow(L_mr, 2);
00258     float B = (mlx*mry - mly*mrx) / pow(L_mr, 2);
00259 
00260     float th = atan2(B,A);
00261 
00262     if (th < 0)
00263       th += 2*M_PI;
00264 
00265     ang_diff += th / num_points;
00266 
00267     float s = 0.5*(L_ml+L_mr+L_lr);
00268     float area = sqrt( s*(s-L_ml)*(s-L_mr)*(s-L_lr) );
00269 
00270     if (th > 0)
00271       mean_curvature += 4*(area)/(L_ml*L_mr*L_lr*num_points);
00272     else
00273       mean_curvature -= 4*(area)/(L_ml*L_mr*L_lr*num_points);
00274 
00275     left++;
00276     mid++;
00277     right++;
00278   }
00279 
00280   boundary_length += last_boundary_seg;
00281   sum_boundary_reg_sq += last_boundary_seg*last_boundary_seg;
00282 
00283   boundary_regularity = sqrt( (sum_boundary_reg_sq - pow(boundary_length,2)/num_points)/(num_points - 1) );
00284 
00285   features.push_back(boundary_length);
00286   features.push_back(ang_diff);
00287   features.push_back(mean_curvature);
00288 
00289   features.push_back(boundary_regularity);
00290 
00291 
00292   // Mean angular difference
00293   first = cluster->begin();
00294   mid = cluster->begin();
00295   mid++;
00296   last = cluster->end();
00297   last--;
00298   
00299   double sum_iav = 0.0;
00300   double sum_iav_sq  = 0.0;
00301 
00302   while (mid != last)
00303   {
00304     float mlx = (*first)->x - (*mid)->x;
00305     float mly = (*first)->y - (*mid)->y;
00306     //float L_ml = sqrt(mlx*mlx + mly*mly);
00307 
00308     float mrx = (*last)->x - (*mid)->x;
00309     float mry = (*last)->y - (*mid)->y;
00310     float L_mr = sqrt(mrx*mrx + mry*mry);
00311 
00312     //float lrx = (*first)->x - (*last)->x;
00313     //float lry = (*first)->y - (*last)->y;
00314     //float L_lr = sqrt(lrx*lrx + lry*lry);
00315       
00316     float A = (mlx*mrx + mly*mry) / pow(L_mr, 2);
00317     float B = (mlx*mry - mly*mrx) / pow(L_mr, 2);
00318 
00319     float th = atan2(B,A);
00320 
00321     if (th < 0)
00322       th += 2*M_PI;
00323 
00324     sum_iav += th;
00325     sum_iav_sq += th*th;
00326 
00327     mid++;
00328   }
00329 
00330   float iav = sum_iav / num_points;
00331   float std_iav = sqrt( (sum_iav_sq - pow(sum_iav,2)/num_points)/(num_points - 1) );
00332 
00333   features.push_back(iav);
00334   features.push_back(std_iav);
00335 
00336   return features;
00337 }


cob_leg_detection
Author(s): Caroline Pantofaru, Olha Meyer
autogenerated on Mon May 6 2019 02:32:17