瀏覽代碼

change driver_map_xodrload.

yuchuli 2 年之前
父節點
當前提交
9a15a702ec
共有 2 個文件被更改,包括 28 次插入3 次删除
  1. 23 3
      src/driver/driver_map_xodrload/globalplan.cpp
  2. 5 0
      src/driver/driver_map_xodrload/main.cpp

+ 23 - 3
src/driver/driver_map_xodrload/globalplan.cpp

@@ -2768,6 +2768,8 @@ void ChangeLane(std::vector<PlanPoint> & xvectorPP)
 {
     int i = 0;
     int nsize = xvectorPP.size();
+    int nstart = -1;
+    int nend = -1;
     for(i=0;i<nsize;i++)
     {
         if((xvectorPP[i].mfSecx == xvectorPP[i].x)&&(xvectorPP[i].mfSecy == xvectorPP[i].y))
@@ -2788,7 +2790,7 @@ void ChangeLane(std::vector<PlanPoint> & xvectorPP)
             int nchangepoint = 300;
             double froadlen = sqrt(pow(xvectorPP[k].x - xvectorPP[i].x,2)
                                    +pow(xvectorPP[k].y - xvectorPP[i].y,2));
-            const double fMAXCHANGE = 100;
+            const double fMAXCHANGE = 50;
             if(froadlen<fMAXCHANGE)
             {
                 nchangepoint = nnum;
@@ -2801,8 +2803,8 @@ void ChangeLane(std::vector<PlanPoint> & xvectorPP)
             qDebug(" road %d len is %f changepoint is %d nnum is %d",
                    xvectorPP[k-1].nRoadID,froadlen,nchangepoint,nnum);
 
-            int nstart = i + nnum/2 -nchangepoint/2;
-            int nend = i+nnum/2 + nchangepoint/2;
+            nstart = i + nnum/2 -nchangepoint/2;
+            nend = i+nnum/2 + nchangepoint/2;
             if(nnum<300)
             {
                 nstart = i;
@@ -2838,6 +2840,24 @@ void ChangeLane(std::vector<PlanPoint> & xvectorPP)
 
         }
     }
+
+    if(nstart != -1)
+    {
+        for(i=0;i<nstart;i++)
+        {
+            xvectorPP[i].nlrchange = 0;
+            if(i>nsize)break;
+        }
+    }
+    if(nend >0)
+    {
+        for(i=nend;i<nsize;i++)
+        {
+            xvectorPP[i].nlrchange = 0;
+            if(i>nsize)break;
+        }
+    }
+
 }
 
 #include <QFile>

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

@@ -929,6 +929,11 @@ void SetPlan(xodrobj xo)
             }
         }
 
+//        if(data->roadMode != 0)
+//        {
+//            std::cout<<"i: "<<i<<std::endl;
+//        }
+
         data->gps_lat = gps_lat;
         data->gps_lat_avoidleft = gps_lat_avoidleft;
         data->gps_lat_avoidright = gps_lat_avoidright;