Browse Source

change odtolanelet. change map route ok.

yuchuli 2 years ago
parent
commit
73bc44cd3a
2 changed files with 4 additions and 9 deletions
  1. 3 7
      src/map/odtolanelet/odtolanelet.cpp
  2. 1 2
      src/map/odtolanelet/odtolanelet.h

+ 3 - 7
src/map/odtolanelet/odtolanelet.cpp

@@ -520,7 +520,7 @@ void odtolanelet::ExecMerge(lanelet::LaneletMapPtr & laneletMap,std::vector<iv::
 
 
 void odtolanelet::InsertSameNodeID(std::vector<std::vector<iv::LaneletSameID>> & xvecotorsameID,lanelet::Id xLeftID1,lanelet::Id xRightID1,
-                                   lanelet::Id xLeftID2,lanelet::Id xRightID2,lanelet::LaneletLayer::iterator & iter1,lanelet::LaneletLayer::iterator & iter2,
+                                   lanelet::Id xLeftID2,lanelet::Id xRightID2,
                                    int npos1,int npos2)
 {
     unsigned int nSize = static_cast<unsigned int >(xvecotorsameID.size());
@@ -537,7 +537,6 @@ void odtolanelet::InsertSameNodeID(std::vector<std::vector<iv::LaneletSameID>> &
                 iv::LaneletSameID xsame;
                 xsame.mLeftID = xLeftID2;
                 xsame.mRightID = xRightID2;
-                xsame.iter = iter2;
                 xsame.npos = npos2;
 
                 xvecotorsameID[i].push_back(xsame);
@@ -551,7 +550,6 @@ void odtolanelet::InsertSameNodeID(std::vector<std::vector<iv::LaneletSameID>> &
                 iv::LaneletSameID xsame;
                 xsame.mLeftID = xLeftID1;
                 xsame.mRightID = xRightID1;
-                xsame.iter = iter1;
                 xsame.npos = npos1;
                 xvecotorsameID[i].push_back(xsame);
                 return;
@@ -563,12 +561,10 @@ void odtolanelet::InsertSameNodeID(std::vector<std::vector<iv::LaneletSameID>> &
     iv::LaneletSameID xsame;
     xsame.mLeftID = xLeftID1;
     xsame.mRightID = xRightID1;
-    xsame.iter = iter1;
     xsame.npos = npos1;
     xvls.push_back(xsame);
     xsame.mLeftID = xLeftID2;
     xsame.mRightID = xRightID2;
-    xsame.iter = iter2;
     xsame.npos = npos2;
     xvls.push_back(xsame);
     xvecotorsameID.push_back(xvls);
@@ -601,7 +597,7 @@ int odtolanelet::MergeLetPoint(lanelet::LaneletLayer::iterator & iter1,lanelet::
         std::cout<<" merge1 "<<std::endl;
 
         InsertSameNodeID(xvecotorsameID,iter1->leftBound()[iter1_leftsize-1].id(),iter1->rightBound()[iter1_rightsize-1].id(),
-                iter2->leftBound()[0].id(),iter2->rightBound()[0].id(),iter1,iter2,2,1);
+                iter2->leftBound()[0].id(),iter2->rightBound()[0].id(),2,1);
 
 //        iter2->leftBound().erase(iter2->leftBound().begin());
 //        iter2->rightBound().erase(iter2->rightBound().begin());
@@ -623,7 +619,7 @@ int odtolanelet::MergeLetPoint(lanelet::LaneletLayer::iterator & iter1,lanelet::
         std::cout<<" merge2 "<<std::endl;
 
         InsertSameNodeID(xvecotorsameID,iter1->leftBound()[0].id(),iter1->rightBound()[0].id(),
-                iter2->leftBound()[iter2_leftsize-1].id(),iter2->rightBound()[iter2_rightsize-1].id(),iter1,iter2,1,2);
+                iter2->leftBound()[iter2_leftsize-1].id(),iter2->rightBound()[iter2_rightsize-1].id(),1,2);
 
 //        iter2->leftBound().pop_back();
 //        iter2->rightBound().pop_back();

+ 1 - 2
src/map/odtolanelet/odtolanelet.h

@@ -17,7 +17,6 @@ struct LaneletSameID
     lanelet::Id mLeftID;
     lanelet::Id mRightID;
 
-    lanelet::LaneletLayer::iterator iter;
     int npos; //1 start  2 end
 };
 }
@@ -61,7 +60,7 @@ private:
     int MergeLetPoint(lanelet::LaneletLayer::iterator & iter1,lanelet::LaneletLayer::iterator & iter2,std::vector<std::vector<iv::LaneletSameID>> & xvecotorsameID);
 
     void InsertSameNodeID(std::vector<std::vector<iv::LaneletSameID>> & xvecotorsameID,lanelet::Id xLeftID1,lanelet::Id xRightID1,
-                          lanelet::Id xLeftID2,lanelet::Id xRightID2,lanelet::LaneletLayer::iterator & iter1,lanelet::LaneletLayer::iterator & iter2,int npos1,int npos2);
+                          lanelet::Id xLeftID2,lanelet::Id xRightID2,int npos1,int npos2);
 
 };