Browse Source

edit decide_gps_00.cpp by liusunan

fujiankuan 4 years ago
parent
commit
b311afa079
30 changed files with 1764 additions and 308 deletions
  1. 0 125
      deploy.sh
  2. 2 0
      src/decition/decition_brain/decition/adc_tools/compute_00.cpp
  3. 6 4
      src/decition/decition_brain_sf/decition/adc_controller/pid_controller.cpp
  4. 125 115
      src/decition/decition_brain_sf/decition/decide_gps_00.cpp
  5. 141 39
      src/tool/map_lanetoxodr/OpenDrive/ObjectSignal.cpp
  6. 26 9
      src/tool/map_lanetoxodr/OpenDrive/ObjectSignal.h
  7. 6 0
      src/tool/map_lanetoxodr/OpenDrive/OpenDrive.cpp
  8. 3 0
      src/tool/map_lanetoxodr/OpenDrive/OpenDrive.h
  9. 55 4
      src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlParser.cpp
  10. 2 0
      src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlParser.h
  11. 42 0
      src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlWriter.cpp
  12. 2 0
      src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlWriter.h
  13. 2 2
      src/tool/map_lanetoxodr/OpenDrive/Road.cpp
  14. 2 2
      src/tool/map_lanetoxodr/OpenDrive/Road.h
  15. 9 0
      src/tool/map_lanetoxodr/mainwindow.cpp
  16. 3 0
      src/tool/map_lanetoxodr/mainwindow.h
  17. 6 0
      src/tool/map_lanetoxodr/mainwindow.ui
  18. 10 1
      src/tool/map_lanetoxodr/map_lanetoxodr.pro
  19. 305 0
      src/tool/map_lanetoxodr/trafficlightdialog.cpp
  20. 48 0
      src/tool/map_lanetoxodr/trafficlightdialog.h
  21. 521 0
      src/tool/map_lanetoxodr/trafficlightdialog.ui
  22. 40 0
      src/tool/map_lanetoxodr/trafficlightlanevaliditydialog.cpp
  23. 27 0
      src/tool/map_lanetoxodr/trafficlightlanevaliditydialog.h
  24. 78 0
      src/tool/map_lanetoxodr/trafficlightlanevaliditydialog.ui
  25. 76 0
      src/tool/map_lanetoxodr/trafficlightpositiondialog.cpp
  26. 30 0
      src/tool/map_lanetoxodr/trafficlightpositiondialog.h
  27. 170 0
      src/tool/map_lanetoxodr/trafficlightpositiondialog.ui
  28. 6 3
      src/tool/tool_electronic_fence/mainwindow.cpp
  29. 7 0
      src/ui/ADCIntelligentShow_grpc/adcintelligentshow.cpp
  30. 14 4
      src/ui/ADCIntelligentShow_grpc/adcintelligentshow.ui

+ 0 - 125
deploy.sh

@@ -1,125 +0,0 @@
-#! /bin/bash
-
-#Qtgccdir=''
-Qtgccdir='/usr/lib/aarch64-linux-gnu/qt5'
-QtPlatformdir=$Qtgccdir/plugins/platforms
-QtLibDir=/usr/lib/aarch64-linux-gnu/
-
-if [ ${#Qtgccdir} -lt 6 ]; then
-  echo "Because not set gcc_64 , so auto find gcc_64 "
-  optfiles=`find /opt -name 'gcc_64'` 
-  for entry in $optfiles
-  do
-     if [ ${entry:0-6:6} == "gcc_64" ];  then
-       if [ -d $entry ];  then
-          Qtgccdir="$entry"
-	  echo -e "\033[32m""  -----found gccdir:"$Qtgccdir"\033[0m"
-       fi
-     fi
-  done
-fi
-
-if [ ${#Qtgccdir} -lt 6 ]; then
-  if [ -d '/usr/lib/aarch64-linux-gnu/qt5' ]; then
-    Qtgccdir='/usr/lib/aarch64-linux-gnu/qt5'
-  else 
-    echo "if NVIDIA,please sudo apt install qt"
-  fi
-fi
-
-if [ ${#Qtgccdir} -lt 6 ]; then
-   echo -e "\033[31m""  -----not found gccdir: so exit""\033[0m"
-   exit 1
-fi
-
-
-if [ "$#" -lt 1 ]; then
-	echo "没有输入"
-	echo "$1"
-	exit
-fi
-
-ignore_lib_name=(
-libstdc++.so.*
-libm.so.*
-libgcc_s.so.*
-libc.so.*
-libpthread.so.*
-libGL.so.*
-libz.so.*
-libgthread*
-libglib*
-libexpat*
-libxcb*
-libdl.so.*
-libxshmfence*
-libglapi.so.*
-libXext.so.*
-libXdamage.so.*
-libXfixes.so.*
-libX11*
-libXxf86vm.so.*
-libdrm.so.*
-libpcre.so.*
-libXau.so.*
-libXdmcp.so.*
-)
-
-EXE="$1"
-PWD=`pwd`
-rm -rf app
-mkdir app
-cd app
-mkdir lib
-cd ..
-mkdir commonlib
-cd commonlib
-mkdir platforms
-cp $QtPlatformdir/libqxcb.so platforms
-cd platforms
-mkdir lib
-libfiles=`ldd libqxcb.so | awk '{ if(match($3,"^/"))printf("%s "),$3 }'` 
-cp $libfiles $PWD/lib 
-cd ..
-mkdir lib
-cp $QtLibDir/libQt5DBus.* $PWD/lib
-cp $QtLibDir/libQt5XcbQpa.* $PWD/lib
-rm -rf $PWD/platforms/lib
-cd platforms
-
-cd ..
-cd ..
-
-files=`ldd $EXE | awk '{ if(match($3,"^/"))printf("%s "),$3 }'`
-cp $files $PWD/app/lib
-cp $PWD/commonlib/lib/* $PWD/app/lib
-cp -r  $PWD/commonlib/platforms $PWD/app
-cp $EXE $PWD/app
-
-for x in ${ignore_lib_name[@]}
-do
-rm -f $PWD/app/lib/${x}
-done
-
-rm -rf commonlib
-
-cd app
-patchelf --set-rpath '$ORIGIN/lib/' $EXE
-if [ "$?" != 0 ];then
-	echo -e "\e[31m deploy.sh: patchelf $EXE faile, Ensure patchelf tool installed\e[0m"
-	exit 1
-fi
-cd platforms
-patchelf --set-rpath '$ORIGIN/../lib/' libqxcb.so
-if [ "$?" != 0 ];then
-	echo -e "\e[31m deploy.sh: patchelf $EXE faile, Ensure patchelf tool installed\e[0m"
-	exit 1
-fi
-cd ..
-cd ..
-
-cp -r app $PWD/deploy/
-
-rm -rf app
-
-

+ 2 - 0
src/decition/decition_brain/decition/adc_tools/compute_00.cpp

@@ -835,6 +835,8 @@ int  iv::decition::Compute00::getEsrIndex(std::vector<Point2D> gpsTrace,int road
 
 
                 if (abs(xxx - gpsTrace[j].x) <= (3.0*Veh_Width / 4.0+fxiuzhengCs) && abs(yyy - (gpsTrace[j].y)) <= 1)
                 if (abs(xxx - gpsTrace[j].x) <= (3.0*Veh_Width / 4.0+fxiuzhengCs) && abs(yyy - (gpsTrace[j].y)) <= 1)
                 {
                 {
+                    return i;
+
 
 
                     if (lastEsrID == i)
                     if (lastEsrID == i)
                     {
                     {

+ 6 - 4
src/decition/decition_brain_sf/decition/adc_controller/pid_controller.cpp

@@ -57,7 +57,7 @@ float iv::decition::PIDController::getPidAngle(float realSpeed, std::vector<Poin
 
 
     double KEang = 14, KEPos = 10, DEang = 0, DEPos = 0,IEpos=0,IEang=0;
     double KEang = 14, KEPos = 10, DEang = 0, DEPos = 0,IEpos=0,IEang=0;
     if(ServiceCarStatus.msysparam.mvehtype=="zhongche"){
     if(ServiceCarStatus.msysparam.mvehtype=="zhongche"){
-        IEpos=1,IEang=0.5;
+        KEang = 14, KEPos = 100,IEpos=3,IEang=0.5;
     }
     }
 
 
 
 
@@ -131,9 +131,11 @@ float iv::decition::PIDController::getPidAngle(float realSpeed, std::vector<Poin
     //    else if (ang < -angleLimit) {
     //    else if (ang < -angleLimit) {
     //        ang = -angleLimit;
     //        ang = -angleLimit;
     //    }
     //    }
-    if (lastAng >-3000&&lastAng<3000) {
-        ang = 0.2 * lastAng + 0.8 * ang;
-    }
+
+        if (lastAng >-3000&&lastAng<3000) {
+            ang = 0.2 * lastAng + 0.8 * ang;
+        }
+
     if(ang >-3000&&ang<3000){
     if(ang >-3000&&ang<3000){
         lastAng = ang;
         lastAng = ang;
     }else{
     }else{

+ 125 - 115
src/decition/decition_brain_sf/decition/decide_gps_00.cpp

@@ -216,9 +216,9 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
 
 
 
 
 
 
-//    GPS_INS gps= Coordinate_UnTransfer(0,1.5,now_gps_ins);
-//    now_gps_ins.gps_x=gps.gps_x;
-//    now_gps_ins.gps_y=gps.gps_y;
+    //    GPS_INS gps= Coordinate_UnTransfer(0,1.5,now_gps_ins);
+    //    now_gps_ins.gps_x=gps.gps_x;
+    //    now_gps_ins.gps_y=gps.gps_y;
 
 
     //    GaussProjInvCal(now_gps_ins.gps_x, now_gps_ins.gps_y,&now_gps_ins.gps_lng, &now_gps_ins.gps_lat);
     //    GaussProjInvCal(now_gps_ins.gps_x, now_gps_ins.gps_y,&now_gps_ins.gps_lng, &now_gps_ins.gps_lat);
 
 
@@ -1093,13 +1093,16 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
     }
     }
 
 
     //2020-0106
     //2020-0106
-    if(vehState==avoiding){
-        controlAng=max(-150.0,controlAng);
-        controlAng=min(150.0,controlAng);
-    }
-    if(vehState==backOri){
-        controlAng=max(-120.0,controlAng);
-        controlAng=min(120.0,controlAng);
+    if(ServiceCarStatus.msysparam.mvehtype !="zhongche"){
+
+        if(vehState==avoiding){
+            controlAng=max(-150.0,controlAng);
+            controlAng=min(150.0,controlAng);
+        }
+        if(vehState==backOri){
+            controlAng=max(-120.0,controlAng);
+            controlAng=min(120.0,controlAng);
+        }
     }
     }
 
 
     //准备驻车
     //准备驻车
@@ -1677,15 +1680,18 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
     if ( vehState==changingRoad || vehState==chaocheBack)
     if ( vehState==changingRoad || vehState==chaocheBack)
     {
     {
         double lastAng = 0.0 - lastAngle;
         double lastAng = 0.0 - lastAngle;
-        if (controlAng>40)
-        {
-            controlAng =40;
-        }
-        else if (controlAng<-40)
-        {
-            controlAng = - 40;
-        }
 
 
+        if(ServiceCarStatus.msysparam.mvehtype !="zhongche"){
+
+            if (controlAng>40)
+            {
+                controlAng =40;
+            }
+            else if (controlAng<-40)
+            {
+                controlAng = - 40;
+            }
+        }
 
 
     }
     }
 
 
@@ -1847,6 +1853,10 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
     //------------------------------v2x traffic light end--------------------------------------------------------------------------------------
     //------------------------------v2x traffic light end--------------------------------------------------------------------------------------
 
 
 
 
+
+   // if(obsDistance>6.5){
+     //   obsDistance=500;
+    //}
     if(obsDistance>0 && obsDistance<10){
     if(obsDistance>0 && obsDistance<10){
         dSpeed=0;
         dSpeed=0;
     }
     }
@@ -1863,7 +1873,7 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
 
 
     // givlog->debug("SPEED","dSpeed is %f",dSpeed);
     // givlog->debug("SPEED","dSpeed is %f",dSpeed);
 
 
-     gps_decition->wheel_angle = 0.0 - controlAng;
+    gps_decition->wheel_angle = 0.0 - controlAng;
     phaseSpeedDecition(gps_decition, secSpeed, obsDistance, obsSpeed,now_gps_ins);
     phaseSpeedDecition(gps_decition, secSpeed, obsDistance, obsSpeed,now_gps_ins);
 
 
 
 
@@ -2636,74 +2646,74 @@ void iv::decition::DecideGps00::predictObsOnRoad(std::vector<iv::Perception::Per
 int iv::decition::DecideGps00::chooseAvoidRoad(iv::LidarGridPtr lidarGridPtr, GPS_INS now_gps_ins, const std::vector<GPSData> gpsMapLine,std::vector<iv::Perception::PerceptionOutput> lidar_per) {
 int iv::decition::DecideGps00::chooseAvoidRoad(iv::LidarGridPtr lidarGridPtr, GPS_INS now_gps_ins, const std::vector<GPSData> gpsMapLine,std::vector<iv::Perception::PerceptionOutput> lidar_per) {
     roadPre = -1;
     roadPre = -1;
 
 
-//    if (roadNow<roadOri)
-//    {
-//        for (int i = 0; i < roadNow; i++)
-//        {
-//            gpsTraceAvoid.clear();
-//            //	gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsR[int(abs(roadWidth * 2)*(roadOri-i))], lastGpsIndex);
-//            avoidX = (roadWidth)*(roadOri - i);
-//            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
-//            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
-//            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
-//        }
-
-
-//        for (int i = roadOri+1; i < roadSum; i++)
-//        {
-//            gpsTraceAvoid.clear();
-//            //	gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsL[int(abs(roadWidth * 2)*(i - roadOri))], lastGpsIndex);
-//            avoidX = (roadWidth)*(roadOri - i);
-//            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
-//            //	bsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
-//            computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, i,gpsMapLine,lidar_per);
-//        }
-//    }
-//    else if (roadNow>roadOri)
-//    {
-//        for (int i = 0; i < roadOri; i++)
-//        {
-//            gpsTraceAvoid.clear();
-//            //	gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsR[int(abs(roadWidth * 2)*(roadOri - i))], lastGpsIndex);
-//            avoidX = (roadWidth)*(roadOri - i);
-//            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
-//            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
-//            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
-//        }
-//        for (int i = roadNow + 1; i < roadSum; i++)
-//        {
-//            gpsTraceAvoid.clear();
-//            //		gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsL[int(abs(roadWidth * 2)*(i - roadOri))], lastGpsIndex);
-//            avoidX = (roadWidth)*(roadOri - i);
-//            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
-//            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
-//            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
-//        }
-
-//    }
-
-//    else
-//    {
-//        for (int i = 0; i < roadOri; i++)
-//        {
-//            gpsTraceAvoid.clear();
-//            //	gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsR[int(abs(roadWidth * 2)*(roadOri - i))], lastGpsIndex);
-//            avoidX = (roadWidth)*(roadOri - i);
-//            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
-//            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
-//            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
-//        }
-//        for (int i = roadOri + 1; i < roadSum; i++)
-//        {
-//            gpsTraceAvoid.clear();
-//            //		gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsL[int(abs(roadWidth * 2)*(i - roadOri))], lastGpsIndex);
-//            avoidX = (roadWidth)*(roadOri - i);
-//            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
-//            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
-//            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
-//        }
-
-//    }
+    //    if (roadNow<roadOri)
+    //    {
+    //        for (int i = 0; i < roadNow; i++)
+    //        {
+    //            gpsTraceAvoid.clear();
+    //            //	gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsR[int(abs(roadWidth * 2)*(roadOri-i))], lastGpsIndex);
+    //            avoidX = (roadWidth)*(roadOri - i);
+    //            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
+    //            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
+    //            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
+    //        }
+
+
+    //        for (int i = roadOri+1; i < roadSum; i++)
+    //        {
+    //            gpsTraceAvoid.clear();
+    //            //	gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsL[int(abs(roadWidth * 2)*(i - roadOri))], lastGpsIndex);
+    //            avoidX = (roadWidth)*(roadOri - i);
+    //            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
+    //            //	bsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
+    //            computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, i,gpsMapLine,lidar_per);
+    //        }
+    //    }
+    //    else if (roadNow>roadOri)
+    //    {
+    //        for (int i = 0; i < roadOri; i++)
+    //        {
+    //            gpsTraceAvoid.clear();
+    //            //	gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsR[int(abs(roadWidth * 2)*(roadOri - i))], lastGpsIndex);
+    //            avoidX = (roadWidth)*(roadOri - i);
+    //            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
+    //            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
+    //            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
+    //        }
+    //        for (int i = roadNow + 1; i < roadSum; i++)
+    //        {
+    //            gpsTraceAvoid.clear();
+    //            //		gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsL[int(abs(roadWidth * 2)*(i - roadOri))], lastGpsIndex);
+    //            avoidX = (roadWidth)*(roadOri - i);
+    //            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
+    //            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
+    //            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
+    //        }
+
+    //    }
+
+    //    else
+    //    {
+    //        for (int i = 0; i < roadOri; i++)
+    //        {
+    //            gpsTraceAvoid.clear();
+    //            //	gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsR[int(abs(roadWidth * 2)*(roadOri - i))], lastGpsIndex);
+    //            avoidX = (roadWidth)*(roadOri - i);
+    //            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
+    //            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
+    //            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
+    //        }
+    //        for (int i = roadOri + 1; i < roadSum; i++)
+    //        {
+    //            gpsTraceAvoid.clear();
+    //            //		gpsTraceAvoid = getGpsTrace(now_gps_ins, gmapsL[int(abs(roadWidth * 2)*(i - roadOri))], lastGpsIndex);
+    //            avoidX = (roadWidth)*(roadOri - i);
+    //            gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
+    //            //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
+    //            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
+    //        }
+
+    //    }
 
 
     for (int i =  0; i < roadSum; i++)
     for (int i =  0; i < roadSum; i++)
     {
     {
@@ -2712,7 +2722,7 @@ int iv::decition::DecideGps00::chooseAvoidRoad(iv::LidarGridPtr lidarGridPtr, GP
         avoidX = (roadWidth)*(roadOri - i);
         avoidX = (roadWidth)*(roadOri - i);
         gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
         gpsTraceAvoid = getGpsTraceOffset(gpsTraceOri, avoidX);
         //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
         //	computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, roadNow + i);
-       computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, i,gpsMapLine,lidar_per);
+        computeObsOnRoad(lidarGridPtr, gpsTraceAvoid, i,gpsMapLine,lidar_per);
     }
     }
 
 
     if (lidarGridPtr!=NULL)
     if (lidarGridPtr!=NULL)
@@ -2774,33 +2784,33 @@ int iv::decition::DecideGps00::chooseAvoidRoad(iv::LidarGridPtr lidarGridPtr, GP
 int iv::decition::DecideGps00::chooseBackRoad(iv::LidarGridPtr lidarGridPtr, GPS_INS now_gps_ins, std::vector<GPSData> gpsMapLine,std::vector<iv::Perception::PerceptionOutput> lidar_per) {
 int iv::decition::DecideGps00::chooseBackRoad(iv::LidarGridPtr lidarGridPtr, GPS_INS now_gps_ins, std::vector<GPSData> gpsMapLine,std::vector<iv::Perception::PerceptionOutput> lidar_per) {
     roadPre = -1;
     roadPre = -1;
 
 
-//    computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
-
-
-
-//    if (roadNow>roadOri+1)
-//    {
-//        for (int i = roadOri+1; i < roadNow; i++)
-//        {
-//            gpsTraceBack.clear();
-//            //	gpsTraceBack = getGpsTrace(now_gps_ins, gmapsL[int(abs(roadWidth * 2)*(i-roadOri))], lastGpsIndex);
-//            avoidX = (roadWidth)*(roadOri - i);
-//            gpsTraceBack = getGpsTraceOffset(gpsTraceOri, avoidX);
-//            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
-//        }
-//    }
-//    else if (roadNow < roadOri - 1) {
-
-//        for (int i = roadOri - 1; i > roadNow; i--)
-//        {
-//            gpsTraceBack.clear();
-//            //	gpsTraceBack = getGpsTrace(now_gps_ins, gmapsR[int(abs(roadWidth * 2)*(roadOri-i))], lastGpsIndex);
-//            avoidX = (roadWidth)*(roadOri - i);
-//            gpsTraceBack = getGpsTraceOffset(gpsTraceOri, avoidX);
-//            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
-//        }
-
-//    }
+    //    computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
+
+
+
+    //    if (roadNow>roadOri+1)
+    //    {
+    //        for (int i = roadOri+1; i < roadNow; i++)
+    //        {
+    //            gpsTraceBack.clear();
+    //            //	gpsTraceBack = getGpsTrace(now_gps_ins, gmapsL[int(abs(roadWidth * 2)*(i-roadOri))], lastGpsIndex);
+    //            avoidX = (roadWidth)*(roadOri - i);
+    //            gpsTraceBack = getGpsTraceOffset(gpsTraceOri, avoidX);
+    //            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
+    //        }
+    //    }
+    //    else if (roadNow < roadOri - 1) {
+
+    //        for (int i = roadOri - 1; i > roadNow; i--)
+    //        {
+    //            gpsTraceBack.clear();
+    //            //	gpsTraceBack = getGpsTrace(now_gps_ins, gmapsR[int(abs(roadWidth * 2)*(roadOri-i))], lastGpsIndex);
+    //            avoidX = (roadWidth)*(roadOri - i);
+    //            gpsTraceBack = getGpsTraceOffset(gpsTraceOri, avoidX);
+    //            computeObsOnRoad(lidarGridPtr, gpsTraceNow, roadNow,gpsMapLine,lidar_per);
+    //        }
+
+    //    }
 
 
 
 
     for (int i =  0; i <roadSum; i++)
     for (int i =  0; i <roadSum; i++)

+ 141 - 39
src/tool/map_lanetoxodr/OpenDrive/ObjectSignal.cpp

@@ -1,5 +1,6 @@
 #include "ObjectSignal.h"
 #include "ObjectSignal.h"
 
 
+#include <iostream>
 
 
 signal_positionRoad::signal_positionRoad(double s, double t, double zOffset, double hOffset, double pitch, double roll)
 signal_positionRoad::signal_positionRoad(double s, double t, double zOffset, double hOffset, double pitch, double roll)
 {
 {
@@ -142,10 +143,36 @@ void signal_positionInertial::Setroll(double roll)
 }
 }
 
 
 
 
+signal_laneValidity::signal_laneValidity(int fromLane,int toLane)
+{
+    mfromLane = fromLane;
+    mtoLane = toLane;
+}
+
+int signal_laneValidity::GetfromLane()
+{
+    return mfromLane;
+}
+
+int signal_laneValidity::GettoLane()
+{
+    return mtoLane;
+}
+
+void signal_laneValidity::SetfromLane(int fromLane)
+{
+    mfromLane = fromLane;
+}
+
+void signal_laneValidity::SettoLane(int toLane)
+{
+    mtoLane = toLane;
+}
+
 
 
 Signal::Signal(double s, double t, std::string id, std::string name, bool dynamic,string orientation,
 Signal::Signal(double s, double t, std::string id, std::string name, bool dynamic,string orientation,
-               double zOffset, int type, std::string country, std::string countryRevision,
-               int subtype, double hOffset, double pitch, double roll, double height, double width)
+               double zOffset, string type, std::string country, std::string countryRevision,
+               string subtype, double hOffset, double pitch, double roll, double height, double width)
 {
 {
     ms = s;
     ms = s;
     mt = t;
     mt = t;
@@ -163,45 +190,102 @@ Signal::Signal(double s, double t, std::string id, std::string name, bool dynami
     mroll = roll;
     mroll = roll;
     mheight = height;
     mheight = height;
     mwidth = width;
     mwidth = width;
+    mpsignal_laneValidity = 0;
     mpsignal_positionInertial = 0;
     mpsignal_positionInertial = 0;
     mpsignal_positionRoad = new signal_positionRoad(s,t,zOffset,hOffset,pitch,roll);
     mpsignal_positionRoad = new signal_positionRoad(s,t,zOffset,hOffset,pitch,roll);
 }
 }
 
 
+Signal::Signal()
+{
+    mpsignal_positionInertial = 0;
+    mpsignal_positionRoad = 0;
+    mpsignal_laneValidity = 0;
+
+}
 Signal::~Signal()
 Signal::~Signal()
 {
 {
-//    if(mpsignal_positionInertial != 0)delete mpsignal_positionInertial;
-//    if(mpsignal_positionRoad != 0)delete mpsignal_positionRoad;
-}
-
-//Signal& Signal::operator=(const Signal& x)
-//{
-//    if (this != &x)
-//    {
-//        this->Sets(x.Gets());
-//        ms = x.Gets();
-//        mt = x.Gett();
-//        mid = x.Getid();
-//        mname = x.Getname();
-//        mdynamic = x.Getdynamic();
-//        morientation = x.Getorientation();
-//        mzOffset = x.GetzOffset();
-//        mtype = x.Gettype();
-//        mcountry = x.Getcountry();
-//        mcountryRevision = x.GetcountryRevision();
-//        msubtype = x.Getsubtype();
-//        mhOffset = x.GethOffset();
-//        mpitch = x.Getpitch();
-//        mroll = x.Getroll();
-//        mheight = x.Getheight();
-//        mwidth = x.Getwidth();
-//        mpsignal_positionInertial = 0;
-//        signal_positionRoad * p = x.GetpositionRoad();
-//        mpsignal_positionRoad = new signal_positionRoad(p->Gets(),p->Gett(),
-//                                                        p->GetzOffset(),p->GethOffset(),
-//                                                        p->Getpitch(),p->Getroll());
-//    }
-//    return *this;
-//}
+    if(mpsignal_laneValidity != 0)delete mpsignal_laneValidity;
+    if(mpsignal_positionInertial != 0)delete mpsignal_positionInertial;
+    if(mpsignal_positionRoad != 0)delete mpsignal_positionRoad;
+}
+
+Signal& Signal::operator=(const Signal& x)
+{
+    if (this != &x)
+    {
+        this->ms = x.ms;
+        this->mt = x.mt;
+        this->mid = x.mid;
+        this->mname = x.mname;
+        this->mdynamic = x.mdynamic;
+        this->morientation = x.morientation;
+        this->mzOffset = x.mzOffset;
+        this->mtype = x.mtype;
+        this->mcountry = x.mcountry;
+        this->mcountryRevision = x.mcountryRevision;
+        this->msubtype = x.msubtype;
+        this->mhOffset = x.mhOffset;
+        this->mpitch = x.mpitch;
+        this->mroll = x.mroll;
+        this->mheight = x.mheight;
+        this->mwidth = x.mwidth;
+        this->mpsignal_positionInertial = 0;
+        if(x.mpsignal_positionInertial != 0)
+        {
+            this->mpsignal_positionInertial = new signal_positionInertial(x.mpsignal_positionInertial->Getx(),
+                                                                      x.mpsignal_positionInertial->Gety(),
+                                                                      x.mpsignal_positionInertial->Getz(),
+                                                                      x.mpsignal_positionInertial->Gethdg(),
+                                                                      x.mpsignal_positionInertial->Getpitch(),
+                                                                      x.mpsignal_positionInertial->Getroll());
+        }
+        this->mpsignal_laneValidity = 0;
+        if(x.mpsignal_laneValidity != 0)
+        {
+            this->mpsignal_laneValidity = new signal_laneValidity(x.mpsignal_laneValidity->GetfromLane(),
+                                                              x.mpsignal_laneValidity->GettoLane());
+        }
+        this->mpsignal_positionRoad = new signal_positionRoad(ms,mt,mzOffset,mhOffset,mpitch,mroll);
+    }
+    return *this;
+}
+
+Signal::Signal(const Signal &x)
+{
+    ms = x.ms;
+    mt = x.mt;
+    mid = x.mid;
+    mname = x.mname;
+    mdynamic = x.mdynamic;
+    morientation = x.morientation;
+    mzOffset = x.mzOffset;
+    mtype = x.mtype;
+    mcountry = x.mcountry;
+    mcountryRevision = x.mcountryRevision;
+    msubtype = x.msubtype;
+    mhOffset = x.mhOffset;
+    mpitch = x.mpitch;
+    mroll = x.mroll;
+    mheight = x.mheight;
+    mwidth = x.mwidth;
+    this->mpsignal_positionInertial = 0;
+    if(x.mpsignal_positionInertial != 0)
+    {
+        this->mpsignal_positionInertial = new signal_positionInertial(x.mpsignal_positionInertial->Getx(),
+                                                                  x.mpsignal_positionInertial->Gety(),
+                                                                  x.mpsignal_positionInertial->Getz(),
+                                                                  x.mpsignal_positionInertial->Gethdg(),
+                                                                  x.mpsignal_positionInertial->Getpitch(),
+                                                                  x.mpsignal_positionInertial->Getroll());
+    }
+    this->mpsignal_laneValidity = 0;
+    if(x.mpsignal_laneValidity != 0)
+    {
+        this->mpsignal_laneValidity = new signal_laneValidity(x.mpsignal_laneValidity->GetfromLane(),
+                                                          x.mpsignal_laneValidity->GettoLane());
+    }
+    mpsignal_positionRoad = new signal_positionRoad(ms,mt,mzOffset,mhOffset,mpitch,mroll);
+}
 
 
 double Signal::Gets()
 double Signal::Gets()
 {
 {
@@ -238,7 +322,7 @@ double Signal::GetzOffset()
     return mzOffset;
     return mzOffset;
 }
 }
 
 
-int Signal::Gettype()
+string Signal::Gettype()
 {
 {
     return mtype;
     return mtype;
 }
 }
@@ -253,7 +337,7 @@ string Signal::GetcountryRevision()
     return mcountryRevision;
     return mcountryRevision;
 }
 }
 
 
-int Signal::Getsubtype()
+string Signal::Getsubtype()
 {
 {
     return msubtype;
     return msubtype;
 }
 }
@@ -328,7 +412,7 @@ void Signal::SetzOffset(double zOffset)
     mzOffset = zOffset;
     mzOffset = zOffset;
 }
 }
 
 
-void Signal::Settype(int type)
+void Signal::Settype(string type)
 {
 {
     mtype = type;
     mtype = type;
 }
 }
@@ -343,7 +427,7 @@ void Signal::SetcountryRevision(std::string countryRevision)
     mcountryRevision = countryRevision;
     mcountryRevision = countryRevision;
 }
 }
 
 
-void Signal::Setsubtype(int subtype)
+void Signal::Setsubtype(string subtype)
 {
 {
     msubtype = subtype;
     msubtype = subtype;
 }
 }
@@ -373,6 +457,19 @@ void Signal::Setwidth(double width)
     mwidth = width;
     mwidth = width;
 }
 }
 
 
+void Signal::SetlaneValidity(int fromLane, int toLane)
+{
+    if(mpsignal_laneValidity == 0)
+    {
+        mpsignal_laneValidity = new signal_laneValidity(fromLane,toLane);
+    }
+    else
+    {
+        mpsignal_laneValidity->SetfromLane(fromLane);
+        mpsignal_laneValidity->SettoLane(toLane);
+    }
+}
+
 void Signal::SetpositionRoad(double s, double t, double zOffset, double hOffset, double pitch,double roll)
 void Signal::SetpositionRoad(double s, double t, double zOffset, double hOffset, double pitch,double roll)
 {
 {
     if(mpsignal_positionRoad == 0)
     if(mpsignal_positionRoad == 0)
@@ -407,6 +504,11 @@ void Signal::SetpositionInertial(double x, double y, double z, double hdg, doubl
     }
     }
 }
 }
 
 
+signal_laneValidity * Signal::GetlaneValidity()
+{
+    return mpsignal_laneValidity;
+}
+
 
 
 
 
 
 

+ 26 - 9
src/tool/map_lanetoxodr/OpenDrive/ObjectSignal.h

@@ -70,6 +70,18 @@ public:
     void Setroll(double roll);
     void Setroll(double roll);
 };
 };
 
 
+class signal_laneValidity
+{
+private:
+    int mfromLane;
+    int mtoLane;
+public:
+    signal_laneValidity(int fromLane,int toLane);
+    int GetfromLane();
+    int GettoLane();
+    void SetfromLane(int fromLane);
+    void SettoLane(int toLane);
+};
 
 
 
 
 //***********************************************************************************
 //***********************************************************************************
@@ -85,10 +97,10 @@ private:
     bool mdynamic;
     bool mdynamic;
     string morientation;
     string morientation;
     double mzOffset;
     double mzOffset;
-    int mtype;
+    string mtype;
     string mcountry;
     string mcountry;
     string mcountryRevision;
     string mcountryRevision;
-    int msubtype;
+    string msubtype;
     double mhOffset;
     double mhOffset;
     double mpitch;
     double mpitch;
     double mroll;
     double mroll;
@@ -96,11 +108,14 @@ private:
     double mwidth;
     double mwidth;
     signal_positionRoad * mpsignal_positionRoad;
     signal_positionRoad * mpsignal_positionRoad;
     signal_positionInertial * mpsignal_positionInertial;
     signal_positionInertial * mpsignal_positionInertial;
+    signal_laneValidity * mpsignal_laneValidity;
 public:
 public:
-    Signal(double s,double t,string id,string name,bool dynamic,string orientation,double zOffset,int type,string country,string countryRevision,
-           int subtype,double hOffset,double pitch,double roll ,double height,double width);
+    Signal(double s,double t,string id,string name,bool dynamic,string orientation,double zOffset,string type,string country,string countryRevision,
+           string subtype,double hOffset,double pitch,double roll ,double height,double width);
+    Signal();
     ~Signal();
     ~Signal();
-//    Signal& operator=(const Signal& x);
+    Signal& operator=(const Signal& x);
+    Signal(const Signal & x);
     double Gets();
     double Gets();
     double Gett();
     double Gett();
     string Getid();
     string Getid();
@@ -108,10 +123,10 @@ public:
     bool Getdynamic();
     bool Getdynamic();
     string Getorientation();
     string Getorientation();
     double GetzOffset();
     double GetzOffset();
-    int Gettype();
+    string Gettype();
     string Getcountry();
     string Getcountry();
     string GetcountryRevision();
     string GetcountryRevision();
-    int Getsubtype();
+    string Getsubtype();
     double GethOffset();
     double GethOffset();
     double Getpitch();
     double Getpitch();
     double Getroll();
     double Getroll();
@@ -119,6 +134,7 @@ public:
     double Getwidth();
     double Getwidth();
     signal_positionRoad * GetpositionRoad();
     signal_positionRoad * GetpositionRoad();
     signal_positionInertial * GetpositionInertial();
     signal_positionInertial * GetpositionInertial();
+    signal_laneValidity * GetlaneValidity();
     void Sets(double s);
     void Sets(double s);
     void Sett(double t);
     void Sett(double t);
     void Setid(string id);
     void Setid(string id);
@@ -126,15 +142,16 @@ public:
     void Setdynamic(bool dynamic);
     void Setdynamic(bool dynamic);
     void Setorientation(string orientation);
     void Setorientation(string orientation);
     void SetzOffset(double zOffset);
     void SetzOffset(double zOffset);
-    void Settype(int type);
+    void Settype(string type);
     void Setcountry(string country);
     void Setcountry(string country);
     void SetcountryRevision(string countryRevision);
     void SetcountryRevision(string countryRevision);
-    void Setsubtype(int subtype);
+    void Setsubtype(string subtype);
     void SethOffset(double hOffset);
     void SethOffset(double hOffset);
     void Setpitch(double pitch);
     void Setpitch(double pitch);
     void Setroll(double roll);
     void Setroll(double roll);
     void Setheight(double height);
     void Setheight(double height);
     void Setwidth(double width);
     void Setwidth(double width);
+    void SetlaneValidity(int fromLane, int toLane);
     void SetpositionRoad(double s,double t, double zOffset,double hOffset,double pitch,double roll);
     void SetpositionRoad(double s,double t, double zOffset,double hOffset,double pitch,double roll);
     void SetpositionInertial(double x,double y, double z, double hdg,double pitch,double roll);
     void SetpositionInertial(double x,double y, double z, double hdg,double pitch,double roll);
 
 

+ 6 - 0
src/tool/map_lanetoxodr/OpenDrive/OpenDrive.cpp

@@ -299,3 +299,9 @@ void Header::SetXYValues(double north, double south, double east,double west)
 	mEast=east;
 	mEast=east;
 	mWest=west;
 	mWest=west;
 }
 }
+
+void Header::GetLat0Lon0(double &lat0, double &lon0)
+{
+    lat0 = mLat0;
+    lon0 = mLon0;
+}

+ 3 - 0
src/tool/map_lanetoxodr/OpenDrive/OpenDrive.h

@@ -181,6 +181,9 @@ public:
 
 
     void SetAllParams(unsigned short int revMajor, unsigned short int revMinor, string name, float version, string date,
     void SetAllParams(unsigned short int revMajor, unsigned short int revMinor, string name, float version, string date,
         double north, double south, double east,double west,double lat0,double lon0,double hdg0);
         double north, double south, double east,double west,double lat0,double lon0,double hdg0);
+
+
+    void GetLat0Lon0(double & lat0,double & lon0);
 };
 };
 
 
 
 

+ 55 - 4
src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlParser.cpp

@@ -937,10 +937,10 @@ bool OpenDriveXmlParser::ReadSignal(Road *road, TiXmlElement *node)
     string strdynamic;
     string strdynamic;
     string orientation;
     string orientation;
     double zOffset;
     double zOffset;
-    int type;
+    string type;
     string country;
     string country;
     string countryRevision;
     string countryRevision;
-    int subtype;
+    string subtype;
     double hOffset;
     double hOffset;
     double pitch;
     double pitch;
     double roll;
     double roll;
@@ -955,10 +955,10 @@ bool OpenDriveXmlParser::ReadSignal(Road *road, TiXmlElement *node)
     checker+=node->QueryStringAttribute("dynamic",&strdynamic);
     checker+=node->QueryStringAttribute("dynamic",&strdynamic);
     checker+=node->QueryStringAttribute("orientation",&orientation);
     checker+=node->QueryStringAttribute("orientation",&orientation);
     checker+=node->QueryDoubleAttribute("zOffset",&zOffset);
     checker+=node->QueryDoubleAttribute("zOffset",&zOffset);
-    checker+=node->QueryIntAttribute("type",&type);
+    checker+=node->QueryStringAttribute("type",&type);
     checker+=node->QueryStringAttribute("country",&country);
     checker+=node->QueryStringAttribute("country",&country);
     checker+=node->QueryStringAttribute("countryRevision",&countryRevision);
     checker+=node->QueryStringAttribute("countryRevision",&countryRevision);
-    checker+=node->QueryIntAttribute("subtype",&subtype);
+    checker+=node->QueryStringAttribute("subtype",&subtype);
     checker+=node->QueryDoubleAttribute("hOffset",&hOffset);
     checker+=node->QueryDoubleAttribute("hOffset",&hOffset);
     checker+=node->QueryDoubleAttribute("pitch",&pitch);
     checker+=node->QueryDoubleAttribute("pitch",&pitch);
     checker+=node->QueryDoubleAttribute("roll",&roll);
     checker+=node->QueryDoubleAttribute("roll",&roll);
@@ -973,8 +973,59 @@ bool OpenDriveXmlParser::ReadSignal(Road *road, TiXmlElement *node)
     else dynamic = true;
     else dynamic = true;
     road->AddSignal(s,t,id,name,dynamic,orientation,zOffset,type,country,countryRevision,subtype,hOffset,
     road->AddSignal(s,t,id,name,dynamic,orientation,zOffset,type,country,countryRevision,subtype,hOffset,
                     pitch,roll,height,width);
                     pitch,roll,height,width);
+
+    Signal * pSignal = road->GetSignal(road->GetSignalCount() - 1);
+    TiXmlElement * subNode;
+    //Proceed to Signals
+    subNode=node->FirstChildElement("validity");
+    if (subNode)
+    {
+        ReadSignal_laneValidity(pSignal, subNode);
+    }
+    subNode=node->FirstChildElement("positionInertial");
+    if(subNode)
+    {
+        ReadSignal_positionInertial(pSignal,subNode);
+    }
+    return true;
+}
+
+bool OpenDriveXmlParser::ReadSignal_laneValidity(Signal *pSignal, TiXmlElement *node)
+{
+    int fromLane;
+    int toLane;
+    int checker=TIXML_SUCCESS;
+    checker+=node->QueryIntAttribute("fromLane",&fromLane);
+    checker+=node->QueryIntAttribute("toLane",&toLane);
+    if (checker!=TIXML_SUCCESS)
+    {
+        cout<<"Error parsing laneValidity attributes"<<endl;
+        return false;
+    }
+    pSignal->SetlaneValidity(fromLane,toLane);
     return true;
     return true;
 }
 }
+
+bool OpenDriveXmlParser::ReadSignal_positionInertial(Signal *pSignal, TiXmlElement *node)
+{
+    double x,y,z,hdg,pitch,roll;
+    int checker=TIXML_SUCCESS;
+    checker+=node->QueryDoubleAttribute("x",&x);
+    checker+=node->QueryDoubleAttribute("y",&y);
+    checker+=node->QueryDoubleAttribute("z",&z);
+    checker+=node->QueryDoubleAttribute("hdg",&hdg);
+    checker+=node->QueryDoubleAttribute("pitch",&pitch);
+    checker+=node->QueryDoubleAttribute("roll",&roll);
+    if (checker!=TIXML_SUCCESS)
+    {
+        cout<<"Error parsing positionInertial attributes"<<endl;
+        return false;
+    }
+    pSignal->SetpositionInertial(x,y,z,hdg,pitch,roll);
+    return true;
+}
+
+
 //--------------
 //--------------
 
 
 bool OpenDriveXmlParser::ReadSurface (Road* road, TiXmlElement *node)
 bool OpenDriveXmlParser::ReadSurface (Road* road, TiXmlElement *node)

+ 2 - 0
src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlParser.h

@@ -65,6 +65,8 @@ public:
 	bool ReadObjects (Road* road, TiXmlElement *node);
 	bool ReadObjects (Road* road, TiXmlElement *node);
 	bool ReadSignals (Road* road, TiXmlElement *node);
 	bool ReadSignals (Road* road, TiXmlElement *node);
     bool ReadSignal(Road * road,TiXmlElement * node);
     bool ReadSignal(Road * road,TiXmlElement * node);
+    bool ReadSignal_positionInertial(Signal * pSignal, TiXmlElement *node);
+    bool ReadSignal_laneValidity(Signal * pSignal,TiXmlElement * node);
 	//--------------
 	//--------------
 
 
 	bool ReadSurface (Road* road, TiXmlElement *node);
 	bool ReadSurface (Road* road, TiXmlElement *node);

+ 42 - 0
src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlWriter.cpp

@@ -937,6 +937,7 @@ bool OpenDriveXmlWriter::WriteSignal(TiXmlElement *node, Signal * pSignal)
     nodeSignal->SetAttribute("s",pSignal->Gets());
     nodeSignal->SetAttribute("s",pSignal->Gets());
     nodeSignal->SetAttribute("t",pSignal->Gett());
     nodeSignal->SetAttribute("t",pSignal->Gett());
     nodeSignal->SetAttribute("id",pSignal->Getid());
     nodeSignal->SetAttribute("id",pSignal->Getid());
+    nodeSignal->SetAttribute("name",pSignal->Getname());
     if(pSignal->Getdynamic() == true)
     if(pSignal->Getdynamic() == true)
     nodeSignal->SetAttribute("dynamic","yes");
     nodeSignal->SetAttribute("dynamic","yes");
     else
     else
@@ -953,8 +954,49 @@ bool OpenDriveXmlWriter::WriteSignal(TiXmlElement *node, Signal * pSignal)
     nodeSignal->SetAttribute("height",pSignal->Getheight());
     nodeSignal->SetAttribute("height",pSignal->Getheight());
     nodeSignal->SetAttribute("width",pSignal->Getwidth());
     nodeSignal->SetAttribute("width",pSignal->Getwidth());
 
 
+    signal_laneValidity * psignal_lanevalidity = pSignal->GetlaneValidity();
+    if(psignal_lanevalidity != 0)
+    {
+        WriteSignal_laneValidity(nodeSignal,psignal_lanevalidity);
+    }
+
+    signal_positionInertial * psignal_positionInertial = pSignal->GetpositionInertial();
+    if(psignal_positionInertial != 0)
+    {
+        WriteSignal_positionInertial(nodeSignal,psignal_positionInertial);
+    }
+
     return true;
     return true;
 }
 }
+
+bool OpenDriveXmlWriter::WriteSignal_positionInertial(TiXmlElement *node, signal_positionInertial *pSignal_positionInertial)
+{
+    TiXmlElement* nodepositionInertial = new TiXmlElement("positionInertial");
+
+    node->LinkEndChild(nodepositionInertial);
+
+    nodepositionInertial->SetAttribute("x",pSignal_positionInertial->Getx());
+    nodepositionInertial->SetAttribute("y",pSignal_positionInertial->Gety());
+    nodepositionInertial->SetAttribute("z",pSignal_positionInertial->Getz());
+    nodepositionInertial->SetAttribute("hdg",pSignal_positionInertial->Gethdg());
+    nodepositionInertial->SetAttribute("pitch",pSignal_positionInertial->Getpitch());
+    nodepositionInertial->SetAttribute("roll",pSignal_positionInertial->Getroll());
+
+    return true;
+}
+
+bool OpenDriveXmlWriter::WriteSignal_laneValidity(TiXmlElement *node, signal_laneValidity *pSignal_laneValidity)
+{
+    TiXmlElement* nodelaneValidity = new TiXmlElement("validity");
+
+    node->LinkEndChild(nodelaneValidity);
+
+    nodelaneValidity->SetAttribute("fromLane",pSignal_laneValidity->GetfromLane());
+    nodelaneValidity->SetAttribute("toLane",pSignal_laneValidity->GettoLane());
+
+    return true;
+}
+
 //--------------
 //--------------
 
 
 bool OpenDriveXmlWriter::WriteSurface (TiXmlElement *node, Road* road)
 bool OpenDriveXmlWriter::WriteSurface (TiXmlElement *node, Road* road)

+ 2 - 0
src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlWriter.h

@@ -66,6 +66,8 @@ public:
 	bool WriteObjects (TiXmlElement *node, Road* road);
 	bool WriteObjects (TiXmlElement *node, Road* road);
 	bool WriteSignals (TiXmlElement *node, Road* road);
 	bool WriteSignals (TiXmlElement *node, Road* road);
     bool WriteSignal(TiXmlElement * node, Signal * pSignal);
     bool WriteSignal(TiXmlElement * node, Signal * pSignal);
+    bool WriteSignal_positionInertial(TiXmlElement * node, signal_positionInertial * pSignal_positionInertial);
+    bool WriteSignal_laneValidity(TiXmlElement * node, signal_laneValidity * pSignal_laneValidity);
 	//--------------
 	//--------------
 
 
 	bool WriteSurface (TiXmlElement *node, Road* road);
 	bool WriteSurface (TiXmlElement *node, Road* road);

+ 2 - 2
src/tool/map_lanetoxodr/OpenDrive/Road.cpp

@@ -610,8 +610,8 @@ unsigned int Road::AddObject()
 	return index;
 	return index;
 }
 }
 //-------------
 //-------------
-unsigned int Road::AddSignal(double s,double t,string id,string name,bool dynamic,string orientation,double zOffset,int type,string country,string countryRevision,
-                             int subtype,double hOffset,double pitch,double roll ,double height,double width)
+unsigned int Road::AddSignal(double s,double t,string id,string name,bool dynamic,string orientation,double zOffset,string type,string country,string countryRevision,
+                             string subtype,double hOffset,double pitch,double roll ,double height,double width)
 {
 {
 	// Check the first method in the group for details
 	// Check the first method in the group for details
 
 

+ 2 - 2
src/tool/map_lanetoxodr/OpenDrive/Road.h

@@ -229,8 +229,8 @@ public:
 	unsigned int AddCrossfall (string side, double s, double a, double b, double c, double d);
 	unsigned int AddCrossfall (string side, double s, double a, double b, double c, double d);
 	unsigned int AddLaneSection(double s);
 	unsigned int AddLaneSection(double s);
 	unsigned int AddObject();
 	unsigned int AddObject();
-    unsigned int AddSignal(double s,double t,string id,string name,bool dynamic,string orientation,double zOffset,int type,string country,string countryRevision,
-                           int subtype,double hOffset,double pitch,double roll ,double height,double width);
+    unsigned int AddSignal(double s,double t,string id,string name,bool dynamic,string orientation,double zOffset,string type,string country,string countryRevision,
+                           string subtype,double hOffset,double pitch,double roll ,double height,double width);
 
 
 	/**
 	/**
 	 * Methods used to clone child records in the respective vectors
 	 * Methods used to clone child records in the respective vectors

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

@@ -2639,6 +2639,9 @@ void MainWindow::onClickLoad()
         mxodr.GetJunctionVector()->push_back(pxodr->GetJunctionVector()->at(i));
         mxodr.GetJunctionVector()->push_back(pxodr->GetJunctionVector()->at(i));
     }
     }
 
 
+    if((mxodr.GetRoadCount()>0)&&(mxodr.GetHeader() == 0))
+        mxodr.SetHeader(1,1,"adcmap",1.1,QDateTime::currentDateTime().toString("yyyy-MM-dd").toLatin1().data(),0,0,0,0,glat0,glon0,ghdg0);
+
     updateCBRoad();
     updateCBRoad();
     updateJunction();
     updateJunction();
 
 
@@ -4772,3 +4775,9 @@ void MainWindow::closeEvent(QCloseEvent *event)
         event->accept(); // 接受退出信号,程序退出
         event->accept(); // 接受退出信号,程序退出
     }
     }
 }
 }
+
+void MainWindow::on_actionSet_Traffic_Light_triggered()
+{
+    TrafficLightDialog td(&mxodr,this);
+    int res = td.exec();
+}

+ 3 - 0
src/tool/map_lanetoxodr/mainwindow.h

@@ -41,6 +41,7 @@
 #include "geofit.h"
 #include "geofit.h"
 #include "autoconnect.h"
 #include "autoconnect.h"
 #include "speeddialog.h"
 #include "speeddialog.h"
+#include "trafficlightdialog.h"
 
 
 #include <iostream>
 #include <iostream>
 #include <map>
 #include <map>
@@ -234,6 +235,8 @@ private slots:
 
 
     void closeEvent(QCloseEvent * event);
     void closeEvent(QCloseEvent * event);
 
 
+    void on_actionSet_Traffic_Light_triggered();
+
 private:
 private:
 
 
 
 

+ 6 - 0
src/tool/map_lanetoxodr/mainwindow.ui

@@ -40,6 +40,7 @@
     </property>
     </property>
     <addaction name="actionAutoConnect"/>
     <addaction name="actionAutoConnect"/>
     <addaction name="actionSet_Speed"/>
     <addaction name="actionSet_Speed"/>
+    <addaction name="actionSet_Traffic_Light"/>
    </widget>
    </widget>
    <addaction name="menuFile"/>
    <addaction name="menuFile"/>
    <addaction name="menuFunction"/>
    <addaction name="menuFunction"/>
@@ -79,6 +80,11 @@
     <string>Set Speed</string>
     <string>Set Speed</string>
    </property>
    </property>
   </action>
   </action>
+  <action name="actionSet_Traffic_Light">
+   <property name="text">
+    <string>Edit Traffic Light</string>
+   </property>
+  </action>
  </widget>
  </widget>
  <layoutdefault spacing="6" margin="11"/>
  <layoutdefault spacing="6" margin="11"/>
  <resources>
  <resources>

+ 10 - 1
src/tool/map_lanetoxodr/map_lanetoxodr.pro

@@ -32,6 +32,9 @@ SOURCES += \
         main.cpp \
         main.cpp \
         mainwindow.cpp \
         mainwindow.cpp \
     speeddialog.cpp \
     speeddialog.cpp \
+    trafficlightdialog.cpp \
+    trafficlightlanevaliditydialog.cpp \
+    trafficlightpositiondialog.cpp \
     xodr.cpp \
     xodr.cpp \
     myview.cpp \
     myview.cpp \
     linedata.cpp \
     linedata.cpp \
@@ -62,6 +65,9 @@ HEADERS += \
     autoconnect.h \
     autoconnect.h \
         mainwindow.h \
         mainwindow.h \
     speeddialog.h \
     speeddialog.h \
+    trafficlightdialog.h \
+    trafficlightlanevaliditydialog.h \
+    trafficlightpositiondialog.h \
     xodr.h \
     xodr.h \
     myview.h \
     myview.h \
     boost.h \
     boost.h \
@@ -87,7 +93,10 @@ HEADERS += \
 
 
 FORMS += \
 FORMS += \
         mainwindow.ui \
         mainwindow.ui \
-        speeddialog.ui
+        speeddialog.ui \
+        trafficlightdialog.ui \
+        trafficlightlanevaliditydialog.ui \
+        trafficlightpositiondialog.ui
 
 
 unix:LIBS += -lboost_thread -lboost_system -lboost_serialization -lprotobuf
 unix:LIBS += -lboost_thread -lboost_system -lboost_serialization -lprotobuf
 
 

+ 305 - 0
src/tool/map_lanetoxodr/trafficlightdialog.cpp

@@ -0,0 +1,305 @@
+#include "trafficlightdialog.h"
+#include "ui_trafficlightdialog.h"
+
+#include "trafficlightlanevaliditydialog.h"
+#include "trafficlightpositiondialog.h"
+
+#include <QMessageBox>
+
+TrafficLightDialog::TrafficLightDialog(OpenDrive * pxodr,QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::TrafficLightDialog)
+{
+    ui->setupUi(this);
+    mpxodr = pxodr;
+
+    ui->comboBox_dynamic->addItem("yes");
+    ui->comboBox_dynamic->addItem("no");
+
+    ui->lineEdit_id->setReadOnly(true);
+
+    int i;
+    int nroadcount = mpxodr->GetRoadCount();
+    for(i=0;i<nroadcount;i++)
+    {
+        const char * strname = mpxodr->GetRoad(i)->GetRoadId().data();
+        ui->comboBox_Road->addItem(strname);
+
+    }
+
+
+
+    setWindowTitle("Edit Traffic Light");
+
+}
+
+TrafficLightDialog::~TrafficLightDialog()
+{
+    delete ui;
+}
+
+void TrafficLightDialog::on_comboBox_Road_currentIndexChanged(int index)
+{
+    Road * pRoad = mpxodr->GetRoad(index);
+    if(pRoad == 0)
+    {
+ //       QMessageBox::warning(this,"WARN","MainWindow::onClickCBRoadChange road is NULL");
+        return;
+    }
+
+    ui->lineEdit_RoadLen->setText(QString::number(pRoad->GetRoadLength(),'f',3));
+
+    ui->comboBox_TrafficLIght->clear();
+    int nsigcount = pRoad->GetSignalCount();
+    if(nsigcount == 0)
+    {
+        initlineedit();
+        return;
+    }
+
+    int i;
+    for(i=0;i<nsigcount;i++)
+    {
+        Signal * pSignal = pRoad->GetSignal(i);
+        ui->comboBox_TrafficLIght->addItem(pSignal->Getid().data());
+    }
+}
+
+void TrafficLightDialog::initlineedit()
+{
+    ui->lineEdit_name->setText("");
+    ui->lineEdit_id->setText("");
+    ui->lineEdit_s->setText("0.0");
+    ui->lineEdit_t->setText("0.0");
+//    ui->comboBox_dynamic->setText("");
+    ui->lineEdit_orientation->setText("-");
+    ui->lineEdit_zOffset->setText("0.0");
+    ui->lineEdit_type->setText("1000001");
+    ui->lineEdit_country->setText("OpenDrive");
+    ui->lineEdit_countryRevision->setText("2013");
+    ui->lineEdit_subtype->setText("-1");
+    ui->lineEdit_hOffset->setText("0.1");
+    ui->lineEdit_pitch->setText("0");
+    ui->lineEdit_roll->setText("0");
+    ui->lineEdit_height->setText("0.1");
+    ui->lineEdit_width->setText("0.1");
+}
+
+void TrafficLightDialog::showsignal(Signal *pSignal)
+{
+    ui->lineEdit_name->setText(pSignal->Getname().data());
+    ui->lineEdit_id->setText(pSignal->Getid().data());
+    ui->lineEdit_s->setText(QString::number(pSignal->Gets()));
+    ui->lineEdit_t->setText(QString::number(pSignal->Gett()));
+    if(pSignal->Getdynamic())ui->comboBox_dynamic->setCurrentIndex(0);
+    else ui->comboBox_dynamic->setCurrentIndex(1);
+//    ui->comboBox_dynamic->setText("");
+    ui->lineEdit_orientation->setText(pSignal->Getorientation().data());
+    ui->lineEdit_zOffset->setText(QString::number(pSignal->GetzOffset()));
+    ui->lineEdit_type->setText(pSignal->Gettype().data());
+    ui->lineEdit_country->setText(pSignal->Getcountry().data());
+    ui->lineEdit_countryRevision->setText(pSignal->GetcountryRevision().data());
+    ui->lineEdit_subtype->setText(pSignal->Getsubtype().data());
+    ui->lineEdit_hOffset->setText(QString::number(pSignal->GethOffset()));
+    ui->lineEdit_pitch->setText(QString::number(pSignal->Getpitch()));
+    ui->lineEdit_roll->setText(QString::number(pSignal->Getroll()));
+    ui->lineEdit_height->setText(QString::number(pSignal->Getheight()));
+    ui->lineEdit_width->setText(QString::number(pSignal->Getwidth()));
+}
+
+void TrafficLightDialog::on_comboBox_TrafficLIght_currentIndexChanged(int index)
+{
+    Road * pRoad =mpxodr->GetRoad(ui->comboBox_Road->currentIndex());
+    if(pRoad == 0)return;
+
+    if(pRoad->GetSignalCount() == 0)return;
+
+    if(index >= pRoad->GetSignalCount())return;
+    Signal * pSignal = pRoad->GetSignal(index);
+    showsignal(pSignal);
+}
+
+void TrafficLightDialog::on_pushButton_EditinertialPosition_clicked()
+{
+    Road * pRoad =mpxodr->GetRoad(ui->comboBox_Road->currentIndex());
+    if(pRoad == 0)return;
+
+    if(pRoad->GetSignalCount() == 0)return;
+
+    Signal * pSignal =pRoad->GetSignal(ui->comboBox_TrafficLIght->currentIndex());
+    if(pSignal == 0)return;
+
+    double lon0,lat0;
+    mpxodr->GetHeader()->GetLat0Lon0(lat0,lon0);
+    TrafficLightpositionDialog td(pSignal,lon0,lat0,this);
+    int res = td.exec();
+    (void)&res;
+}
+
+void TrafficLightDialog::on_pushButton_EditlaneValidity_clicked()
+{
+    Road * pRoad =mpxodr->GetRoad(ui->comboBox_Road->currentIndex());
+    if(pRoad == 0)return;
+
+    if(pRoad->GetSignalCount() == 0)return;
+
+    Signal * pSignal =pRoad->GetSignal(ui->comboBox_TrafficLIght->currentIndex());
+    if(pSignal == 0)return;
+
+    TrafficLightlaneValidityDialog td(pSignal,this);
+    int res = td.exec();
+    (void)&res;
+}
+
+void TrafficLightDialog::on_pushButton_Add_clicked()
+{
+    Road * pRoad =mpxodr->GetRoad(ui->comboBox_Road->currentIndex());
+    if(pRoad == 0)return;
+
+    double s;
+    double t;
+    string id;
+    string name;
+    bool dynamic;
+    string orientation;
+    double zOffset;
+    string type;
+    string country;
+    string countryRevision;
+    string subtype;
+    double hOffset;
+    double pitch;
+    double roll;
+    double height;
+    double width;
+
+    int nid = getnewsignalid();
+    string strid = QString::number(nid).toStdString();
+
+    geteditvalue(s,t,name,dynamic,orientation,zOffset,type,country,countryRevision,
+                 subtype,hOffset,pitch,roll,height,width);
+
+    pRoad->AddSignal(s,t,strid,name,dynamic,orientation,zOffset,type,country,countryRevision,
+                     subtype,hOffset,pitch,roll,height,width);
+
+    on_comboBox_Road_currentIndexChanged(ui->comboBox_Road->currentIndex());
+    ui->comboBox_TrafficLIght->setCurrentIndex(pRoad->GetSignalCount()-1);
+
+
+
+}
+
+void TrafficLightDialog::on_pushButton_Delete_clicked()
+{
+    Road * pRoad =mpxodr->GetRoad(ui->comboBox_Road->currentIndex());
+    if(pRoad == 0)return;
+
+    if(pRoad->GetSignalCount() == 0)
+    {
+        QMessageBox::warning(this,"warning","No Signal Delete.");
+        return;
+    }
+
+    pRoad->DeleteSignal(ui->comboBox_TrafficLIght->currentIndex());
+
+    on_comboBox_Road_currentIndexChanged(ui->comboBox_Road->currentIndex());
+    ui->comboBox_TrafficLIght->setCurrentIndex(pRoad->GetSignalCount()-1);
+
+}
+
+void TrafficLightDialog::on_pushButton_Update_clicked()
+{
+    Road * pRoad =mpxodr->GetRoad(ui->comboBox_Road->currentIndex());
+    if(pRoad == 0)return;
+
+    if(pRoad->GetSignalCount() == 0)return;
+    Signal * pSignal =pRoad->GetSignal(ui->comboBox_TrafficLIght->currentIndex());
+    if(pSignal == 0)return;
+
+    double s;
+    double t;
+    string name;
+    bool dynamic;
+    string orientation;
+    double zOffset;
+    string type;
+    string country;
+    string countryRevision;
+    string subtype;
+    double hOffset;
+    double pitch;
+    double roll;
+    double height;
+    double width;
+
+    geteditvalue(s,t,name,dynamic,orientation,zOffset,type,country,countryRevision,
+                 subtype,hOffset,pitch,roll,height,width);
+
+    pSignal->Sets(s);
+    pSignal->Sett(t);
+    pSignal->Setname(name);
+    pSignal->Setdynamic(dynamic);
+    pSignal->Setorientation(orientation);
+    pSignal->SetzOffset(zOffset);
+    pSignal->Settype(type);
+    pSignal->Setcountry(country);
+    pSignal->SetcountryRevision(countryRevision);
+    pSignal->Setsubtype(subtype);
+    pSignal->SethOffset(hOffset);
+    pSignal->Setpitch(pitch);
+    pSignal->Setroll(roll);
+    pSignal->Setheight(height);
+    pSignal->Setwidth(width);
+}
+
+int TrafficLightDialog::geteditvalue(double &s, double &t, std::string &name, bool &dynamic,
+                                     std::string &orientation, double &zOffset, std::string &type,
+                                     std::string &country, std::string &countryRevision, std::string &subtype,
+                                     double &hOffset, double &pitch, double &roll, double &height, double &width)
+{
+    s = ui->lineEdit_s->text().toDouble();
+    t = ui->lineEdit_t->text().toDouble();
+    name = ui->lineEdit_name->text().toStdString();
+    if(ui->comboBox_dynamic->currentIndex() == 0)dynamic = true;
+    else dynamic = false;
+    orientation = ui->lineEdit_orientation->text().toStdString();
+    zOffset = ui->lineEdit_zOffset->text().toDouble();
+    type = ui->lineEdit_type->text().toStdString();
+    country = ui->lineEdit_country->text().toStdString();
+    countryRevision = ui->lineEdit_countryRevision->text().toStdString();
+    subtype = ui->lineEdit_subtype->text().toStdString();
+    hOffset = ui->lineEdit_hOffset->text().toDouble();
+    pitch = ui->lineEdit_pitch->text().toDouble();
+    roll = ui->lineEdit_roll->text().toDouble();
+    height = ui->lineEdit_height->text().toDouble();
+    width = ui->lineEdit_width->text().toDouble();
+    return 0;
+}
+
+int TrafficLightDialog::getnewsignalid()
+{
+    int id = -1;
+    bool bHaveExist = false;
+    do
+    {
+        bHaveExist = false;
+        id = id + 1;
+        int nroadcount = mpxodr->GetRoadCount();
+        int i,j;
+        for(i=0;i<nroadcount;i++)
+        {
+            Road * pRoad = mpxodr->GetRoad(i);
+            int nsignalcount = pRoad->GetSignalCount();
+            for(j=0;j<nsignalcount;j++)
+            {
+                if(id == atoi(pRoad->GetSignal(j)->Getid().data()))
+                {
+                    bHaveExist = true;
+                    break;
+                }
+            }
+            if(bHaveExist)break;
+        }
+    }while(bHaveExist == true);
+    return id;
+}

+ 48 - 0
src/tool/map_lanetoxodr/trafficlightdialog.h

@@ -0,0 +1,48 @@
+#ifndef TRAFFICLIGHTDIALOG_H
+#define TRAFFICLIGHTDIALOG_H
+
+#include <QDialog>
+#include "OpenDrive/OpenDrive.h"
+
+namespace Ui {
+class TrafficLightDialog;
+}
+
+class TrafficLightDialog : public QDialog
+{
+    Q_OBJECT
+
+public:
+    explicit TrafficLightDialog(OpenDrive * pxodr,QWidget *parent = nullptr);
+    ~TrafficLightDialog();
+
+private slots:
+    void on_comboBox_Road_currentIndexChanged(int index);
+
+    void on_comboBox_TrafficLIght_currentIndexChanged(int index);
+
+    void on_pushButton_EditinertialPosition_clicked();
+
+    void on_pushButton_EditlaneValidity_clicked();
+
+    void on_pushButton_Add_clicked();
+
+    void on_pushButton_Delete_clicked();
+
+    void on_pushButton_Update_clicked();
+
+private:
+    Ui::TrafficLightDialog *ui;
+    OpenDrive * mpxodr;
+
+    void initlineedit();
+    void showsignal(Signal * pSignal);
+
+    int geteditvalue(double & s,double & t, string & name, bool &dynamic, string & orientation, double & zOffset,
+                     string & type, string & country, string & countryRevision, string & subtype, double & hOffset,
+                     double & pitch, double & roll, double & height, double & width);
+
+    int getnewsignalid();
+};
+
+#endif // TRAFFICLIGHTDIALOG_H

+ 521 - 0
src/tool/map_lanetoxodr/trafficlightdialog.ui

@@ -0,0 +1,521 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>TrafficLightDialog</class>
+ <widget class="QDialog" name="TrafficLightDialog">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>1006</width>
+    <height>556</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <widget class="QComboBox" name="comboBox_Road">
+   <property name="geometry">
+    <rect>
+     <x>170</x>
+     <y>20</y>
+     <width>231</width>
+     <height>31</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label">
+   <property name="geometry">
+    <rect>
+     <x>30</x>
+     <y>30</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Road</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_2">
+   <property name="geometry">
+    <rect>
+     <x>172</x>
+     <y>70</y>
+     <width>70</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Length</string>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_RoadLen">
+   <property name="geometry">
+    <rect>
+     <x>270</x>
+     <y>70</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QComboBox" name="comboBox_TrafficLIght">
+   <property name="geometry">
+    <rect>
+     <x>170</x>
+     <y>130</y>
+     <width>261</width>
+     <height>31</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_3">
+   <property name="geometry">
+    <rect>
+     <x>30</x>
+     <y>140</y>
+     <width>101</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Traffic Light</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_4">
+   <property name="geometry">
+    <rect>
+     <x>32</x>
+     <y>220</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>s</string>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_s">
+   <property name="geometry">
+    <rect>
+     <x>120</x>
+     <y>220</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_t">
+   <property name="geometry">
+    <rect>
+     <x>350</x>
+     <y>220</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_id">
+   <property name="geometry">
+    <rect>
+     <x>570</x>
+     <y>220</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_name">
+   <property name="geometry">
+    <rect>
+     <x>800</x>
+     <y>220</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_zOffset">
+   <property name="geometry">
+    <rect>
+     <x>350</x>
+     <y>270</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_type">
+   <property name="geometry">
+    <rect>
+     <x>570</x>
+     <y>270</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_country">
+   <property name="geometry">
+    <rect>
+     <x>800</x>
+     <y>267</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_countryRevision">
+   <property name="geometry">
+    <rect>
+     <x>120</x>
+     <y>320</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_subtype">
+   <property name="geometry">
+    <rect>
+     <x>350</x>
+     <y>320</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_hOffset">
+   <property name="geometry">
+    <rect>
+     <x>570</x>
+     <y>320</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_orientation">
+   <property name="geometry">
+    <rect>
+     <x>800</x>
+     <y>319</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_pitch">
+   <property name="geometry">
+    <rect>
+     <x>120</x>
+     <y>370</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_roll">
+   <property name="geometry">
+    <rect>
+     <x>350</x>
+     <y>370</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_5">
+   <property name="geometry">
+    <rect>
+     <x>250</x>
+     <y>220</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>t</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_6">
+   <property name="geometry">
+    <rect>
+     <x>490</x>
+     <y>220</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>id</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_7">
+   <property name="geometry">
+    <rect>
+     <x>720</x>
+     <y>220</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>name</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_8">
+   <property name="geometry">
+    <rect>
+     <x>30</x>
+     <y>272</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>dynamic</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_9">
+   <property name="geometry">
+    <rect>
+     <x>250</x>
+     <y>270</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>zOffset</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_10">
+   <property name="geometry">
+    <rect>
+     <x>490</x>
+     <y>270</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>type</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_11">
+   <property name="geometry">
+    <rect>
+     <x>720</x>
+     <y>272</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>country</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_12">
+   <property name="geometry">
+    <rect>
+     <x>30</x>
+     <y>323</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Revision</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_13">
+   <property name="geometry">
+    <rect>
+     <x>250</x>
+     <y>320</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>subtype</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_14">
+   <property name="geometry">
+    <rect>
+     <x>490</x>
+     <y>320</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>hOffset</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_15">
+   <property name="geometry">
+    <rect>
+     <x>720</x>
+     <y>322</y>
+     <width>80</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>orientation</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_16">
+   <property name="geometry">
+    <rect>
+     <x>30</x>
+     <y>370</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>pitch</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_17">
+   <property name="geometry">
+    <rect>
+     <x>250</x>
+     <y>371</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>roll</string>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_height">
+   <property name="geometry">
+    <rect>
+     <x>570</x>
+     <y>370</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_width">
+   <property name="geometry">
+    <rect>
+     <x>800</x>
+     <y>370</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_18">
+   <property name="geometry">
+    <rect>
+     <x>490</x>
+     <y>372</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>height</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_19">
+   <property name="geometry">
+    <rect>
+     <x>720</x>
+     <y>372</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>width</string>
+   </property>
+  </widget>
+  <widget class="QComboBox" name="comboBox_dynamic">
+   <property name="geometry">
+    <rect>
+     <x>120</x>
+     <y>270</y>
+     <width>111</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QPushButton" name="pushButton_Add">
+   <property name="geometry">
+    <rect>
+     <x>540</x>
+     <y>135</y>
+     <width>89</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Add</string>
+   </property>
+  </widget>
+  <widget class="QPushButton" name="pushButton_Delete">
+   <property name="geometry">
+    <rect>
+     <x>715</x>
+     <y>135</y>
+     <width>89</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Delete</string>
+   </property>
+  </widget>
+  <widget class="QPushButton" name="pushButton_Update">
+   <property name="geometry">
+    <rect>
+     <x>400</x>
+     <y>500</y>
+     <width>89</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Update</string>
+   </property>
+  </widget>
+  <widget class="QPushButton" name="pushButton_EditlaneValidity">
+   <property name="geometry">
+    <rect>
+     <x>170</x>
+     <y>430</y>
+     <width>191</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Edit Lane Validity</string>
+   </property>
+  </widget>
+  <widget class="QPushButton" name="pushButton_EditinertialPosition">
+   <property name="geometry">
+    <rect>
+     <x>620</x>
+     <y>430</y>
+     <width>221</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Edit InertialPosition</string>
+   </property>
+  </widget>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 40 - 0
src/tool/map_lanetoxodr/trafficlightlanevaliditydialog.cpp

@@ -0,0 +1,40 @@
+#include "trafficlightlanevaliditydialog.h"
+#include "ui_trafficlightlanevaliditydialog.h"
+
+#include <QMessageBox>
+
+TrafficLightlaneValidityDialog::TrafficLightlaneValidityDialog(Signal * pSignal,QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::TrafficLightlaneValidityDialog)
+{
+    ui->setupUi(this);
+    mpSignal = pSignal;
+
+    signal_laneValidity * psignal_laneValidity = mpSignal->GetlaneValidity();
+
+    if(psignal_laneValidity != 0)
+    {
+        ui->lineEdit_fromLane->setText(QString::number(psignal_laneValidity->GetfromLane()));
+        ui->lineEdit_toLane->setText(QString::number(psignal_laneValidity->GettoLane()));
+    }
+
+}
+
+TrafficLightlaneValidityDialog::~TrafficLightlaneValidityDialog()
+{
+    delete ui;
+}
+
+void TrafficLightlaneValidityDialog::on_pushButton_clicked()
+{
+    if((ui->lineEdit_fromLane->text().length()== 0)||(ui->lineEdit_toLane->text().length() == 0))
+    {
+        QMessageBox::warning(this,"warning","value is empty.");
+        return;
+    }
+
+    int fromLane = ui->lineEdit_fromLane->text().toInt();
+    int toLane = ui->lineEdit_toLane->text().toInt();
+
+    mpSignal->SetlaneValidity(fromLane,toLane);
+}

+ 27 - 0
src/tool/map_lanetoxodr/trafficlightlanevaliditydialog.h

@@ -0,0 +1,27 @@
+#ifndef TRAFFICLIGHTLANEVALIDITYDIALOG_H
+#define TRAFFICLIGHTLANEVALIDITYDIALOG_H
+
+#include <QDialog>
+#include "OpenDrive/OpenDrive.h"
+
+namespace Ui {
+class TrafficLightlaneValidityDialog;
+}
+
+class TrafficLightlaneValidityDialog : public QDialog
+{
+    Q_OBJECT
+
+public:
+    explicit TrafficLightlaneValidityDialog(Signal * pSignal,QWidget *parent = nullptr);
+    ~TrafficLightlaneValidityDialog();
+
+private slots:
+    void on_pushButton_clicked();
+
+private:
+    Ui::TrafficLightlaneValidityDialog *ui;
+    Signal * mpSignal;
+};
+
+#endif // TRAFFICLIGHTLANEVALIDITYDIALOG_H

+ 78 - 0
src/tool/map_lanetoxodr/trafficlightlanevaliditydialog.ui

@@ -0,0 +1,78 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>TrafficLightlaneValidityDialog</class>
+ <widget class="QDialog" name="TrafficLightlaneValidityDialog">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>592</width>
+    <height>172</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <widget class="QLineEdit" name="lineEdit_fromLane">
+   <property name="geometry">
+    <rect>
+     <x>170</x>
+     <y>40</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_toLane">
+   <property name="geometry">
+    <rect>
+     <x>430</x>
+     <y>40</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QPushButton" name="pushButton">
+   <property name="geometry">
+    <rect>
+     <x>260</x>
+     <y>100</y>
+     <width>89</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Update</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label">
+   <property name="geometry">
+    <rect>
+     <x>62</x>
+     <y>43</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>fromLane</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_2">
+   <property name="geometry">
+    <rect>
+     <x>331</x>
+     <y>42</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>toLane</string>
+   </property>
+  </widget>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 76 - 0
src/tool/map_lanetoxodr/trafficlightpositiondialog.cpp

@@ -0,0 +1,76 @@
+#include "trafficlightpositiondialog.h"
+#include "ui_trafficlightpositiondialog.h"
+
+#include <QMessageBox>
+
+#include <gnss_coordinate_convert.h>
+
+
+TrafficLightpositionDialog::TrafficLightpositionDialog(Signal * pSignal,double lon0,double lat0,QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::TrafficLightpositionDialog)
+{
+    ui->setupUi(this);
+    mpSignal = pSignal;
+    mlon0 = lon0;
+    mlat0 = lat0;
+
+    signal_positionInertial * pSignal_positionInertial;
+    pSignal_positionInertial = mpSignal->GetpositionInertial();
+    if(pSignal_positionInertial != 0)
+    {
+        double x, y;
+        double x0,y0;
+        double lon,lat;
+        GaussProjCal(mlon0,mlat0,&x0,&y0);
+        x = pSignal_positionInertial->Getx();
+        y = pSignal_positionInertial->Gety();
+        GaussProjInvCal((x+x0),(y+y0),&lon,&lat);
+        double hdg = pSignal_positionInertial->Gethdg();
+        double head0 = (M_PI/2.0 - hdg)*180.0/M_PI;
+        if(head0<0)head0 = head0 + 360.0;
+        double z = pSignal_positionInertial->Getz();
+        double pitch = pSignal_positionInertial->Getpitch();
+        double roll = pSignal_positionInertial->Getroll();
+        ui->lineEdit_Lon->setText(QString::number(lon,'f',7));
+        ui->lineEdit_Lat->setText(QString::number(lat,'f',7));
+        ui->lineEdit_Height->setText(QString::number(z,'f',2));
+        ui->lineEdit_hdg->setText(QString::number(head0));
+        ui->lineEdit_pitch->setText(QString::number(pitch));
+        ui->lineEdit_roll->setText(QString::number(roll));
+    }
+
+}
+
+TrafficLightpositionDialog::~TrafficLightpositionDialog()
+{
+    delete ui;
+}
+
+void TrafficLightpositionDialog::on_pushButton_Update_clicked()
+{
+    if(mpSignal == 0)return;
+    double lon,lat,z,head,pitch,roll;
+    if((ui->lineEdit_Lon->text().length() == 0)||(ui->lineEdit_Lat->text().length() == 0))
+    {
+        QMessageBox::warning(this,"warning","Value is Empty.");
+        return;
+    }
+    lon = ui->lineEdit_Lon->text().toDouble();
+    lat = ui->lineEdit_Lat->text().toDouble();
+    z = ui->lineEdit_Height->text().toDouble();
+    head = ui->lineEdit_hdg->text().toDouble();
+    pitch = ui->lineEdit_pitch->text().toDouble();
+    roll = ui->lineEdit_roll->text().toDouble();
+
+    double x, y;
+    double x0,y0;
+
+    GaussProjCal(mlon0,mlat0,&x0,&y0);
+    GaussProjCal(lon,lat,&x,&y);
+    double hdg = (90-head)*M_PI/180.0;
+    if(hdg<0)hdg = hdg +M_PI*2.0;
+    mpSignal->SetpositionInertial(x-x0,y-y0,z,hdg,pitch,roll);
+
+
+}

+ 30 - 0
src/tool/map_lanetoxodr/trafficlightpositiondialog.h

@@ -0,0 +1,30 @@
+#ifndef TRAFFICLIGHTPOSITIONDIALOG_H
+#define TRAFFICLIGHTPOSITIONDIALOG_H
+
+#include <QDialog>
+#include "OpenDrive/OpenDrive.h"
+
+namespace Ui {
+class TrafficLightpositionDialog;
+}
+
+class TrafficLightpositionDialog : public QDialog
+{
+    Q_OBJECT
+
+public:
+    explicit TrafficLightpositionDialog(Signal * pSignal, double lon0,double lat0,QWidget *parent = nullptr);
+    ~TrafficLightpositionDialog();
+
+private slots:
+    void on_pushButton_Update_clicked();
+
+private:
+    Ui::TrafficLightpositionDialog *ui;
+
+    Signal * mpSignal;
+    double mlon0;
+    double mlat0;
+};
+
+#endif // TRAFFICLIGHTPOSITIONDIALOG_H

+ 170 - 0
src/tool/map_lanetoxodr/trafficlightpositiondialog.ui

@@ -0,0 +1,170 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>TrafficLightpositionDialog</class>
+ <widget class="QDialog" name="TrafficLightpositionDialog">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>579</width>
+    <height>298</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <widget class="QPushButton" name="pushButton_Update">
+   <property name="geometry">
+    <rect>
+     <x>220</x>
+     <y>230</y>
+     <width>89</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Update</string>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_Lon">
+   <property name="geometry">
+    <rect>
+     <x>160</x>
+     <y>50</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_Lat">
+   <property name="geometry">
+    <rect>
+     <x>430</x>
+     <y>50</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_Height">
+   <property name="geometry">
+    <rect>
+     <x>160</x>
+     <y>110</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_hdg">
+   <property name="geometry">
+    <rect>
+     <x>430</x>
+     <y>110</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_pitch">
+   <property name="geometry">
+    <rect>
+     <x>160</x>
+     <y>170</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_roll">
+   <property name="geometry">
+    <rect>
+     <x>430</x>
+     <y>170</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label">
+   <property name="geometry">
+    <rect>
+     <x>23</x>
+     <y>53</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Lon</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_2">
+   <property name="geometry">
+    <rect>
+     <x>310</x>
+     <y>54</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Lat</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_3">
+   <property name="geometry">
+    <rect>
+     <x>22</x>
+     <y>115</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>height</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_4">
+   <property name="geometry">
+    <rect>
+     <x>309</x>
+     <y>113</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>hdg</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_5">
+   <property name="geometry">
+    <rect>
+     <x>21</x>
+     <y>176</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>pitch</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_6">
+   <property name="geometry">
+    <rect>
+     <x>313</x>
+     <y>171</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>roll</string>
+   </property>
+  </widget>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 6 - 3
src/tool/tool_electronic_fence/mainwindow.cpp

@@ -101,15 +101,18 @@ void MainWindow::onTimer()
     GaussProjCal(gps_data_set.gps_lng, gps_data_set.gps_lat, &gps_data_set.gps_x, &gps_data_set.gps_y);
     GaussProjCal(gps_data_set.gps_lng, gps_data_set.gps_lat, &gps_data_set.gps_x, &gps_data_set.gps_y);
     GaussProjCal(gps_data_car.gps_lng, gps_data_car.gps_lat, &gps_data_car.gps_x, &gps_data_car.gps_y);
     GaussProjCal(gps_data_car.gps_lng, gps_data_car.gps_lat, &gps_data_car.gps_x, &gps_data_car.gps_y);
     double distance = GetDistance(gps_data_set,gps_data_car);
     double distance = GetDistance(gps_data_set,gps_data_car);
-    ui->lineEdit_6->setText(QString::number(distance, 'g', 12));
+    ui->lineEdit_6->setText(QString::number(distance, 'g', 7));
 
 
     std::cout<<set_R<<std::endl;
     std::cout<<set_R<<std::endl;
     std::cout<<distance<<std::endl;
     std::cout<<distance<<std::endl;
 
 
     if(distance < set_R)
     if(distance < set_R)
-        ui->textEdit->setPlainText("车辆中心点在电子栅栏以内");
+        ui->textEdit->append("<font color=\"#0000FF\">车辆中心点在电子栅栏以内</font> ");
+       // ui->textEdit->setPlainText("车辆中心点在电子栅栏以内");
     if(distance == set_R)
     if(distance == set_R)
         ui->textEdit->setPlainText("车辆中心点在电子栅栏之上");
         ui->textEdit->setPlainText("车辆中心点在电子栅栏之上");
     if(distance > set_R)
     if(distance > set_R)
-        ui->textEdit->setPlainText("车辆中心点在电子栅栏以外");
+       // ui->textEdit->setPlainText("车辆中心点在电子栅栏以外");
+        ui->textEdit->append("<font color=\"#FF0000\">车辆中心点在电子栅栏以外</font> ");
+
 }
 }

+ 7 - 0
src/ui/ADCIntelligentShow_grpc/adcintelligentshow.cpp

@@ -325,6 +325,13 @@ void ADCIntelligentShow::resizeEvent(QResizeEvent *event)
     ui->pushButton_nextstation->setGeometry(380,30,100,50);
     ui->pushButton_nextstation->setGeometry(380,30,100,50);
     ui->pushButton_go->setGeometry(490,30,100,50);
     ui->pushButton_go->setGeometry(490,30,100,50);
 #else
 #else
+
+//    ui->pushButton_prestation->setGeometry(30,30,150,100);
+//    ui->label_station->setGeometry(190,30,260,100);
+//    ui->pushButton_nextstation->setGeometry(460,30,150,100);
+//    ui->pushButton_go->setGeometry(630,30,150,100);
+
+
     ui->pushButton_prestation->setGeometry(50,30,200,100);
     ui->pushButton_prestation->setGeometry(50,30,200,100);
     ui->label_station->setGeometry(260,30,400,100);
     ui->label_station->setGeometry(260,30,400,100);
     ui->pushButton_nextstation->setGeometry(680,30,200,100);
     ui->pushButton_nextstation->setGeometry(680,30,200,100);

+ 14 - 4
src/ui/ADCIntelligentShow_grpc/adcintelligentshow.ui

@@ -788,14 +788,14 @@ color: rgb(200, 200, 200);</string>
      </property>
      </property>
      <property name="font">
      <property name="font">
       <font>
       <font>
-       <pointsize>15</pointsize>
+       <pointsize>8</pointsize>
       </font>
       </font>
      </property>
      </property>
      <property name="styleSheet">
      <property name="styleSheet">
       <string notr="true">color: rgb(255, 255, 255);</string>
       <string notr="true">color: rgb(255, 255, 255);</string>
      </property>
      </property>
      <property name="text">
      <property name="text">
-      <string>北京汽车技师学院</string>
+      <string>中国汽车技术研究中心</string>
      </property>
      </property>
      <property name="alignment">
      <property name="alignment">
       <set>Qt::AlignCenter</set>
       <set>Qt::AlignCenter</set>
@@ -804,12 +804,17 @@ color: rgb(200, 200, 200);</string>
     <widget class="QLabel" name="label_3">
     <widget class="QLabel" name="label_3">
      <property name="geometry">
      <property name="geometry">
       <rect>
       <rect>
-       <x>1480</x>
+       <x>1500</x>
        <y>6</y>
        <y>6</y>
        <width>101</width>
        <width>101</width>
        <height>31</height>
        <height>31</height>
       </rect>
       </rect>
      </property>
      </property>
+     <property name="font">
+      <font>
+       <pointsize>8</pointsize>
+      </font>
+     </property>
      <property name="styleSheet">
      <property name="styleSheet">
       <string notr="true">color: rgb(255, 255, 255);</string>
       <string notr="true">color: rgb(255, 255, 255);</string>
      </property>
      </property>
@@ -823,12 +828,17 @@ color: rgb(200, 200, 200);</string>
     <widget class="QLabel" name="label_4">
     <widget class="QLabel" name="label_4">
      <property name="geometry">
      <property name="geometry">
       <rect>
       <rect>
-       <x>1360</x>
+       <x>1680</x>
        <y>6</y>
        <y>6</y>
        <width>101</width>
        <width>101</width>
        <height>31</height>
        <height>31</height>
       </rect>
       </rect>
      </property>
      </property>
+     <property name="font">
+      <font>
+       <pointsize>8</pointsize>
+      </font>
+     </property>
      <property name="styleSheet">
      <property name="styleSheet">
       <string notr="true">color: rgb(255, 255, 255);</string>
       <string notr="true">color: rgb(255, 255, 255);</string>
      </property>
      </property>