00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00019 #ifndef __POLYOPS_H__
00020 #define __POLYOPS_H__
00021
00022
00023 #include <utility>
00024 #include <math.h>
00025 #include <vector>
00026 #include <set>
00027 #include <map>
00028
00029 #include <art_msgs/ArtLanes.h>
00030 #include <art_map/coordinates.h>
00031 #include <art_map/types.h>
00032
00038 class poly
00039 {
00040 public:
00041
00042
00043
00044 MapXY p1;
00045 MapXY p2;
00046 MapXY p3;
00047 MapXY p4;
00048
00049
00050 float heading;
00051
00052
00053 MapXY midpoint;
00054
00055
00056 float length;
00057
00058 poly_id_t poly_id;
00059
00060 bool is_stop;
00061 bool is_transition;
00062
00063
00064 bool contains_way;
00065
00066 ElementID start_way;
00067 ElementID end_way;
00068
00069 Lane_marking left_boundary;
00070 Lane_marking right_boundary;
00071
00073 poly() {};
00074
00076 poly(const art_msgs::ArtQuadrilateral &msg)
00077 {
00078 p1 = MapXY(msg.poly.points[art_msgs::ArtQuadrilateral::bottom_left]);
00079 p2 = MapXY(msg.poly.points[art_msgs::ArtQuadrilateral::top_left]);
00080 p3 = MapXY(msg.poly.points[art_msgs::ArtQuadrilateral::top_right]);
00081 p4 = MapXY(msg.poly.points[art_msgs::ArtQuadrilateral::bottom_right]);
00082 midpoint = MapXY(msg.midpoint);
00083
00084 heading = msg.heading;
00085 length = msg.length;
00086 poly_id = msg.poly_id;
00087
00088 is_stop = msg.is_stop;
00089 is_transition = msg.is_transition;
00090 contains_way = msg.contains_way;
00091
00092 start_way = ElementID(msg.start_way);
00093 end_way = ElementID(msg.end_way);
00094
00095 left_boundary = Lane_marking(msg.left_boundary.lane_marking);
00096 right_boundary = Lane_marking(msg.right_boundary.lane_marking);
00097 };
00098 };
00099
00100 typedef std::vector<poly> poly_list_t;
00101
00102
00103 typedef struct polyUpdate
00104 {
00105 poly_id_t poly_id;
00106 int point_id;
00107 float distance;
00108 float bearing;
00109 float confidence;
00110 } lanes_poly_vision_t;
00111
00112
00118 class PolyOps
00119 {
00120 public:
00121 PolyOps();
00122 ~PolyOps();
00123
00124 int get_waypoint_index(const std::vector<poly> &polys,
00125 const ElementID& waypoint);
00126
00127 int getPolyWayPt(const std::vector<poly> &polys,
00128 const ElementID& waypoint);
00129
00130
00131 void add_polys_for_waypts(const std::vector <poly> &from_polys,
00132 std::vector <poly> &to_polys,
00133 ElementID from_id, ElementID to_id);
00134
00135
00136 void AddTransitionPolys(const std::vector <poly> &from_polys,
00137 std::vector <poly> &to_polys,
00138 WayPointNode way0, WayPointNode way1);
00139
00140
00141
00142 void AddLanePolys(const std::vector <poly> &from_polys,
00143 std::vector <poly> &to_polys, ElementID id);
00144
00145 void AddLanePolys(const std::vector <poly> &from_polys,
00146 std::vector <poly> &to_polys, WayPointNode waypt);
00147
00148
00149
00150 void AddLanePolysEither(const std::vector <poly> &from_polys,
00151 std::vector <poly> &to_polys, WayPointNode waypt,
00152 int direction);
00153
00154
00155
00156 void AddReverseLanePolys(const std::vector <poly> &from_polys,
00157 std::vector <poly> &to_polys, ElementID id);
00158
00159 void AddReverseLanePolys(const std::vector <poly> &from_polys,
00160 std::vector <poly> &to_polys, WayPointNode waypt);
00161
00162
00163 void CollectPolys(const std::vector<poly> &from_polys,
00164 std::vector<poly> &to_polys,
00165 unsigned start, unsigned end);
00166
00167 void CollectPolys(const std::vector<poly> &from_polys,
00168 std::vector<poly> &to_polys,
00169 unsigned start);
00170
00171
00172
00173
00174 bool LanePoly(const poly &curPoly, ElementID id);
00175
00176 bool LanePoly(const poly &curPoly, WayPointNode waypt);
00177
00178
00179 bool match_waypt_poly(const poly& curPoly, ElementID way0, ElementID way1)
00180 {
00181 return (ElementID(curPoly.start_way) == way0
00182 && ElementID(curPoly.end_way) == way1);
00183 }
00184
00185
00186 bool match_waypt_poly(const poly& curPoly, ElementID way)
00187 {
00188 return (ElementID(curPoly.start_way) == way
00189 && ElementID(curPoly.end_way) == way);
00190 }
00191
00192
00193 bool MatchTransitionPoly(const poly& curPoly,
00194 const WayPointNode& way0,
00195 const WayPointNode& way1);
00196
00197 float PolyHeading(const poly& curPoly);
00198
00199
00200
00201 bool pointInHull(float x, float y, const poly& p)
00202 {
00203 float minx=p.p1.x;
00204 float maxx=p.p1.x;
00205 float miny=p.p1.y;
00206 float maxy=p.p1.y;
00207
00208 minx=fminf(fminf(fminf(minx,p.p2.x),p.p3.x),p.p4.x);
00209 miny=fminf(fminf(fminf(miny,p.p2.y),p.p3.y),p.p4.y);
00210 maxx=fmaxf(fmaxf(fmaxf(maxx,p.p2.x),p.p3.x),p.p4.x);
00211 maxy=fmaxf(fmaxf(fmaxf(maxy,p.p2.y),p.p3.y),p.p4.y);
00212
00213 return (Epsilon::gte(x,minx) && Epsilon::lte(x,maxx) &&
00214 Epsilon::gte(y,miny) && Epsilon::lte(y,maxy));
00215 }
00216
00217 bool pointOnSegment(float x, float y, MapXY p1, MapXY p2)
00218 {
00219 float minx=fminf(p1.x,p2.x);
00220 float miny=fminf(p1.y,p2.y);
00221 float maxx=fmaxf(p1.x,p2.x);
00222 float maxy=fmaxf(p1.y,p2.y);
00223
00224 if (Epsilon::gte(x,minx) && Epsilon::lte(x,maxx) &&
00225 Epsilon::gte(y,miny) && Epsilon::lte(y,maxy))
00226 {
00227 float diffy=p2.y-p1.y;
00228 float diffx=p2.x-p1.x;
00229
00230 float diff2y=y-p1.y;
00231 float diff2x=x-p1.x;
00232
00233 if (Epsilon::equal(diffx,0.0))
00234 return (Epsilon::equal(diff2x,0.0) &&
00235 ((diff2y<0) == (diffy<0)));
00236
00237 if (Epsilon::equal(diff2x,0.0))
00238 return false;
00239
00240 return (Epsilon::equal(diffy/diffx,diff2y/diff2x));
00241 }
00242 return false;
00243
00244 }
00245
00246 bool pointOnEdges(float x, float y, const poly& p)
00247 {
00248 return (pointOnSegment(x, y, MapXY(p.p1), MapXY(p.p2)) ||
00249 pointOnSegment(x, y, MapXY(p.p3), MapXY(p.p2)) ||
00250 pointOnSegment(x, y, MapXY(p.p4), MapXY(p.p3)) ||
00251 pointOnSegment(x, y, MapXY(p.p1), MapXY(p.p4)));
00252 }
00253
00254 bool pointInPoly(float x, float y, const poly& p)
00255 {
00256 if (!pointInHull(x,y,p))
00257 return false;
00258
00259 bool odd = false;
00260
00261
00262
00263 if ((p.p1.y < y && p.p2.y >= y) || (p.p2.y < y && p.p1.y >= y))
00264 if (p.p1.x + (y-p.p1.y)/(p.p2.y-p.p1.y)*(p.p2.x-p.p1.x) < x)
00265 odd = !odd;
00266
00267 if ((p.p2.y < y && p.p3.y >= y) || (p.p3.y < y && p.p2.y >= y))
00268 if (p.p2.x + (y-p.p2.y)/(p.p3.y-p.p2.y)*(p.p3.x-p.p2.x) < x)
00269 odd = !odd;
00270
00271 if ((p.p3.y < y && p.p4.y >= y) || (p.p4.y < y && p.p3.y >= y))
00272 if (p.p3.x + (y-p.p3.y)/(p.p4.y-p.p3.y)*(p.p4.x-p.p3.x) < x)
00273 odd = !odd;
00274
00275 if ((p.p4.y < y && p.p1.y >= y) || (p.p1.y < y && p.p4.y >= y))
00276 if (p.p4.x + (y-p.p4.y)/(p.p1.y-p.p4.y)*(p.p1.x-p.p4.x) < x)
00277 odd = !odd;
00278
00279 if (odd)
00280 return true;
00281
00282 return pointOnEdges(x, y, p);
00283
00284 }
00285
00286 bool pointInPoly(const MapXY& pt, const poly& p)
00287 {
00288 return pointInPoly(pt.x, pt.y, p);
00289 };
00290
00291 bool pointInPoly(const Polar& polar, const MapPose &origin,
00292 const poly &p)
00293 {
00294 return pointInPoly(Coordinates::Polar_to_MapXY(polar, origin), p);
00295 };
00296
00297
00298
00299
00300
00301 bool pointInPoly_ratio(float x, float y, const poly& p, float ratio);
00302 bool pointInPoly_ratio(const MapXY& pt, const poly& p, float ratio)
00303 {
00304 return pointInPoly_ratio(pt.x, pt.y, p, ratio);
00305 };
00306
00307
00308
00309
00310
00311
00312
00313 bool pointNearPoly(double x, double y, const poly& poly, double epsilon)
00314 {
00315 return (getShortestDistToPoly(x, y, poly) < epsilon);
00316 }
00317 bool pointNearPoly(const MapXY& pt, const poly& poly, double epsilon)
00318 {
00319 return (getShortestDistToPoly(pt.x, pt.y, poly) < epsilon);
00320 }
00321
00322
00323
00324
00325
00326
00334 int getContainingPoly(const std::vector<poly> &polys, float x, float y);
00335 int getContainingPoly(const std::vector<poly>& polys, const MapXY& pt)
00336 {
00337 return getContainingPoly(polys, pt.x, pt.y);
00338 };
00339
00340 int getContainingPoly(const std::vector<poly>& polys,
00341 const MapPose &pose)
00342 {
00343 return getContainingPoly(polys, pose.map.x, pose.map.y);
00344 };
00345
00346
00347 poly_id_t getContainingPolyID(const std::vector<poly> &polys,
00348 float x, float y)
00349 {
00350 int index = getContainingPoly(polys, x, y);
00351 if (index < 0)
00352 return -1;
00353 else
00354 return polys[index].poly_id;
00355 };
00356 poly_id_t getContainingPolyID(const std::vector<poly>& polys,
00357 const MapXY& pt)
00358 {
00359 int index = getContainingPoly(polys, pt);
00360 if (index < 0)
00361 return -1;
00362 else
00363 return polys[index].poly_id;
00364 };
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376 int getPolyIndex(const std::vector<poly>& polys, const poly& curPoly)
00377 {
00378 int i;
00379 for (i = 0; i < (int) polys.size(); ++i)
00380 {
00381 if (polys.at(i).poly_id == curPoly.poly_id)
00382 return i;
00383 }
00384 return -1;
00385 }
00386
00387
00388 void getRemainingPolys(const std::vector<poly> &from_polys,
00389 std::vector<poly> &to_polys,
00390 const MapXY &point);
00391
00392
00393
00394
00395
00396
00397
00398
00399
00400
00401 float getShortestDistToPoly(float x, float y, const poly& p);
00402 float getShortestDistToPoly(MapXY pt, const poly& p)
00403 {
00404 return getShortestDistToPoly(pt.x, pt.y, p);
00405 }
00406
00407
00408
00409
00410
00411
00412
00413
00414 int getClosestPoly(const std::vector<poly>& polys, float x, float y);
00415 int getClosestPoly(const std::vector<poly>& polys, MapXY pt)
00416 {
00417 return getClosestPoly(polys, pt.x, pt.y);
00418 }
00419 int getClosestPoly(const std::vector<poly>& polys,
00420 const MapPose &pose)
00421 {
00422 return getClosestPoly(polys, pose.map.x, pose.map.y);
00423 }
00424
00425
00426
00427
00428
00429
00430
00431
00432
00433
00434
00435
00436
00437
00438 int getClosestNonTransPoly(const std::vector<poly>& polys, float x, float y);
00439 int getClosestNonTransPoly(const std::vector<poly>& polys, MapXY pt)
00440 {
00441 return getClosestNonTransPoly(polys, pt.x, pt.y);
00442 }
00443
00444
00445
00446
00447
00448
00449
00450
00451
00452
00453
00454
00455
00456
00457
00458
00459
00460
00461
00462
00463 MapXY getPolyEdgeMidpoint(const poly& p);
00464
00465
00466 MapXY centerpoint(const poly& p);
00467
00468
00469 float getLength(const poly& p);
00470
00471
00472
00473
00474
00475
00476
00477 std::vector<poly> getPolysBetweenPoints(const std::vector<poly>& polys,
00478 float x1, float y1,
00479 float x2, float y2);
00480
00481
00482
00483 std::vector<MapXY> getPointsFromPolys(const std::vector<poly>& polys);
00484
00497 int getStartingPoly(const MapPose &pose,
00498 const std::vector<poly>& polygons,
00499 float distance,
00500 float min_heading);
00501
00502
00503
00504
00505
00506
00507
00508
00509
00510 float distanceAlongLane(const std::vector<poly>& polygons,
00511 const MapXY& from,
00512 const MapXY& to);
00513
00514 std::pair<float, MapXY>
00515 specialDistanceAlongLane(const std::vector<poly>& polygons,
00516 const MapXY& from,
00517 const MapXY& to);
00518
00519
00520
00521
00522
00523
00524
00525
00526
00527 int index_of_downstream_poly(const std::vector<poly>& polygons,
00528 int start_index,
00529 float distance);
00530
00531
00532
00533 float shortestDistToLineSegment(float x, float y, float line_x1,
00534 float line_y1, float line_x2,
00535 float line_y2);
00536
00537
00538 float avgLengthOfPolySides(const poly& p);
00539
00540
00541 std::set<ElementID> getPolyLaneIds(const std::vector<poly>& polys);
00542
00543
00544
00545
00546
00547
00548
00549
00550
00551
00552
00553
00554
00555
00556
00557
00558
00559
00560
00561
00562
00563
00564
00565
00566
00567
00568
00569
00570
00571
00572
00573
00574
00575
00576
00577
00578
00579
00580
00581
00582
00583
00584
00585
00586
00587
00588
00589
00590
00591
00592
00593 void getLaneDir(const std::vector<poly>& polys,
00594 std::vector<poly>& to_polys,
00595 const int relative,
00596 const int direction,
00597 const MapPose &pose);
00598
00599
00600
00601
00602
00603
00604
00605
00606
00607
00608
00609 void printPolygons(const poly_list_t& polys);
00610
00611
00612 poly_list_t getTransitionPolys(const poly_list_t& polys);
00613
00614
00615
00616
00617
00618
00619
00620 bool isValidPoly(const poly& p);
00621
00622
00623
00624
00625 MapXY GetClosestPointToLine(MapXY A, MapXY B,
00626 MapXY P, bool segmentClamp);
00627
00628 MapXY midpoint(const MapXY& p1, const MapXY& p2);
00629
00630 ElementID getReverseLane(const std::vector<poly>& polys,
00631 const MapPose &pose);
00632
00633
00634 bool left_of_poly(const poly &this_poly, const poly &cur_poly)
00635 {
00636
00637 MapPose cur_pose(cur_poly.midpoint, cur_poly.heading);
00638
00639
00640 float theta = Coordinates::bearing(cur_pose, this_poly.midpoint);
00641 return (theta > 0.0);
00642 }
00643
00644
00645 bool same_direction(const poly &p1, const poly &p2, float angle)
00646 {
00647 return (fabs(Coordinates::normalize(p1.heading - p2.heading)) < angle);
00648 }
00649
00650
00651 void getPolysBetweenWayPts(
00652 const std::vector<poly> &from_polys,
00653 std::vector<poly> &to_polys,
00654 ElementID from_id, ElementID to_id);
00655
00656
00657
00658
00659 std::vector<MapXY> getRoadPerimeterPoints(const std::vector<poly>& polys,
00660 const ElementID way0,
00661 const ElementID way1);
00662
00663 std::vector<MapXY> getRoadPerimeterPoints(const std::vector<poly>& polys,
00664 const ElementID way0);
00665
00666
00667 private:
00668
00669
00670
00671 float distance(float x1, float y1, float x2, float y2);
00672
00673
00674 float length_between_polygons(const std::vector<poly>& polygons,
00675 int index1=-1,
00676 int index2=-1);
00677
00678
00679 };
00680
00681 #endif