Răsfoiți Sursa

change driver_map_xodrload. support road borrow.

yuchuli 3 ani în urmă
părinte
comite
1187674fca

+ 39 - 0
src/driver/driver_map_xodrload/globalplan.cpp

@@ -1760,6 +1760,40 @@ std::vector<int> GetLWIndex(std::vector<iv::lanewidthabcd> xvectorLWA,int nlane)
     return xvectorindex;
 }
 
+void CalcBorringRoad(pathsection xps,std::vector<PlanPoint> & xvectorPP)
+{
+    if(xps.mpRoad->GetRoadBorrowCount() == 0)
+    {
+        return;
+    }
+
+    Road * pRoad = xps.mpRoad;
+    unsigned int nborrowsize = pRoad->GetRoadBorrowCount();
+    unsigned int i;
+    unsigned int nPPCount = xvectorPP.size();
+    for(i=0;i<nborrowsize;i++)
+    {
+        RoadBorrow * pborrow = pRoad->GetRoadBorrow(i);
+        if(pborrow == NULL)
+        {
+            std::cout<<"warning:can't get borrow"<<std::endl;
+            continue;
+        }
+        if((pborrow->GetMode() == "All")||((pborrow->GetMode()=="R2L")&&(xps.mainsel<0))||((pborrow->GetMode()=="L2R")&&(xps.mainsel>0)))
+        {
+            unsigned int j;
+            double soffset = pborrow->GetS();
+            double borrowlen = pborrow->GetLength();
+            for(j=0;j<xvectorPP.size();j++)
+            {
+                if((xvectorPP[j].mS>=soffset)&&(xvectorPP[j].mS<=(soffset + borrowlen)))
+                {
+                    xvectorPP[j].mbBoringRoad = true;
+                }
+            }
+        }
+    }
+}
 
 void CalcInLaneAvoid(pathsection xps,std::vector<PlanPoint> & xvectorPP,const double fvehiclewidth,
                      const int nchang1,const int nchang2,const int nchangpoint)
@@ -2271,6 +2305,11 @@ std::vector<PlanPoint> GetLanePoint(pathsection xps,std::vector<PlanPoint> xvPP,
 
     CalcInLaneAvoid(xps,xvectorPP,fvehiclewidth,nchange1,nchange2,nchangepoint);
 
+    if(xps.mpRoad->GetRoadBorrowCount()>0)
+    {
+        CalcBorringRoad(xps,xvectorPP);
+    }
+
 
     if(xps.mnStartLaneSel > 0)
     {

+ 1 - 0
src/driver/driver_map_xodrload/globalplan.h

@@ -39,6 +39,7 @@ public:
     double mfSecx;
     double mfSecy;
     int nlrchange; //1 left 2 right
+    bool mbBoringRoad = false;
 };
 
 class LaneChangePoint

+ 6 - 0
src/driver/driver_map_xodrload/main.cpp

@@ -537,6 +537,12 @@ void SetPlan(xodrobj xo)
 
         data->mbInLaneAvoid = xPlan[i].bInlaneAvoid;
 
+        if(xPlan[i].mbBoringRoad)
+        {
+            data->roadOri = 0;
+            data->roadSum = 2;
+        }
+
         data->mode2 = xPlan[i].nSignal;
         if(data->mode2 == 3000)
         {

+ 2 - 0
src/tool/map_lanetoxodr/mainwindow.cpp

@@ -5352,4 +5352,6 @@ void MainWindow::on_actionEdit_Road_Borrow_triggered()
     std::string strroadid = mpCBRoad->currentText().toStdString();
     DialogRoadBorrow rbd(&mxodr,strroadid,this);
     int res = rbd.exec();
+
+    mpfb->SetOpenDrive(mxodr);
 }

+ 1 - 1
src/tool/tool_xodrobj/tool_xodrobj.pro

@@ -73,7 +73,7 @@ FORMS += \
     error( "Couldn't find the TinyXML.pri file!" )
 }
 
-INCLUDEPATH += $$PWD/../map_lanetoxodr
+INCLUDEPATH += $$PWD/../../common/common/xodr
 
 
 DISTFILES += \