00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00033 #include <door_handle_detector/geometry/point.h>
00034 #include <door_handle_detector/geometry/areas.h>
00035 #include <door_handle_detector/geometry/distances.h>
00036 #include <door_handle_detector/geometry/transforms.h>
00037 #include <door_handle_detector/geometry/intersections.h>
00038
00039 #include <Eigen/Core>
00040 #include <Eigen/Geometry>
00041
00042 #include <cfloat>
00043 #include <algorithm>
00044
00045 namespace cloud_geometry
00046 {
00047
00048 namespace areas
00049 {
00051
00055 double
00056 compute2DPolygonalArea (const sensor_msgs::PointCloud &points, const std::vector<double> &normal)
00057 {
00058 int k0, k1, k2;
00059
00060
00061 k0 = (fabs (normal.at (0) ) > fabs (normal.at (1))) ? 0 : 1;
00062 k0 = (fabs (normal.at (k0)) > fabs (normal.at (2))) ? k0 : 2;
00063 k1 = (k0 + 1) % 3;
00064 k2 = (k0 + 2) % 3;
00065
00066
00067 double ct = fabs ( normal.at (k0) );
00068
00069 double area = 0;
00070 float p_i[3], p_j[3];
00071
00072 for (unsigned int i = 0; i < points.points.size (); i++)
00073 {
00074 p_i[0] = points.points[i].x; p_i[1] = points.points[i].y; p_i[2] = points.points[i].z;
00075 int j = (i + 1) % points.points.size ();
00076 p_j[0] = points.points[j].x; p_j[1] = points.points[j].y; p_j[2] = points.points[j].z;
00077
00078 area += p_i[k1] * p_j[k2] - p_i[k2] * p_j[k1];
00079 }
00080 area = fabs (area) / (2 * ct);
00081
00082 return (area);
00083 }
00084
00086
00090 double
00091 compute2DPolygonalArea (const geometry_msgs::Polygon &polygon, const std::vector<double> &normal)
00092 {
00093 int k0, k1, k2;
00094
00095
00096 k0 = (fabs (normal.at (0) ) > fabs (normal.at (1))) ? 0 : 1;
00097 k0 = (fabs (normal.at (k0)) > fabs (normal.at (2))) ? k0 : 2;
00098 k1 = (k0 + 1) % 3;
00099 k2 = (k0 + 2) % 3;
00100
00101
00102 double ct = fabs ( normal.at (k0) );
00103
00104 double area = 0;
00105 float p_i[3], p_j[3];
00106
00107 for (unsigned int i = 0; i < polygon.points.size (); i++)
00108 {
00109 p_i[0] = polygon.points[i].x; p_i[1] = polygon.points[i].y; p_i[2] = polygon.points[i].z;
00110 int j = (i + 1) % polygon.points.size ();
00111 p_j[0] = polygon.points[j].x; p_j[1] = polygon.points[j].y; p_j[2] = polygon.points[j].z;
00112
00113 area += p_i[k1] * p_j[k2] - p_i[k2] * p_j[k1];
00114 }
00115 area = fabs (area) / (2 * ct);
00116
00117 return (area);
00118 }
00119
00120
00121 bool compute2DPolygonNormal(const geometry_msgs::Polygon &poly, std::vector<double> &normal)
00122 {
00123 int k0,k1,k2;
00124 int sz=poly.points.size();
00125 if(sz<3)
00126 return false;
00127
00128 k0=0;
00129 k1=sz/3;
00130 if(k1<=k0) k1=k0+1;
00131 k2=(2*sz)/3;
00132 if(k2<=k1) k2=k1+1;
00133
00134 if(k2>=sz) return false;
00135
00136 Eigen::Vector3d p1, p2, p3;
00137
00138 p1 (0) = poly.points[k0].x-poly.points[k2].x;
00139 p1 (1) = poly.points[k0].y-poly.points[k2].y;
00140 p1 (2) = poly.points[k0].z-poly.points[k2].z;
00141
00142 p2 (0) = poly.points[k1].x-poly.points[k2].x;
00143 p2 (1) = poly.points[k1].y-poly.points[k2].y;
00144 p2 (2) = poly.points[k1].z-poly.points[k2].z;
00145
00146 p3 = p1.cross (p2);
00147 p3.normalize();
00148
00149 normal.resize(3);
00150 normal[0]=p3(0);
00151 normal[1]=p3(1);
00152 normal[2]=p3(2);
00153 return true;
00154 }
00155
00157
00161 double
00162 compute2DPolygonalArea (const geometry_msgs::Polygon &polygon)
00163 {
00164 std::vector<double> normal;
00165 if(!compute2DPolygonNormal(polygon,normal))
00166 return 0;
00167
00168 return compute2DPolygonalArea (polygon,normal);
00169
00170 }
00171
00173
00179 void
00180 convexHull2D (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, const std::vector<double> &coeff,
00181 geometry_msgs::Polygon &hull)
00182 {
00183
00184
00185 std::vector<Eigen::Vector3f> epoints (indices.size ());
00186 for (unsigned int cp = 0; cp < indices.size (); cp++)
00187 {
00188 epoints[cp](0) = points.points[indices.at (cp)].x;
00189 epoints[cp](1) = points.points[indices.at (cp)].y;
00190 epoints[cp](2) = points.points[indices.at (cp)].z;
00191 }
00192
00193
00194 int k0, k1, k2;
00195 k0 = (fabs (coeff.at (0) ) > fabs (coeff.at (1))) ? 0 : 1;
00196 k0 = (fabs (coeff.at (k0)) > fabs (coeff.at (2))) ? k0 : 2;
00197 k1 = (k0 + 1) % 3;
00198 k2 = (k0 + 2) % 3;
00199
00200
00201 Eigen::Vector2d centroid (0, 0);
00202 for (unsigned int cp = 0; cp < epoints.size (); cp++)
00203 {
00204 centroid (0) += epoints[cp](k1);
00205 centroid (1) += epoints[cp](k2);
00206 }
00207 centroid (0) /= epoints.size ();
00208 centroid (1) /= epoints.size ();
00209
00210
00211 std::vector<geometry_msgs::Point32> epoints_demean (epoints.size ());
00212 for (unsigned int cp = 0; cp < indices.size (); cp++)
00213 {
00214 epoints_demean[cp].x = epoints[cp](k1) - centroid (0);
00215 epoints_demean[cp].y = epoints[cp](k2) - centroid (1);
00216 }
00217
00218 std::sort (epoints_demean.begin (), epoints_demean.end (), comparePoint2D);
00219
00220 geometry_msgs::Polygon hull_2d;
00221 convexHull2D (epoints_demean, hull_2d);
00222
00223 int nr_points_hull = hull_2d.points.size ();
00224 if (nr_points_hull >= 3)
00225 {
00226
00227 Eigen::Vector3d p1, p2, p3;
00228
00229 p1 (k0) = 0;
00230 p1 (k1) = -hull_2d.points[0].x + hull_2d.points[1].x;
00231 p1 (k2) = -hull_2d.points[0].y + hull_2d.points[1].y;
00232
00233 p2 (k0) = 0;
00234 p2 (k1) = -hull_2d.points[0].x + hull_2d.points[2].x;
00235 p2 (k2) = -hull_2d.points[0].y + hull_2d.points[2].y;
00236
00237 p3 = p1.cross (p2);
00238
00239 bool direction = (p3 (k0) * coeff.at (k0) > 0);
00240
00241
00242 hull.points.resize (nr_points_hull);
00243
00244
00245 for (int cp = 0; cp < nr_points_hull; cp++)
00246 {
00247 int d = direction ? cp : (nr_points_hull - cp - 1);
00248 Eigen::Vector3f pt;
00249 pt (k1) = hull_2d.points[cp].x + centroid (0);
00250 pt (k2) = hull_2d.points[cp].y + centroid (1);
00251 pt (k0) = -(coeff.at (3) + pt (k1) * coeff.at (k1) + pt (k2) * coeff.at (k2)) / coeff.at (k0);
00252
00253
00254 hull.points[d].x = pt (0);
00255 hull.points[d].y = pt (1);
00256 hull.points[d].z = pt (2);
00257 }
00258 }
00259 }
00260
00262
00268 void
00269 convexHull2D (const std::vector<geometry_msgs::Point32> &points, geometry_msgs::Polygon &hull)
00270 {
00271 int nr_points = points.size ();
00272 hull.points.resize (nr_points + 1);
00273
00274
00275 int bot = 0, top = -1;
00276 int i;
00277
00278 for (i = 1; i < nr_points; i++)
00279
00280 if (points[i].x != points[0].x)
00281 break;
00282
00283
00284 int minmax = i - 1;
00285
00286
00287 if ( minmax == (nr_points - 1) )
00288 {
00289 ++top;
00290 hull.points[top].x = points[0].x;
00291 hull.points[top].y = points[0].y;
00292 hull.points[top].z = points[0].z;
00293
00294 if (points[minmax].y != points[0].y)
00295 {
00296 ++top;
00297 hull.points[top].x = points[minmax].x;
00298 hull.points[top].y = points[minmax].y;
00299 hull.points[top].z = points[minmax].z;
00300 }
00301 ++top;
00302
00303 hull.points[top].x = points[0].x;
00304 hull.points[top].y = points[0].y;
00305 hull.points[top].z = points[0].z;
00306 hull.points.resize (top + 1);
00307 return;
00308 }
00309
00310 int maxmin;
00311 for (i = nr_points - 2; i >= 0; i--)
00312 if (points[i].x != points[nr_points - 1].x)
00313 break;
00314 maxmin = i + 1;
00315
00316
00317 ++top;
00318
00319 hull.points[top].x = points[0].x;
00320 hull.points[top].y = points[0].y;
00321 hull.points[top].z = points[0].z;
00322
00323 i = minmax;
00324 while (++i <= maxmin)
00325 {
00326
00327 if ((i < maxmin) && (
00328 (points[maxmin].x - points[0].x) * (points[i].y - points[0].y) -
00329 (points[i].x - points[0].x) * (points[maxmin].y - points[0].y) >= 0))
00330 continue;
00331
00332
00333 while (top > 0)
00334 {
00335
00336 if ((hull.points[top].x - hull.points[top-1].x) * (points[i].y - hull.points[top-1].y) -
00337 (points[i].x - hull.points[top-1].x) * (hull.points[top].y - hull.points[top-1].y) > 0)
00338 break;
00339 else
00340 top--;
00341 }
00342 ++top;
00343 hull.points[top].x = points[i].x;
00344 hull.points[top].y = points[i].y;
00345 hull.points[top].z = points[i].z;
00346 }
00347
00348
00349 if ((nr_points - 1) != maxmin)
00350 {
00351 ++top;
00352
00353 hull.points[top].x = points[nr_points - 1].x;
00354 hull.points[top].y = points[nr_points - 1].y;
00355 hull.points[top].z = points[nr_points - 1].z;
00356 }
00357
00358 bot = top;
00359
00360 i = maxmin;
00361 while (--i >= minmax)
00362 {
00363
00364 if ((i > minmax) && (
00365 (points[minmax].x - points[nr_points - 1].x) * (points[i].y - points[nr_points - 1].y) -
00366 (points[i].x - points[nr_points - 1].x) * (points[minmax].y - points[nr_points - 1].y) >= 0))
00367 continue;
00368
00369
00370 while (top > bot)
00371 {
00372
00373 if ((hull.points[top].x - hull.points[top-1].x) * (points[i].y - hull.points[top-1].y) -
00374 (points[i].x - hull.points[top-1].x) * (hull.points[top].y - hull.points[top-1].y) > 0)
00375 break;
00376 else
00377 top--;
00378 }
00379 ++top;
00380
00381 hull.points[top].x = points[i].x;
00382 hull.points[top].y = points[i].y;
00383 hull.points[top].z = points[i].z;
00384 }
00385
00386 if (minmax != 0)
00387 {
00388 ++top;
00389
00390 hull.points[top].x = points[0].x;
00391 hull.points[top].y = points[0].y;
00392 hull.points[top].z = points[0].z;
00393 }
00394 hull.points.resize (top + 1);
00395 return;
00396 }
00397
00399
00405 bool
00406 isPointIn2DPolygon (const geometry_msgs::Point32 &point, const geometry_msgs::Polygon &polygon)
00407 {
00408 bool in_poly = false;
00409 double x1, x2, y1, y2;
00410
00411 int nr_poly_points = polygon.points.size ();
00412 double xold = polygon.points[nr_poly_points - 1].x;
00413 double yold = polygon.points[nr_poly_points - 1].y;
00414 for (int i = 0; i < nr_poly_points; i++)
00415 {
00416 double xnew = polygon.points[i].x;
00417 double ynew = polygon.points[i].y;
00418 if (xnew > xold)
00419 {
00420 x1 = xold;
00421 x2 = xnew;
00422 y1 = yold;
00423 y2 = ynew;
00424 }
00425 else
00426 {
00427 x1 = xnew;
00428 x2 = xold;
00429 y1 = ynew;
00430 y2 = yold;
00431 }
00432
00433 if ( (xnew < point.x) == (point.x <= xold) && (point.y - y1) * (x2 - x1) < (y2 - y1) * (point.x - x1) )
00434 {
00435 in_poly = !in_poly;
00436 }
00437 xold = xnew;
00438 yold = ynew;
00439 }
00440 return (in_poly);
00441 }
00442
00443 }
00444 }