00001
00002
00003
00004
00005
00006
00007
00008
00009
00019 #include <float.h>
00020 #include <assert.h>
00021 #include <limits>
00022 #include <iostream>
00023
00024 #include <art/epsilon.h>
00025
00026 #include <art_map/coordinates.h>
00027 #include <art_map/euclidean_distance.h>
00028 #include <art_map/PolyOps.h>
00029
00030
00031
00032
00033 PolyOps::PolyOps()
00034 {
00035
00036 }
00037
00038 PolyOps::~PolyOps()
00039 {
00040
00041 }
00042
00043
00044 bool PolyOps::pointInPoly_ratio(float x, float y, const poly& p, float ratio)
00045 {
00046
00047
00048
00049 float diff=(1-ratio)/2;
00050
00051 MapXY p1=p.p1;
00052 MapXY p2=p.p2;
00053 MapXY p3=p.p3;
00054 MapXY p4=p.p4;
00055
00056 poly newpoly;
00057
00058 newpoly.p1.x=p1.x+(p4.x-p1.x)*diff;
00059 newpoly.p4.x=p1.x+(p4.x-p1.x)*(1-diff);
00060 newpoly.p1.y=p1.y+(p4.y-p1.y)*diff;
00061 newpoly.p4.y=p1.y+(p4.y-p1.y)*(1-diff);
00062
00063 newpoly.p2.x=p2.x+(p3.x-p2.x)*diff;
00064 newpoly.p3.x=p2.x+(p3.x-p2.x)*(1-diff);
00065 newpoly.p2.y=p2.y+(p3.y-p2.y)*diff;
00066 newpoly.p3.y=p2.y+(p3.y-p2.y)*(1-diff);
00067
00068 bool value=pointInPoly(x,y,newpoly);
00069
00070 #if 0
00071 if (value) {
00072 ROS_DEBUG("Point in small poly: original poly: [%f,%f; %f,%f;%f,%f;%f,%f]"
00073 " new poly: [%f,%f; %f,%f;%f,%f;%f,%f] point: [%f,%f]",
00074 p.x1,p.y1,p.x2,p.y2,p.x3,p.y3,p.x4,p.y4,
00075 newpoly.x1,newpoly.y1,newpoly.x2,newpoly.y2,
00076 newpoly.x3,newpoly.y3,newpoly.x4,newpoly.y4,x,y);
00077 }
00078 #endif
00079
00080 return value;
00081
00082 }
00083
00084
00085 int PolyOps::getContainingPoly(const std::vector<poly> &polys,
00086 float x, float y)
00087 {
00088
00089 int pindex;
00090 pindex= getClosestPoly(polys, x, y);
00091
00092 if (pindex < 0)
00093 {
00094 ROS_DEBUG("no polygon contains point (%.3f, %.3f)", x, y);
00095 return -1;
00096 }
00097
00098 poly closest=polys.at(pindex);
00099
00100
00101 if (getShortestDistToPoly(x, y, closest) < Epsilon::distance)
00102 {
00103 return pindex;
00104 }
00105
00106 ROS_DEBUG("no polygon contains point (%.3f, %.3f)", x, y);
00107 return -1;
00108 }
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131 float PolyOps::getShortestDistToPoly(float x, float y, const poly& p)
00132 {
00133 float dist = 0;
00134 float d;
00135
00136
00137 if (pointInPoly(x, y, p))
00138 return dist;
00139
00140
00141
00142
00143 dist = shortestDistToLineSegment(x, y, p.p1.x, p.p1.y, p.p2.x, p.p2.y);
00144
00145 if ( (d = shortestDistToLineSegment(x, y, p.p2.x, p.p2.y, p.p3.x, p.p3.y))
00146 < dist)
00147 dist = d;
00148
00149 if ( (d = shortestDistToLineSegment(x, y, p.p3.x, p.p3.y, p.p4.x, p.p4.y))
00150 < dist)
00151 dist = d;
00152
00153 if ( (d = shortestDistToLineSegment(x, y, p.p4.x, p.p4.y, p.p1.x, p.p1.y))
00154 < dist)
00155 dist = d;
00156
00157 return dist;
00158 }
00159
00160
00161
00162
00163 int PolyOps::getClosestPoly(const std::vector<poly>& polys, float x,
00164 float y)
00165 {
00166 poly p;
00167 float d;
00168 int index = -1;
00169
00170 float min_dist = std::numeric_limits<float>::max();
00171
00172 for (int i = 0; (unsigned)i < polys.size(); i++)
00173 {
00174 p = polys.at(i);
00175 d = getShortestDistToPoly(x, y, p);
00176
00177 if (Epsilon::equal(d,0))
00178 {
00179 index = i;
00180 return index;
00181 }
00182
00183 if (i == 0)
00184 {
00185 min_dist = d;
00186 index = 0;
00187 }
00188
00189 if (d < min_dist)
00190 {
00191 min_dist = d;
00192 index = i;
00193 }
00194 }
00195
00196 return index;
00197 }
00198
00199
00200
00201
00202 int PolyOps::getClosestNonTransPoly(const std::vector<poly>& polys, float x,
00203 float y)
00204 {
00205 poly p;
00206 float d;
00207 int index = -1;
00208
00209 float min_dist = std::numeric_limits<float>::max();
00210
00211 for (int i = 0; (unsigned)i < polys.size(); i++)
00212 {
00213 p = polys.at(i);
00214 if (p.is_transition)
00215 continue;
00216 d = getShortestDistToPoly(x, y, p);
00217
00218 if (Epsilon::equal(d,0))
00219 {
00220 index = i;
00221 return index;
00222 }
00223
00224 if (i == 0)
00225 {
00226 min_dist = d;
00227 index = 0;
00228 }
00229
00230 if (d < min_dist)
00231 {
00232 min_dist = d;
00233 index = i;
00234 }
00235 }
00236
00237 return index;
00238 }
00239
00240 #if 0 //TODO
00241
00242 int PolyOps::getClosestPolyEpsilon(const std::vector<poly>& polys,
00243 const player_pose2d_t& pose, const float epsilon)
00244 {
00245 int index = getClosestPoly(polys, pose);
00246 if (index < 0)
00247 return -1;
00248 if (pointNearPoly(pose, polys.at(index), epsilon))
00249 return index;
00250 else
00251 return -1;
00252 }
00253
00254
00255
00256 int PolyOps::getClosestNonTransPolyEpsilon(const std::vector<poly>& polys,
00257 const player_pose2d_t& pose, const float epsilon)
00258 {
00259 int index = getClosestNonTransPoly(polys, pose);
00260 if (index < 0)
00261 return -1;
00262 if (pointNearPoly(pose, polys.at(index), epsilon))
00263 return index;
00264 else
00265 return -1;
00266 }
00267 #endif
00268
00269 MapXY PolyOps::getPolyEdgeMidpoint(const poly& p)
00270 {
00271 MapXY r;
00272 r.x = (p.p2.x + p.p3.x)/2;
00273 r.y = (p.p2.y + p.p3.y)/2;
00274 return r;
00275 }
00276
00277 MapXY PolyOps::centerpoint(const poly& p)
00278 {
00279 return midpoint(midpoint(p.p1, p.p3) , midpoint(p.p2, p.p4));
00280 }
00281
00282 float PolyOps::getLength(const poly& p)
00283 {
00284 MapXY back=midpoint(p.p1, p.p4);
00285 MapXY front=midpoint(p.p2, p.p3);
00286 float d1 = distance(back.x,back.y,p.midpoint.x,p.midpoint.y);
00287 float d2 = distance(front.x,front.y,p.midpoint.x,p.midpoint.y);
00288 return d1+d2;
00289 }
00290
00291 std::vector<poly>
00292 PolyOps::getPolysBetweenPoints(const std::vector<poly>& polys,
00293 float x1, float y1,
00294 float x2, float y2)
00295 {
00296 std::vector<poly> retPolys;
00297 bool foundFirstPoint = false;
00298
00299
00300
00301
00302
00303
00304
00305
00306
00307
00308
00309
00310
00311
00312
00313
00314
00315
00316
00317
00318 int i;
00319 for (i = 0; (unsigned)i < polys.size(); i++)
00320 {
00321 if(pointInPoly(x1, y1, polys.at(i)))
00322 {
00323 foundFirstPoint = true;
00324 break;
00325 }
00326 }
00327
00328 if (!foundFirstPoint)
00329 {
00330 poly p;
00331 i= getClosestPoly(polys, x1, y1);
00332 if (i<0)
00333 return retPolys;
00334 p=polys.at(i);
00335 }
00336
00337 for ( ; (unsigned)i < polys.size(); i++)
00338 {
00339 if(pointInPoly(x2, y2, polys.at(i)))
00340 break;
00341
00342 retPolys.push_back(polys.at(i));
00343 }
00344
00345 return retPolys;
00346 }
00347
00348
00349 void PolyOps::getRemainingPolys(const std::vector<poly> &from_polys,
00350 std::vector<poly> &to_polys,
00351 const MapXY &point)
00352 {
00353 bool found_point = false;
00354
00355
00356 unsigned i;
00357 for (i = 0; i < from_polys.size(); i++)
00358 {
00359 if(pointInPoly(point, from_polys.at(i)))
00360 {
00361 found_point = true;
00362 break;
00363 }
00364 }
00365
00366 if (!found_point)
00367 {
00368
00369 poly p;
00370 int closest = getClosestPoly(from_polys, point);
00371 if (closest < 0)
00372 {
00373
00374 to_polys.clear();
00375 return;
00376 }
00377 i = closest;
00378 }
00379
00380 CollectPolys(from_polys, to_polys, i);
00381 }
00382
00383 std::vector<MapXY> PolyOps::getPointsFromPolys(const std::vector<poly>& polys)
00384 {
00385 std::vector<MapXY> retPoints;
00386
00387 for (int i = 0; (unsigned)i < polys.size(); i++)
00388 {
00389 retPoints.push_back(getPolyEdgeMidpoint(polys.at(i)));
00390 }
00391
00392 return retPoints;
00393 }
00394
00395 float PolyOps::distance(float x1, float y1, float x2, float y2)
00396 {
00397 return Euclidean::DistanceTo(x1,y1,x2,y2);
00398 }
00399
00400 float PolyOps::shortestDistToLineSegment(float x, float y,
00401 float line_x1, float line_y1,
00402 float line_x2, float line_y2)
00403 {
00404 float dist1, dist2;
00405 dist1=dist2=0;
00406
00407 Euclidean::DistanceFromLine(x,y,line_x1,line_y1,line_x2,line_y2,dist1,dist2);
00408 return dist1;
00409
00410
00411
00412
00413
00414
00415
00416
00417
00418
00419
00420
00421
00422
00423
00424
00425
00426
00427
00428
00429
00430
00431
00432
00433
00434
00435
00436
00437
00438
00439
00440 }
00441
00442 int PolyOps::get_waypoint_index(const std::vector<poly> &polys,
00443 const ElementID& waypoint)
00444 {
00445
00446 for (unsigned i=0; i<polys.size(); i++)
00447 if (polys.at(i).start_way==waypoint &&
00448 polys.at(i).end_way==waypoint)
00449 return i;
00450
00451 return -1;
00452 }
00453
00454 int PolyOps::getPolyWayPt(const std::vector<poly> &polys,
00455 const ElementID& waypoint) {
00456
00457 for (unsigned i=0; i<polys.size(); i++)
00458 if (polys.at(i).start_way==waypoint)
00459 return i;
00460
00461 return -1;
00462 }
00463
00464
00465
00466
00467
00468
00469 void PolyOps::add_polys_for_waypts(const std::vector <poly> &from_polys,
00470 std::vector <poly> &to_polys,
00471 ElementID from_id, ElementID to_id)
00472 {
00473 if (from_id != to_id)
00474 {
00475 for (unsigned i = 0; i < from_polys.size(); ++i)
00476 if (match_waypt_poly(from_polys.at(i), from_id, to_id))
00477 {
00478 to_polys.push_back(from_polys.at(i));
00479 #define EXTREME_DEBUG 1
00480 #ifdef EXTREME_DEBUG
00481 ROS_DEBUG("adding start, end waypoints %s, %s, poly_id = %d",
00482 to_polys.back().start_way.name().str,
00483 to_polys.back().end_way.name().str,
00484 to_polys.back().poly_id);
00485 #endif
00486 }
00487 }
00488
00489 for (unsigned i = 0; i < from_polys.size(); ++i)
00490 if (match_waypt_poly(from_polys.at(i), to_id))
00491 {
00492 to_polys.push_back(from_polys.at(i));
00493 #ifdef EXTREME_DEBUG
00494 ROS_DEBUG("adding start, end waypoints %s, %s, poly_id = %d",
00495 to_polys.back().start_way.name().str,
00496 to_polys.back().end_way.name().str,
00497 to_polys.back().poly_id);
00498 #endif
00499 break;
00500 }
00501 }
00502
00503
00504 void PolyOps::AddTransitionPolys(const std::vector <poly> &from_polys,
00505 std::vector <poly> &to_polys,
00506 WayPointNode way0, WayPointNode way1)
00507 {
00508 for (unsigned i = 0; i < from_polys.size(); ++i)
00509 {
00510 if (MatchTransitionPoly(from_polys.at(i), way0, way1))
00511 {
00512 to_polys.push_back(from_polys.at(i));
00513 }
00514 }
00515 }
00516
00517
00518
00519 void PolyOps::AddLanePolys(const std::vector <poly> &from_polys,
00520 std::vector <poly> &to_polys, ElementID id)
00521 {
00522 for (unsigned i = 0; i < from_polys.size(); ++i)
00523 {
00524 if (LanePoly(from_polys.at(i), id))
00525 {
00526 to_polys.push_back(from_polys.at(i));
00527 }
00528 }
00529 }
00530
00531
00532
00533 void PolyOps::AddLanePolys(const std::vector <poly> &from_polys,
00534 std::vector <poly> &to_polys, WayPointNode waypt)
00535 {
00536 AddLanePolys(from_polys, to_polys, waypt.id);
00537 }
00538
00539
00540
00541 void PolyOps::AddLanePolysEither(const std::vector <poly> &from_polys,
00542 std::vector <poly> &to_polys, WayPointNode waypt,
00543 int direction)
00544 {
00545 if (direction >= 0)
00546 AddLanePolys(from_polys, to_polys, waypt);
00547 else
00548 AddReverseLanePolys(from_polys, to_polys, waypt);
00549 }
00550
00551
00552
00553 void PolyOps::AddReverseLanePolys(const std::vector <poly> &from_polys,
00554 std::vector <poly> &to_polys, ElementID id)
00555 {
00556
00557 int last = from_polys.size() - 1;
00558 ROS_DEBUG("scanning polygons from %d back to 0", last);
00559 for (int i = last; i >= 0; --i)
00560 {
00561
00562 if (LanePoly(from_polys.at(i), id))
00563 {
00564 to_polys.push_back(from_polys.at(i));
00565 }
00566 }
00567 }
00568
00569
00570
00571 void PolyOps::AddReverseLanePolys(const std::vector <poly> &from_polys,
00572 std::vector <poly> &to_polys, WayPointNode waypt)
00573 {
00574 AddReverseLanePolys(from_polys, to_polys, waypt.id);
00575 }
00576
00577
00578 void PolyOps::CollectPolys(const std::vector<poly> &from_polys,
00579 std::vector<poly> &to_polys,
00580 unsigned start, unsigned end)
00581 {
00582 to_polys.clear();
00583 for (unsigned i = start; i < end; ++i)
00584 to_polys.push_back(from_polys.at(i));
00585 }
00586 void PolyOps::CollectPolys(const std::vector<poly> &from_polys,
00587 std::vector<poly> &to_polys,
00588 unsigned start)
00589 {
00590 CollectPolys(from_polys, to_polys, start, from_polys.size());
00591 }
00592
00593
00594 bool PolyOps::LanePoly(const poly &curPoly, WayPointNode waypt)
00595 {
00596 return LanePoly(curPoly, waypt.id);
00597 }
00598
00599
00600 bool PolyOps::LanePoly(const poly &curPoly, ElementID id)
00601 {
00602 return (curPoly.start_way.seg == id.seg
00603 && curPoly.start_way.lane == id.lane
00604 && curPoly.end_way.seg == id.seg
00605 && curPoly.end_way.lane == id.lane
00606 && !curPoly.is_transition);
00607 }
00608
00609
00610 bool PolyOps::MatchTransitionPoly(const poly& curPoly,
00611 const WayPointNode& way0,
00612 const WayPointNode& way1)
00613 {
00614 return (curPoly.start_way.same_lane(way0.id) &&
00615 curPoly.end_way.same_lane(way1.id) &&
00616 curPoly.is_transition);
00617 }
00618
00619 float PolyOps::PolyHeading(const poly& curPoly)
00620 {
00621 using Coordinates::bearing;
00622 float left_heading = bearing(curPoly.p1,curPoly.p2);
00623 float right_heading = bearing(curPoly.p4, curPoly.p3);
00624 using Coordinates::normalize;
00625 return normalize(right_heading
00626 + normalize(left_heading - right_heading) / 2.0f);
00627 }
00628
00629 int PolyOps::getStartingPoly(const MapPose &pose,
00630 const std::vector<poly>& polygons,
00631 float distance,
00632 float min_heading)
00633 {
00634 using Coordinates::normalize;
00635
00636
00637 int index = getContainingPoly(polygons, pose.map);
00638 if (index >=0
00639 && (fabs(normalize(polygons.at(index).heading - pose.yaw))
00640 < min_heading))
00641 {
00642 return index;
00643 }
00644
00645
00646 index = getClosestPoly(polygons, pose);
00647 if (index < 0)
00648 {
00649 ROS_WARN_STREAM("none of " << polygons.size()
00650 << " polygons near starting pose");
00651 return index;
00652 }
00653 else if (fabs(normalize(polygons.at(index).heading - pose.yaw))
00654 < min_heading)
00655 {
00656 ROS_DEBUG_STREAM("closest polygon[" << index
00657 << "] has suitable heading");
00658 return index;
00659 }
00660
00661
00662 segment_id_t segment = polygons.at(index).start_way.seg;
00663 ROS_INFO_STREAM("closest polygon[" << index
00664 << "] in segment " << segment);
00665
00666
00667 std::vector<lane_id_t> lanes;
00668
00669 for (uint i=0; i<polygons.size(); i++)
00670 if (polygons.at(i).start_way.seg ==
00671 segment) {
00672 bool lane_found=false;
00673 for (uint j=0;j<lanes.size();j++)
00674 if (lanes.at(j)==polygons.at(i).start_way.lane) {
00675 lane_found=true;
00676 break;
00677 }
00678 if (!lane_found)
00679 lanes.push_back(polygons.at(i).start_way.lane);
00680 }
00681
00682
00683
00684
00685 float mindist = FLT_MAX;
00686 poly minpoly = polygons.at(0);
00687 bool foundd = false;
00688 for (uint i=0; i<lanes.size(); i++)
00689 {
00690 ElementID point(segment,lanes.at(i),0);
00691 WayPointNode waypt;
00692 waypt.id=point;
00693
00694 std::vector<poly> lane_polys;
00695 AddLanePolys(polygons, lane_polys, waypt);
00696 int newind = getClosestPoly(lane_polys, pose);
00697 if (newind < 0)
00698 continue;
00699 float tempdist =
00700 fabs(normalize(lane_polys.at(newind).heading - pose.yaw));
00701 if (tempdist < mindist)
00702 {
00703 mindist = tempdist;
00704 minpoly = lane_polys.at(newind);
00705 foundd=true;
00706 }
00707 }
00708
00709 if (!foundd)
00710 {
00711 ROS_WARN_STREAM("no lane within distance " << distance);
00712 return -1;
00713 }
00714
00715
00716 for (uint i=0; i< polygons.size(); i++)
00717 if (minpoly.poly_id == polygons.at(i).poly_id)
00718 return i;
00719
00720 ROS_WARN("no min polygon found");
00721 return -1;
00722 }
00723
00724 #if 0 //TODO
00725 ElementID
00726 PolyOps::updateLaneLocation(const std::vector<poly>& polygons,
00727 const MapPose& pose,
00728 const WayPointNode& waypt1,
00729 const WayPointNode& waypt2)
00730 {
00731
00732 std::vector<poly> lanes_polys;
00733
00734 for (uint i=0; i< polygons.size(); i++)
00735 if ((polygons.at(i).start_way.seg == waypt1.id.seg &&
00736 polygons.at(i).start_way.lane == waypt1.id.lane &&
00737 polygons.at(i).start_way.pt == waypt1.id.pt)
00738 ||
00739 (polygons.at(i).start_way.seg == waypt2.id.seg &&
00740 polygons.at(i).start_way.lane == waypt2.id.lane &&
00741 polygons.at(i).start_way.pt == waypt2.id.pt))
00742 lanes_polys.push_back(polygons.at(i));
00743
00744 int index=getClosestPoly(lanes_polys,pose.px,pose.py);
00745
00746 if (index >= 0)
00747 return lanes_polys.at(index).start_way;
00748
00749 return waypt1.id;
00750
00751 }
00752 #endif
00753
00754 float PolyOps::length_between_polygons(const std::vector<poly>& polygons,
00755 int index1,
00756 int index2)
00757 {
00758 float length = 0;
00759
00760 index1=std::max(0,index1);
00761 index1=std::min(int(polygons.size()),index1);
00762
00763 index2=std::max(0,index2);
00764 index2=std::min(int(polygons.size()),index2);
00765
00766 for(int i = index1+1; i < index2; i++)
00767 length += polygons.at(i).length;
00768 return length;
00769 }
00770
00771
00772
00773
00774
00775
00776
00777
00778
00779
00780
00781
00782
00783 float PolyOps::distanceAlongLane(const std::vector<poly>& polygons,
00784 const MapXY& from,
00785 const MapXY& to)
00786 {
00787 return (specialDistanceAlongLane(polygons, from, to)).first;
00788 }
00789
00790
00791
00792
00793 std::pair<float, MapXY>
00794 PolyOps::specialDistanceAlongLane(const std::vector<poly>& polygons,
00795 const MapXY& from,
00796 const MapXY& to)
00797 {
00798
00799 int index1=getClosestPoly(polygons, from);
00800 int index2=getClosestPoly(polygons, to);
00801
00802 if (index1 == -1 || index2 == -1) {
00803 std::pair<float, MapXY> return_value(0, MapXY());
00804 return return_value;
00805 }
00806
00807 poly poly_start = polygons.at(index1);
00808 poly poly_end = polygons.at(index2);
00809
00810 MapXY start_bisect1=midpoint(poly_start.p1, poly_start.p4);
00811 MapXY start_bisect2=midpoint(poly_start.p2, poly_start.p3);
00812
00813 MapXY end_bisect1=midpoint(poly_end.p1, poly_end.p4);
00814 MapXY end_bisect2=midpoint(poly_end.p2, poly_end.p3);
00815
00816 MapXY start_point=GetClosestPointToLine(start_bisect1,start_bisect2,
00817 from, true);
00818
00819 MapXY end_point=GetClosestPointToLine(end_bisect1,end_bisect2,
00820 to, true);
00821
00822 float distance_start, distance_end, polygon_length;
00823 float tmp;
00824 if (index1 < index2)
00825 {
00826 Euclidean::DistanceFromLine(start_point, poly_start.p2, poly_start.p3,
00827 distance_start, tmp);
00828 Euclidean::DistanceFromLine(end_point, poly_end.p1, poly_end.p4,
00829 distance_end, tmp);
00830 polygon_length = length_between_polygons(polygons, index1, index2);
00831 }
00832 else if (index1 > index2)
00833 {
00834 Euclidean::DistanceFromLine(start_point, poly_start.p1, poly_start.p4,
00835 distance_start, tmp);
00836 Euclidean::DistanceFromLine(end_point, poly_end.p2, poly_end.p3,
00837 distance_end, tmp);
00838 polygon_length = length_between_polygons(polygons, index2, index1);
00839 }
00840 else
00841 {
00842 Euclidean::DistanceFromLine(start_point, poly_start.p1, poly_start.p4,
00843 distance_start, tmp);
00844 distance_start = -distance_start;
00845 Euclidean::DistanceFromLine(end_point, poly_end.p1, poly_end.p4,
00846 distance_end, tmp);
00847 polygon_length = 0;
00848 }
00849
00850 float distance_total = distance_start + polygon_length + distance_end;
00851
00852 if (index1 > index2)
00853 distance_total = -distance_total;
00854
00855 #ifdef EXTREME_DEBUG
00856 ROS_DEBUG("distance_total to (%f, %f) %f )", to.x, to.y, distance_total);
00857 ROS_DEBUG("polygon_length to (%f, %f) %f )", to.x, to.y, polygon_length);
00858 #endif
00859
00860 std::pair<float, MapXY> return_value(distance_total, start_point);
00861 return return_value;
00862 }
00863
00864 int PolyOps::index_of_downstream_poly(const std::vector<poly>& polygons,
00865 int start_index,
00866 float distance)
00867 {
00868 if(start_index < 0 || start_index >= (int)polygons.size())
00869 return -1;
00870
00871 if(distance <= 0)
00872 return start_index;
00873
00874 int index = start_index;
00875 float length_so_far = polygons.at(index).length;
00876 while(distance > length_so_far) {
00877 if(index == (int)polygons.size() - 1)
00878 return index;
00879 index++;
00880 length_so_far += polygons.at(index).length;
00881 }
00882 return index;
00883 }
00884
00885 MapXY PolyOps::midpoint(const MapXY& p1, const MapXY& p2)
00886 {
00887 MapXY mid((p1.x+p2.x)/2.0, (p1.y+p2.y)/2.0);
00888 return mid;
00889 }
00890
00891 float PolyOps::avgLengthOfPolySides(const poly& p)
00892 {
00893 float s12 = Euclidean::DistanceTo(p.p1, p.p2);
00894 float s23 = Euclidean::DistanceTo(p.p2, p.p3);
00895 float s34 = Euclidean::DistanceTo(p.p3, p.p4);
00896 float s41 = Euclidean::DistanceTo(p.p4, p.p1);
00897 return (s12 + s23 + s34 + s41) / 4;
00898 }
00899
00900
00901 std::set<ElementID> PolyOps::getPolyLaneIds(const std::vector<poly>& polys)
00902 {
00903 std::set<ElementID> lane_ids;
00904 lane_ids.clear();
00905 for (uint i = 0; i < polys.size(); ++i) {
00906 lane_ids.insert(ElementID(polys.at(i).start_way.seg,
00907 polys.at(i).start_way.lane, 0));
00908 }
00909 return lane_ids;
00910 }
00911
00912 #if 0 //TODO
00913
00914
00915
00916
00917
00918
00919
00920
00921
00922
00923
00924
00925
00926 ElementID PolyOps::getPolyLaneIdDir(const std::vector<poly>& polys,
00927 const int relative,
00928 const int direction,
00929 const player_pose2d_t& pose,
00930 const float poly_epsilon)
00931 {
00932 int cur_poly_index = getClosestPolyEpsilon(polys, pose, poly_epsilon);
00933 if (cur_poly_index == -1) {
00934 ROS_DEBUG("PolyOps::getPolyLaneIdDir: No poly found");
00935 return ElementID(-1,-1,-1);
00936 }
00937
00938 int adj_poly_index[2];
00939 poly my_cur_poly = polys.at(cur_poly_index);
00940
00941 if (direction == 0)
00942 return ElementID(my_cur_poly.start_way.seg, my_cur_poly.start_way.lane, 0);
00943
00944
00945 ElementID adj_lane[2];
00946 adj_lane[0] = polys.at(cur_poly_index).start_way;
00947 adj_lane[1] = polys.at(cur_poly_index).start_way;
00948 adj_lane[0].lane--;
00949 adj_lane[1].lane++;
00950 poly_list_t adj_lane_polys[2];
00951
00952
00953 for (unsigned i = 0; i < 2; ++i) {
00954 adj_lane[i].pt = 0;
00955 adj_lane_polys[i].clear();
00956
00957 if (adj_lane[i].lane > 0) {
00958
00959
00960 AddLanePolys(polys, adj_lane_polys[i], adj_lane[i]);
00961 if (adj_lane_polys[i].size() == 0 )
00962 continue;
00963
00964
00965 adj_poly_index[i] = getClosestPoly(adj_lane_polys[i],
00966 my_cur_poly.midpoint);
00967 if (adj_poly_index[i] == -1)
00968 continue;
00969 poly my_adj_poly = adj_lane_polys[i].at(adj_poly_index[i]);
00970
00971
00972 MapPose poly_pose(my_cur_poly.midpoint, 0.0);
00973 if (relative == 0)
00974 poly_pose.yaw = my_cur_poly.heading;
00975 else if (relative == 1)
00976 poly_pose.yaw = pose.pa;
00977 float theta = Coordinates::bearing(poly_pose, my_adj_poly.midpoint);
00978
00979 if ( (theta > 0 && direction == +1) ||
00980 (theta < 0 && direction == -1) )
00981 return ElementID(my_adj_poly.start_way.seg,
00982 my_adj_poly.start_way.lane, 0);
00983 else;
00984
00985 }
00986 }
00987
00988 ROS_DEBUG("Error: lane must not exist this direction");
00989 return ElementID();
00990 }
00991
00992
00993
00994
00995
00996
00997
00998
00999
01000
01001
01002
01003
01004
01005 ElementID PolyOps::getNonTransPolyLaneIdDir(const poly_list_t& polys,
01006 const int relative,
01007 const int direction,
01008 const player_pose2d_t& pose,
01009 const float poly_epsilon)
01010 {
01011 int cur_poly_index = getClosestNonTransPolyEpsilon(polys, pose, poly_epsilon);
01012 if (cur_poly_index == -1) {
01013 ROS_DEBUG("PolyOps::getNonTransPolyLaneIdDir: No poly found");
01014 return ElementID(-1,-1,-1);
01015 }
01016
01017 int adj_poly_index[2];
01018 poly my_cur_poly = polys.at(cur_poly_index);
01019
01020 if (direction == 0)
01021 return ElementID(my_cur_poly.start_way.seg, my_cur_poly.start_way.lane, 0);
01022
01023
01024 ElementID adj_lane[2];
01025 adj_lane[0] = polys.at(cur_poly_index).start_way;
01026 adj_lane[1] = polys.at(cur_poly_index).start_way;
01027 adj_lane[0].lane--;
01028 adj_lane[1].lane++;
01029 poly_list_t adj_lane_polys[2];
01030
01031
01032 for (unsigned i = 0; i < 2; ++i) {
01033 adj_lane[i].pt = 0;
01034 adj_lane_polys[i].clear();
01035
01036 if (adj_lane[i].lane > 0) {
01037
01038
01039 AddLanePolys(polys, adj_lane_polys[i], adj_lane[i]);
01040 if (adj_lane_polys[i].size() == 0 )
01041 continue;
01042
01043
01044 adj_poly_index[i] = getClosestNonTransPoly(adj_lane_polys[i],
01045 my_cur_poly.midpoint);
01046 if (adj_poly_index[i] == -1)
01047 continue;
01048 poly my_adj_poly = adj_lane_polys[i].at(adj_poly_index[i]);
01049
01050
01051 MapPose poly_pose(my_cur_poly.midpoint, 0.0);
01052 if (relative == 0)
01053 poly_pose.yaw = my_cur_poly.heading;
01054 else if (relative == 1)
01055 poly_pose.yaw = pose.pa;
01056 float theta = Coordinates::bearing(poly_pose, my_adj_poly.midpoint);
01057
01058 if ( (theta > 0 && direction == +1) ||
01059 (theta < 0 && direction == -1) )
01060 return ElementID(my_adj_poly.start_way.seg,
01061 my_adj_poly.start_way.lane, 0);
01062 else;
01063
01064 }
01065 }
01066 ROS_DEBUG("Error: lane must not exist this direction");
01067 return ElementID(-1,-1,-1);
01068
01069 }
01070 #endif
01071
01072
01073
01074
01075
01076
01077
01078
01079
01080
01081
01082
01083 void PolyOps::getLaneDir(const std::vector<poly>& polys,
01084 std::vector<poly>& to_polys,
01085 const int relative,
01086 const int direction,
01087 const MapPose &pose)
01088 {
01089
01090 to_polys.clear();
01091
01092 int cur_poly_index = getClosestPoly(polys, pose);
01093 if (cur_poly_index == -1) {
01094 ROS_DEBUG("PolyOps::getLaneDir: No poly found");
01095 return;
01096 }
01097 int adj_poly_index[2];
01098 poly my_cur_poly = polys.at(cur_poly_index);
01099
01100 if (direction == 0) {
01101 AddLanePolys(polys, to_polys, my_cur_poly.start_way);
01102 return;
01103 }
01104
01105
01106 ElementID adj_lane[2];
01107 adj_lane[0] = polys.at(cur_poly_index).start_way;
01108 adj_lane[1] = polys.at(cur_poly_index).start_way;
01109 adj_lane[0].lane--;
01110 adj_lane[1].lane++;
01111 poly_list_t adj_lane_polys[2];
01112
01113
01114 for (unsigned i = 0; i < 2; ++i) {
01115 adj_lane[i].pt = 0;
01116 adj_lane_polys[i].clear();
01117
01118 if (adj_lane[i].lane > 0) {
01119
01120
01121 AddLanePolys(polys, adj_lane_polys[i], adj_lane[i]);
01122 if (adj_lane_polys[i].size() == 0 )
01123 continue;
01124
01125
01126 adj_poly_index[i] = getClosestPoly(adj_lane_polys[i],
01127 my_cur_poly.midpoint);
01128 if (adj_poly_index[i] == -1)
01129 continue;
01130 poly my_adj_poly = adj_lane_polys[i].at(adj_poly_index[i]);
01131
01132
01133 MapPose poly_pose(my_cur_poly.midpoint, 0.0);
01134 if (relative == 0)
01135 poly_pose.yaw = my_cur_poly.heading;
01136 else if (relative == 1)
01137 poly_pose.yaw = pose.yaw;
01138 float theta = Coordinates::bearing(poly_pose, my_adj_poly.midpoint);
01139
01140 if ( (theta > 0 && direction == +1) ||
01141 (theta < 0 && direction == -1) )
01142 {
01143 CollectPolys(adj_lane_polys[i], to_polys, 0);
01144 return;
01145 }
01146
01147
01148 }
01149 }
01150 ROS_DEBUG("Error: lane must not exist this direction");
01151 }
01152
01153 #if 0 //TODO
01154
01155
01156 void PolyOps::getNumLanesDir(const std::vector<poly>& polys,
01157 std::vector<poly>& to_polys,
01158 const int relative,
01159 const int direction,
01160 const player_pose2d_t &pose,
01161 const unsigned num_lanes)
01162 {
01163 int poly_index;
01164 player_pose2d_t my_pose = pose;
01165 poly_list_t dir_polys;
01166 to_polys.clear();
01167 for (unsigned i = 0; i < num_lanes; i++) {
01168 getLaneDir(polys, dir_polys, relative, direction, my_pose);
01169 poly_index = getClosestPoly(dir_polys, my_pose);
01170 if (poly_index < 0)
01171 return;
01172 AddLanePolys(dir_polys, to_polys, dir_polys.at(poly_index).start_way);
01173 my_pose.px = dir_polys.at(poly_index).midpoint.x;
01174 my_pose.py = dir_polys.at(poly_index).midpoint.y;
01175 }
01176 if (to_polys.size() == 0)
01177 ROS_DEBUG("no lanes in given direction when expected");
01178 }
01179 #endif
01180
01181 ElementID PolyOps::getReverseLane(const std::vector<poly>& polys,
01182 const MapPose &pose)
01183 {
01184 poly_list_t to_polys;
01185
01186 ElementID return_id;
01187
01188 int base_index = getClosestPoly(polys, pose);
01189 if (base_index < 0)
01190 return return_id;
01191
01192 float base_heading=polys.at(base_index).heading;
01193 MapPose my_pose = pose;
01194
01195 while (true)
01196 {
01197 getLaneDir(polys,to_polys,0,+1,my_pose);
01198 int poly_index = getClosestPoly(to_polys, my_pose);
01199 if (poly_index < 0)
01200 break;
01201 float lane_heading=to_polys.at(poly_index).heading;
01202 if (fabs(Coordinates::normalize(lane_heading - base_heading)) > HALFPI)
01203 return to_polys.at(poly_index).end_way;
01204 my_pose.map.x = to_polys.at(poly_index).midpoint.x;
01205 my_pose.map.y = to_polys.at(poly_index).midpoint.y;
01206 }
01207 return return_id;
01208 }
01209
01210
01211 void PolyOps::printPolygons(const poly_list_t& polys)
01212 {
01213 for (uint i = 0; i < polys.size(); ++i) {
01214 poly p = polys.at(i);
01215 ROS_INFO("poly: %d S/T/CW: %d/%d/%d start: %d.%d.%d "
01216 "end: %d.%d.%d mp: %f,%f",
01217 p.poly_id, p.is_stop, p.is_transition, p.contains_way,
01218 p.start_way.seg, p.start_way.lane, p.start_way.pt,
01219 p.end_way.seg, p.end_way.lane, p.end_way.pt,
01220 p.midpoint.x, p.midpoint.y);
01221 }
01222 }
01223
01224
01225 poly_list_t PolyOps::getTransitionPolys(const poly_list_t& polys) {
01226 poly_list_t tran_polys;
01227 for (uint i = 0; i < polys.size(); ++i)
01228 if (polys.at(i).is_transition)
01229 tran_polys.push_back(polys.at(i));
01230 return tran_polys;
01231 }
01232
01233 #if 0 //TODO
01234
01235 poly PolyOps::getClosestPolyInLane(const std::vector<poly>& polys,
01236 const player_pose2d_t& pose,
01237 const ElementID id)
01238 {
01239 std::vector<poly> lane_polys;
01240 AddLanePolys(polys, lane_polys, id);
01241 int poly_index = getClosestPoly(lane_polys, pose);
01242 if (poly_index == -1) {
01243 poly null_poly;
01244 null_poly.poly_id = -1;
01245 return null_poly;
01246 }
01247 else
01248 return lane_polys.at(poly_index);
01249 }
01250 #endif
01251
01252
01253 bool PolyOps::isValidPoly(const poly& p)
01254 {
01255 if (p.poly_id == -1)
01256 return false;
01257 else
01258 return true;
01259 }
01260
01261 #if 0 //TODO
01262
01263 bool PolyOps::travelingCorrectDir(const poly& p, const player_pose2d_t& pose)
01264 {
01265 float theta = Coordinates::normalize(pose.pa - p.heading);
01266 if (fabs(theta) < HALFPI)
01267 return true;
01268 else
01269 return false;
01270 }
01271 #endif
01272
01273 MapXY PolyOps::GetClosestPointToLine(MapXY A, MapXY B,
01274 MapXY P, bool segmentClamp)
01275
01276
01277 {
01278 MapXY AP = P - A;
01279 MapXY AB = B - A;
01280 float ab2 = AB.x*AB.x + AB.y*AB.y;
01281 float ap_ab = AP.x*AB.x + AP.y*AB.y;
01282 float t = ap_ab / ab2;
01283 if (segmentClamp)
01284 {
01285 if (t < 0.0f)
01286 t = 0.0f;
01287 else if (t > 1.0f)
01288 t = 1.0f;
01289 }
01290 AB.x*=t;
01291 AB.y*=t;
01292
01293 MapXY Closest = A + AB;
01294 return Closest;
01295 }
01296
01297
01298 void PolyOps::getPolysBetweenWayPts(const std::vector<poly> &from_polys,
01299 std::vector<poly> &to_polys,
01300 ElementID from_id, ElementID to_id)
01301 {
01302
01303 to_polys.clear();
01304
01305 if (!from_id.valid() or !to_id.valid()) {
01306 ROS_DEBUG("points not valid");
01307 return;
01308 }
01309
01310 if (!from_id.same_lane(to_id)) {
01311 ROS_DEBUG("points not in same lane");
01312 return;
01313 }
01314
01315 int from_index = -1;
01316
01317 for (uint i = 0; i < from_polys.size(); ++i) {
01318 if (from_polys.at(i).start_way.pt == from_id.pt) {
01319 from_index = i;
01320 break;
01321 }
01322 }
01323
01324
01325 if (from_index == -1)
01326 return;
01327
01328
01329 for (uint i = from_index; i < from_polys.size(); ++i) {
01330 if (from_polys.at(i).start_way.pt < to_id.pt)
01331 to_polys.push_back(from_polys.at(i));
01332 }
01333
01334 }
01335
01336
01337
01338
01339 std::vector<MapXY> PolyOps::getRoadPerimeterPoints(
01340 const std::vector<poly>& polys,
01341 const ElementID way0, const ElementID way1)
01342 {
01343
01344 std::vector<poly> all_polys_in_curr_lane;
01345 std::vector<poly> all_polys_in_left_lane;
01346 std::vector<poly> polys_in_curr_lane_forward;
01347 std::vector<poly> polys_in_left_lane_reverse;
01348
01349 std::vector<MapXY> perim_points;
01350 perim_points.clear();
01351
01352
01353 if (!way0.valid() or !way1.valid() or polys.empty() or (way1 < way0))
01354 return perim_points;
01355
01356
01357 int p_idx_way0 = get_waypoint_index(polys, way0);
01358 if (p_idx_way0 < 0)
01359 return perim_points;
01360 poly way0_poly = polys.at(p_idx_way0);
01361
01362 MapPose way0_pose(way0_poly.midpoint, way0_poly.heading);
01363
01364
01365 int p_idx_way1 = get_waypoint_index(polys, way1);
01366 if (p_idx_way1 < 0)
01367 return perim_points;
01368 poly way1_poly = polys.at(p_idx_way1);
01369
01370 MapPose way1_pose(way1_poly.midpoint, way1_poly.heading);
01371
01372
01373 getLaneDir(polys, all_polys_in_curr_lane, 0, 0, way0_pose);
01374
01375 int way0_pi = getPolyIndex(all_polys_in_curr_lane, way0_poly);
01376 int way1_pi = getPolyIndex(all_polys_in_curr_lane, way1_poly);
01377 CollectPolys(all_polys_in_curr_lane, polys_in_curr_lane_forward,
01378 way0_pi, way1_pi);
01379
01380
01381 getLaneDir(polys, all_polys_in_left_lane, 0, +1, way0_pose);
01382 int ll_way0_pi = getClosestPoly(all_polys_in_left_lane, way0_pose);
01383 if (ll_way0_pi < 0) {
01384 ROS_DEBUG("no poly found 0");
01385 return perim_points;
01386 }
01387 int ll_way1_pi = getClosestPoly(all_polys_in_left_lane, way1_pose);
01388 if (ll_way1_pi < 0) {
01389 ROS_DEBUG("no poly found 1");
01390 return perim_points;
01391 }
01392 poly ll_way0_poly = all_polys_in_left_lane.at(ll_way0_pi);
01393 poly ll_way1_poly = all_polys_in_left_lane.at(ll_way1_pi);
01394
01395 ll_way0_pi = getPolyIndex(all_polys_in_left_lane, ll_way0_poly);
01396 ll_way1_pi = getPolyIndex(all_polys_in_left_lane, ll_way1_poly);
01397 CollectPolys(all_polys_in_left_lane, polys_in_left_lane_reverse,
01398 ll_way1_pi, ll_way0_pi);
01399
01400
01401 for (uint i = 0; i < polys_in_curr_lane_forward.size(); ++i) {
01402 perim_points.push_back(polys_in_curr_lane_forward.at(i).p4);
01403 }
01404 if (polys_in_curr_lane_forward.size() > 0)
01405 perim_points.push_back(polys_in_curr_lane_forward.back().p3);
01406
01407
01408 for (uint i = 0; i < polys_in_left_lane_reverse.size(); ++i) {
01409 perim_points.push_back(polys_in_left_lane_reverse.at(i).p2);
01410 }
01411 if (polys_in_left_lane_reverse.size() > 0)
01412 perim_points.push_back(polys_in_left_lane_reverse.back().p1);
01413
01414 return perim_points;
01415
01416 }
01417
01418 std::vector<MapXY> PolyOps::getRoadPerimeterPoints(
01419 const std::vector<poly>& polys,
01420 const ElementID way0)
01421 {
01422
01423 ElementID way1;
01424 std::vector<poly> all_polys_in_curr_lane;
01425 std::vector<poly> all_polys_in_left_lane;
01426 std::vector<poly> polys_in_curr_lane_forward;
01427 std::vector<poly> polys_in_left_lane_reverse;
01428
01429 std::vector<MapXY> perim_points;
01430 perim_points.clear();
01431
01432
01433 if (!way0.valid() or polys.empty())
01434 return perim_points;
01435
01436
01437 int p_idx_way0 = get_waypoint_index(polys, way0);
01438 if (p_idx_way0 < 0)
01439 return perim_points;
01440 poly way0_poly = polys.at(p_idx_way0);
01441
01442 MapPose way0_pose(way0_poly.midpoint, way0_poly.heading);
01443
01444
01445 getLaneDir(polys, all_polys_in_curr_lane, 0, 0, way0_pose);
01446
01447
01448
01449 for (uint i = 0; i < all_polys_in_curr_lane.size(); ++i) {
01450 if (all_polys_in_curr_lane.at(i).is_stop and
01451 all_polys_in_curr_lane.at(i).start_way > way0) {
01452 way1 = all_polys_in_curr_lane.at(i).start_way;
01453 break;
01454 }
01455 if (i == all_polys_in_curr_lane.size()-1)
01456 way1 = all_polys_in_curr_lane.at(i).start_way;
01457 }
01458
01459
01460 if (!way1.valid())
01461 return perim_points;
01462
01463
01464 int p_idx_way1 = get_waypoint_index(polys, way1);
01465 if (p_idx_way1 < 0)
01466 return perim_points;
01467 poly way1_poly = polys.at(p_idx_way1);
01468
01469 MapPose way1_pose(way1_poly.midpoint, way1_poly.heading);
01470
01471
01472 int way0_pi = getPolyIndex(all_polys_in_curr_lane, way0_poly);
01473 int way1_pi = getPolyIndex(all_polys_in_curr_lane, way1_poly);
01474 CollectPolys(all_polys_in_curr_lane, polys_in_curr_lane_forward,
01475 way0_pi, way1_pi);
01476
01477
01478 getLaneDir(polys, all_polys_in_left_lane, 0, +1, way0_pose);
01479 int ll_way0_pi = getClosestPoly(all_polys_in_left_lane, way0_pose);
01480 if (ll_way0_pi < 0) {
01481 ROS_DEBUG("no poly found 0");
01482 return perim_points;
01483 }
01484 int ll_way1_pi = getClosestPoly(all_polys_in_left_lane, way1_pose);
01485 if (ll_way1_pi < 0) {
01486 ROS_DEBUG("no poly found 1");
01487 return perim_points;
01488 }
01489 poly ll_way0_poly = all_polys_in_left_lane.at(ll_way0_pi);
01490 poly ll_way1_poly = all_polys_in_left_lane.at(ll_way1_pi);
01491
01492 ll_way0_pi = getPolyIndex(all_polys_in_left_lane, ll_way0_poly);
01493 ll_way1_pi = getPolyIndex(all_polys_in_left_lane, ll_way1_poly);
01494 CollectPolys(all_polys_in_left_lane, polys_in_left_lane_reverse,
01495 ll_way1_pi, ll_way0_pi);
01496
01497
01498 for (uint i = 0; i < polys_in_curr_lane_forward.size(); ++i) {
01499 perim_points.push_back(polys_in_curr_lane_forward.at(i).p4);
01500 }
01501 if (polys_in_curr_lane_forward.size() > 0)
01502 perim_points.push_back(polys_in_curr_lane_forward.back().p3);
01503
01504
01505 for (uint i = 0; i < polys_in_left_lane_reverse.size(); ++i) {
01506 perim_points.push_back(polys_in_left_lane_reverse.at(i).p2);
01507 }
01508 if (polys_in_left_lane_reverse.size() > 0)
01509 perim_points.push_back(polys_in_left_lane_reverse.back().p1);
01510
01511 return perim_points;
01512
01513 }