Browse Source

add adcxodrview2. use roadsample.

yuchuli 2 years ago
parent
commit
0e6c2e4a2a

+ 554 - 0
src/common/common/xodr/xodrfunc/roadsample.cpp

@@ -0,0 +1,554 @@
+#include "roadsample.h"
+
+#include <math.h>
+
+#include <iostream>
+
+namespace iv {
+
+
+RoadSample::RoadSample(Road * pRoad)
+{
+    mfRefX_max = 0;
+    mfRefY_max = 0;
+    mfRefX_min = 0;
+    mfRefY_min = 0;
+    SampleRoad(pRoad);
+
+    std::vector<RoadPoint> xvectorRoadPoint = mvectorRoadPoint;
+
+    int n = 1;
+}
+
+int RoadSample::SampleRoad(Road * pRoad)
+{
+    mfRoadLen = pRoad->GetRoadLength();
+    mstrroadid = pRoad->GetRoadId();
+    mstrroadname = pRoad->GetRoadName();
+
+    bool bMaxMinInit = false;
+
+    double fS = 0;
+    const double fStep = 0.1;
+    LaneSection * pLS;
+    unsigned int nLSCount = pRoad->GetLaneSectionCount();
+    unsigned int i;
+    int nSec = 0;
+
+//#ifdef ODRTOLANELET
+//    const double fSampleMark = 10.0;
+//#else
+     const double fSampleMark = 2.5;
+//#endif
+
+
+
+    bool bMarkBrokenVisable = false;
+
+    for(i=0;i<nLSCount;i++)
+    {
+        pLS = pRoad->GetLaneSection(i);
+
+        if(pLS == NULL)
+        {
+            break;
+        }
+
+
+        bMarkBrokenVisable = false;
+        std::vector<double> xvectorFeaturePoint = GetFeaturePoint(pLS);
+
+        double fLastRefX,fLastRefY,fLastRefZ,fLastRefHdg,fLastOffsetValue,fLastS;
+        bool bHaveLast = false;
+        std::vector<LaneSamplePoint> xvectorLastLanePoint;
+
+        double sstart_Section = pLS->GetS();
+
+        double send_Section = pLS->GetS();
+        if(i == (nLSCount -1))
+        {
+            send_Section = pRoad->GetRoadLength();
+        }
+        else
+        {
+            LaneSection * pLSNext = pRoad->GetLaneSection(i+1);
+            if(pLSNext != NULL)
+            {
+                send_Section = pLSNext->GetS();
+            }
+        }
+        nSec++;
+
+        while(fS<send_Section)
+        {
+
+            double fRefX,fRefY,fRefZ,fRefHdg,fOffsetValue;
+            pRoad->GetGeometryCoords(fS,fRefX,fRefY,fRefHdg);
+            fRefZ = pRoad->GetElevationValue(fS);
+            fOffsetValue = pRoad->GetLaneOffsetValue(fS);
+
+            if(fabs(send_Section - fS)<0.1)
+            {
+                fS = send_Section;  //If Section End,Same Point
+//                if(i == (nLSCount - 1))
+//                {
+//                    fS = send_Section;
+//                }
+//                else
+//                {
+//                    fS = send_Section;
+//                }
+            }
+
+            bool bIsCrossFeature = false;
+
+            if((fS - sstart_Section)>fStep*0.5)
+                bIsCrossFeature = IsCrossFeaturePoint(xvectorFeaturePoint,fS,fLastS);
+
+            if(bIsCrossFeature)
+            {
+                if(fS> send_Section)fS = send_Section;
+            }
+
+            RoadPoint xRP;
+            xRP.ms = fS;
+            xRP.mfRefX = fRefX;
+            xRP.mfRefY = fRefY;
+            xRP.mfRefZ = fRefZ;
+            xRP.mfHdg = fRefHdg;
+            xRP.mfLaneOffValue = fOffsetValue;
+            xRP.nSecNum = nSec;
+
+            if(bMaxMinInit)
+            {
+                if(mfRefX_max<fRefX)mfRefX_max = fRefX;
+                if(mfRefX_min>fRefX)mfRefX_min = fRefX;
+                if(mfRefY_max<fRefY)mfRefY_max = fRefY;
+                if(mfRefY_min>fRefY)mfRefY_min = fRefY;
+            }
+            else
+            {
+                mfRefX_max = fRefX;
+                mfRefX_min = fRefX;
+                mfRefY_max = fRefY;
+                mfRefY_min = fRefY;
+                bMaxMinInit = true;
+            }
+
+            std::vector<LaneSamplePoint> xvectorLanePoint;
+ //           SampleLanePoint(pRoad,pLS,fS,xvectorLanePoint);
+
+
+            bool bInserPoint = false;
+
+            if(bHaveLast == false)
+            {
+                bInserPoint = true;
+            }
+            else
+            {
+                if(fabs((fOffsetValue - fLastOffsetValue)/(fS - fLastS))>0.1)
+                {
+                    bInserPoint = true;
+                }
+                else
+                {
+                    double fHdgDiff = fRefHdg - fLastRefHdg;
+                    if(fHdgDiff>M_PI)fHdgDiff = fHdgDiff - 2.0*M_PI;
+                    if(fHdgDiff<-M_PI)fHdgDiff = fHdgDiff + 2.0*M_PI;
+                    if((fabs((fHdgDiff)/(1.0))>0.05) ||((fS - fLastS)>=fSampleMark))
+                    {
+                        bInserPoint = true;
+                    }
+                }
+            }
+
+            if(mstrroadid == "10014")
+            {
+                int a = 1;
+            }
+
+            if((bInserPoint == false)&&(bHaveLast))
+            {
+
+                if(bIsCrossFeature)
+                {
+                    SampleLanePoint(pRoad,pLS,fS,xvectorLanePoint);
+                    xRP.mvectorLanePoint = xvectorLanePoint;
+                    unsigned int k;
+                    unsigned int ksize = static_cast<unsigned int >(xRP.mvectorLanePoint.size());
+                    for(k=0;k<ksize;k++)
+                    {
+                        xRP.mvectorLanePoint[k].mstrroadmarkcolor = mvectorRoadPoint[mvectorRoadPoint.size()-1].mvectorLanePoint[k].mstrroadmarkcolor;
+                        xRP.mvectorLanePoint[k].mstrroadmarktype = mvectorRoadPoint[mvectorRoadPoint.size()-1].mvectorLanePoint[k].mstrroadmarktype;
+                    }
+                    mvectorRoadPoint.push_back(xRP);
+                    bInserPoint = true;
+                    nSec++;
+                    xRP.nSecNum = nSec;
+                }
+
+//                if(IsMarkChange(xvectorLanePoint,xvectorLastLanePoint))
+//                {
+//                    bInserPoint = true;
+//                    nSec++;
+//                    xRP.nSecNum = nSec;
+//                    mvectorRoadPoint.push_back(mvectorRoadPoint[mvectorRoadPoint.size() -1]);
+//                    mvectorRoadPoint[mvectorRoadPoint.size()-1].nSecNum = nSec;
+//                }
+            }
+
+            if((bInserPoint == false)&&(bHaveLast))
+            {
+
+                if((fS-fLastS)>1.0)
+                {
+                    double fGradientMax = GetMaxWidthRatio(pLS,fS);
+                    if(fabs(fGradientMax*(fS-fLastS))>0.1)
+                    {
+                        bInserPoint = true;
+                    }
+                }
+
+
+//                xRP.mvectorLanePoint = xvectorLanePoint;
+//                unsigned int k;
+//                unsigned int ksize = static_cast<unsigned int >(xRP.mvectorLanePoint.size());
+//                for(k=0;k<ksize;k++)
+//                {
+//                    if(fabs(xRP.mvectorLanePoint[k].mfLaneWidth - mvectorRoadPoint[mvectorRoadPoint.size()-1].mvectorLanePoint[k].mfLaneWidth )>0.1)
+//                    {
+//                        bInserPoint = true;
+//                        break;
+//                    }
+//                }
+            }
+
+            if((bInserPoint == false)&&(bHaveLast))
+            {
+                double fcalmod = fmod(fS-sstart_Section,10.0);
+                double fcalmod2 = fmod(fLastS-sstart_Section,10.0);
+                if((fcalmod>=2.5)&&(fcalmod2<2.5))
+                {
+                    bInserPoint = true;
+                }
+                if((fcalmod>=7.5)&&(fcalmod2<7.5))
+                {
+                    bInserPoint = true;
+                }
+
+
+            }
+
+            if(bHaveLast)
+            {
+                double fcalmod = fmod(fS-sstart_Section,10.0);
+                if(fcalmod<2.5)
+                {
+                    bMarkBrokenVisable = false;
+                }
+                else
+                {
+                    if(fcalmod<7.5)
+                    {
+                        bMarkBrokenVisable = true;
+                    }
+                    else
+                        bMarkBrokenVisable = false;
+                }
+            }
+
+
+
+            if((i == (nLSCount -1))&&(fabs(fS - send_Section)<0.001))
+            {
+                bInserPoint = true;
+            }
+
+            if((bIsCrossFeature== false)&&bInserPoint)
+            {
+                SampleLanePoint(pRoad,pLS,fS,xvectorLanePoint);
+            }
+
+
+            if(bInserPoint)
+            {
+                xRP.mvectorLanePoint = xvectorLanePoint;
+                xRP.mbMarkBrokenVisable = bMarkBrokenVisable;
+                mvectorRoadPoint.push_back(xRP);
+
+                fLastS = fS;
+                fLastRefX = fRefX;
+                fLastRefY = fRefY;
+                fLastRefZ = fRefZ;
+                fLastRefHdg = fRefHdg;
+                fLastOffsetValue = fOffsetValue;
+                xvectorLastLanePoint = xvectorLanePoint;
+                bHaveLast = true;
+            }
+
+
+            fS = fS + fStep;
+        }
+    }
+
+ //   std::vector<RoadPoint> * pvectorRoadPoint = &mvectorRoadPoint;
+
+    std::cout<<"Road: "<<mstrroadid<<" max "<<mfRefX_max<<" "<<mfRefY_max<<"  min "<<mfRefX_min<<" "<<mfRefY_min<<std::endl;
+
+    return 0;
+}
+
+int RoadSample::SampleLanePoint(Road * pRoad,LaneSection * pLS, double fS,std::vector<LaneSamplePoint> & xvectorLanePoint)
+{
+
+    unsigned int nLeftLaneCount = pLS->GetLeftLaneCount();
+    unsigned int nRightLaneCount = pLS->GetRightLaneCount();
+
+
+    std::vector<double> xLeftWidth = pRoad->GetLaneWidthVector(fS,1);
+    std::vector<double> xRightWidth = pRoad->GetLaneWidthVector(fS,2);
+
+    if(static_cast<unsigned int>(xLeftWidth.size()) != nLeftLaneCount )
+    {
+        std::cout<<"RoadSample::SampleLanePoint xLeftWidth not equal nLeftLaneCount. "<<" left width size: "<<xLeftWidth.size()
+                <<" nLeftLaneCount: "<<nLeftLaneCount<<std::endl;
+        return -1;
+    }
+
+    if(static_cast<unsigned int>(xRightWidth.size()) != nRightLaneCount )
+    {
+        std::cout<<"RoadSample::SampleLanePoint xRightWidth not equal nRIghtLaneCount. "<<" right width size: "<<xRightWidth.size()
+                <<" nRightLaneCount: "<<nRightLaneCount<<std::endl;
+        return -2;
+    }
+
+    std::vector<double> xvectorLeftLaneT;
+    std::vector<double> xvectorRightLaneT;
+
+    unsigned int i;
+    for(i=0;i<nLeftLaneCount;i++)
+    {
+        unsigned int j;
+        double fValue = xLeftWidth[nLeftLaneCount-i-1];
+        for(j=(nLeftLaneCount-i-1);j>0;j--)
+        {
+            fValue = fValue + xLeftWidth[j-1];
+        }
+        xvectorLeftLaneT.push_back(fValue);
+    }
+
+    for(i=0;i<nRightLaneCount;i++)
+    {
+        unsigned int j;
+        double fValue = 0;
+        for(j=0;j<=i;j++)
+        {
+            fValue = fValue - xRightWidth[j];
+        }
+        xvectorRightLaneT.push_back(fValue);
+    }
+
+
+    iv::LaneSamplePoint xLanePoint;
+    for(i=0;i<nLeftLaneCount;i++)
+    {      
+        pRoad->GetLaneCoords(fS,xvectorLeftLaneT[i],xLanePoint.mx,xLanePoint.my,xLanePoint.mz,xLanePoint.mhdg);
+        LaneRoadMark xRoadMark = pRoad->GetLaneRoadMarkValue(fS,static_cast<int>(nLeftLaneCount -i));
+        xLanePoint.mfmarkwidth = xRoadMark.GetWidth();
+        xLanePoint.mstrroadmarkcolor = xRoadMark.GetColor();
+        xLanePoint.mstrroadmarktype = xRoadMark.GetType();
+        xLanePoint.nLane = static_cast<int>(nLeftLaneCount -i);
+        xLanePoint.mstrLaneType = pLS->GetLeftLaneAt(nLeftLaneCount -i)->GetType();
+        xLanePoint.mfLaneWidth = xLeftWidth[nLeftLaneCount-1 -i];
+        xvectorLanePoint.push_back(xLanePoint);
+    }
+
+    pRoad->GetLaneCoords(fS,0,xLanePoint.mx,xLanePoint.my,xLanePoint.mz,xLanePoint.mhdg);
+    LaneRoadMark xRoadMark = pRoad->GetLaneRoadMarkValue(fS,0);
+    xLanePoint.mfmarkwidth = xRoadMark.GetWidth();
+    xLanePoint.mstrroadmarkcolor = xRoadMark.GetColor();
+    xLanePoint.mstrroadmarktype = xRoadMark.GetType();
+    xLanePoint.nLane = static_cast<int>(0);
+    xLanePoint.mstrLaneType = pLS->GetCenterLane()->GetType();
+    xLanePoint.mfLaneWidth = 0.0;
+    xvectorLanePoint.push_back(xLanePoint);
+
+    for(i=0;i<nRightLaneCount;i++)
+    {
+        pRoad->GetLaneCoords(fS,xvectorRightLaneT[i],xLanePoint.mx,xLanePoint.my,xLanePoint.mz,xLanePoint.mhdg);
+        LaneRoadMark xRoadMark = pRoad->GetLaneRoadMarkValue(fS,static_cast<int>(i+1)*(-1));
+        xLanePoint.mfmarkwidth = xRoadMark.GetWidth();
+        xLanePoint.mstrroadmarkcolor = xRoadMark.GetColor();
+        xLanePoint.mstrroadmarktype = xRoadMark.GetType();
+        xLanePoint.mfLaneWidth = xRightWidth[i];
+        xLanePoint.nLane = static_cast<int>(i+1);
+        xLanePoint.mstrLaneType = pLS->GetRightLaneAt(i+1)->GetType();
+        xvectorLanePoint.push_back(xLanePoint);
+    }
+
+
+
+
+
+    return 0;
+}
+
+bool RoadSample::IsMarkChange(std::vector<LaneSamplePoint> & xvectorLastLanePoint,std::vector<LaneSamplePoint> & xvectorLanePoint)
+{
+    if(xvectorLanePoint.size() != xvectorLastLanePoint.size())
+    {
+        return true;
+    }
+
+    unsigned int i;
+    unsigned int nSize = static_cast<unsigned int >(xvectorLanePoint.size());
+
+    for(i=0;i<nSize;i++)
+    {
+        if(xvectorLanePoint[i].mstrroadmarkcolor != xvectorLastLanePoint[i].mstrroadmarkcolor)
+        {
+            return true;
+        }
+        if(xvectorLanePoint[i].mstrroadmarktype != xvectorLastLanePoint[i].mstrroadmarktype)
+        {
+            return true;
+        }
+    }
+
+    return false;
+
+
+}
+
+std::vector<RoadPoint> * RoadSample::GetRoadPointVector()
+{
+    return  &mvectorRoadPoint;
+}
+
+std::vector<double> RoadSample::GetFeaturePoint(LaneSection * pLS)
+{
+    unsigned int i;
+    unsigned int nlanecount = pLS->GetLaneCount();
+    std::vector<double> xvectorS;
+    for(i=0;i<nlanecount;i++)
+    {
+        Lane * pLane = pLS->GetLane(i);
+        if(pLane != NULL)
+        {
+            unsigned int nMarkCount = pLane->GetLaneRoadMarkCount();
+            unsigned int j;
+            for(j=0;j<nMarkCount;j++)
+            {
+                LaneRoadMark * pMark = pLane->GetLaneRoadMark(j);
+                if(fabs(pMark->GetS())>0.001)
+                {
+                    xvectorS.push_back(pMark->GetS());
+                }
+            }
+        }
+    }
+
+    std::vector<double> xvectorFeature;
+    if(xvectorS.size() == 0)return xvectorFeature;
+    while(xvectorS.size()>0)
+    {
+        unsigned int indexmin = 0;
+        unsigned int nsize = static_cast<unsigned int >(xvectorS.size());
+        for(i=1;i<nsize;i++)
+        {
+            if(xvectorS[i] < xvectorS[indexmin])
+            {
+                indexmin = i;
+            }
+        }
+        if(xvectorFeature.size() == 0)
+        {
+            xvectorFeature.push_back(xvectorS[indexmin]);
+        }
+        else
+        {
+            if(fabs(xvectorS[indexmin] - xvectorFeature[xvectorFeature.size()-1]) > 0.001)
+            {
+                xvectorFeature.push_back(xvectorS[indexmin]);
+            }
+        }
+        xvectorS.erase(xvectorS.begin() + indexmin);
+    }
+
+    return xvectorFeature;
+}
+
+bool RoadSample::IsCrossFeaturePoint(std::vector<double> & xvectorFeature,double & fS,double fSLast)
+{
+    unsigned int nSize = static_cast<unsigned int>(xvectorFeature.size());
+    unsigned int i;
+    for(i=0;i<nSize;i++)
+    {
+        if(((fSLast - xvectorFeature[i])<-0.001)&&((fS+0.1-xvectorFeature[i])>0))
+        {
+            fS = xvectorFeature[i];
+            return true;
+        }
+    }
+
+    return false;
+}
+
+double RoadSample::GetMaxWidthRatio(LaneSection * pLS, double fS)
+{
+    unsigned int nlanecount = static_cast<unsigned int>(pLS->GetLaneCount());
+    unsigned int i;
+    double fRtn = 0.0;
+    for(i=0;i<nlanecount;i++)
+    {
+        Lane * pLane = pLS->GetLane(i);
+        if(pLane != NULL)
+        {
+            if(pLane->GetId() != 0)
+            {
+               double fGradient =  pLane->GetWidthValueGradient(fS-pLS->GetS());
+               if(fabs(fGradient)>fabs(fRtn))
+               {
+                   fRtn = fGradient;
+               }
+            }
+        }
+    }
+    return fRtn;
+}
+
+std::string RoadSample::GetRoadID()
+{
+    return mstrroadid;
+}
+
+std::string RoadSample::GetRoadName()
+{
+    return mstrroadname;
+}
+
+double RoadSample::GetRefXMax()
+{
+    return  mfRefX_max;
+}
+
+double RoadSample::GetRefXMin()
+{
+    return  mfRefX_min;
+}
+
+double RoadSample::GetRefYMax()
+{
+    return mfRefY_max;
+}
+
+double RoadSample::GetRefYMin()
+{
+    return  mfRefY_min;
+}
+
+}
+
+
+

+ 99 - 0
src/common/common/xodr/xodrfunc/roadsample.h

@@ -0,0 +1,99 @@
+#ifndef ROADSAMPLE_H
+#define ROADSAMPLE_H
+
+#include <string>
+#include <vector>
+
+#include "OpenDrive/OpenDrive.h"
+
+namespace iv
+{
+
+struct LaneSamplePoint
+{
+public:
+
+    //
+    int nLane; // 1 left 1   0 center lane   -1 right lane1
+    double mx;
+    double my;
+    double mz;
+    double mhdg;
+    std::string mstrroadmarktype = "none";
+    std::string mstrroadmarkcolor = "standard";
+    //IF solid all is visialbe,  5-5 in view. if broken mark type  6-9   2-4 3-6  if motor way is 6-9 or 3-6 other 2-4
+    double mfroadmarkwidth;
+
+    double mfLaneWidth;
+    double mfmarkwidth;
+    std::string mstrLaneType;  //if nlane = 0 center lane, lanetype is not valid.
+
+};
+
+struct RoadPoint
+{
+public:
+    double ms;
+    std::vector<LaneSamplePoint> mvectorLanePoint;  //From Left to Right
+
+    double mfRefX;
+    double mfRefY;
+    double mfRefZ;
+    double mfHdg;
+    double mfLaneOffValue;
+
+    bool mbMarkBrokenVisable = false;
+
+    int nSecNum;  //If lane count change or lane roadmarkchange is new section.
+
+};
+
+
+
+class RoadSample
+{
+public:
+    RoadSample(Road * pRoad);
+
+    std::vector<RoadPoint> * GetRoadPointVector();
+
+    std::string GetRoadID();
+    std::string GetRoadName();
+    double GetRefXMax();
+    double GetRefXMin();
+    double GetRefYMax();
+    double GetRefYMin();
+
+private:
+    std::string mstrroadid;
+    std::string mstrroadname;
+    double mfRoadLen;
+    std::vector<RoadPoint> mvectorRoadPoint;
+    double mfRefX_min,mfRefX_max,mfRefY_min,mfRefY_max;
+
+private:
+    /**
+     * @brief Samle OpenDrive Road
+     * @param pRoad
+     * @return
+     */
+    int SampleRoad(Road * pRoad);
+
+
+    int SampleLanePoint(Road * pRoad,LaneSection * pLS, double fS,std::vector<LaneSamplePoint> & xvectorLanePoint);
+
+    bool IsMarkChange(std::vector<LaneSamplePoint> & xvectorLastLanePoint,std::vector<LaneSamplePoint> & xvectorLanePoint);
+
+    std::vector<double> GetFeaturePoint(LaneSection * pLS);
+
+    bool IsCrossFeaturePoint(std::vector<double> & xvectorFeature,double & fS,double fSLast);
+
+    inline double GetMaxWidthRatio(LaneSection * pLS, double fS);
+
+
+
+};
+
+}
+
+#endif // ROADSAMPLE_H

+ 14 - 9
src/tool/map_lanetoxodr/adcxodrviewer.pro

@@ -31,10 +31,10 @@ QMAKE_LFLAGS += -no-pie
 
 SOURCES += \
     filedialogextern.cpp \
-    ivxodrtool.cpp \
+    function/ivxodrtool.cpp \
         main.cpp \
-    roaddigit.cpp \
-    myview.cpp \
+    view/roaddigit.cpp \
+    view/myview.cpp \
     TinyXML/tinystr.cpp \
     TinyXML/tinyxml.cpp \
     TinyXML/tinyxmlerror.cpp \
@@ -44,22 +44,24 @@ SOURCES += \
     const.cpp \
     gnss_coordinate_convert.cpp \
     simpleCustomEvent.cpp \
-    xodrscenfunc.cpp \
-    xvmainwindow.cpp
+    view/xodrscenfunc.cpp \
+    xvmainwindow.cpp \
+    ../../common/common/xodr/xodrfunc/roadsample.cpp
 
 HEADERS += \
     filedialogextern.h \
-    ivxodrtool.h \
+    function/ivxodrtool.h \
     roaddigit.h \
-    myview.h \
+    view/myview.h \
     gps_type.h \
     linedata.h \
     TinyXML/tinystr.h \
     TinyXML/tinyxml.h \
     gnss_coordinate_convert.h \
     simpleCustomEvent.h \
-    xodrscenfunc.h \
-    xvmainwindow.h
+    view/xodrscenfunc.h \
+    xvmainwindow.h \
+    ../../common/common/xodr/xodrfunc/roadsample.h
 
 FORMS += \
     xvmainwindow.ui
@@ -94,5 +96,8 @@ INCLUDEPATH += $$PWD/../../common/common/license
 
 INCLUDEPATH += $$PWD/../../common/common/xodr/xodrfunc
 
+INCLUDEPATH += $$PWD/function
+INCLUDEPATH += $$PWD/view
+
 RESOURCES += \
     opendrive.qrc

+ 107 - 0
src/tool/map_lanetoxodr/adcxodrviewer2.pro

@@ -0,0 +1,107 @@
+#-------------------------------------------------
+#
+# Project created by QtCreator 2019-08-23T15:28:22
+#
+#-------------------------------------------------
+
+QT       += core gui
+
+greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
+
+TARGET = adcxodrviewer
+TEMPLATE = app
+
+CONFIG+= c++11
+
+DEFINES += XODRViewer
+
+DEFINES += ODRTOLANELET
+
+DEFINES += XODRViewer2
+
+# The following define makes your compiler emit warnings if you use
+# any feature of Qt which has been marked as deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+QMAKE_LFLAGS += -no-pie
+
+# You can also make your code fail to compile if you use deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+
+SOURCES += \
+    filedialogextern.cpp \
+    function/ivxodrtool.cpp \
+        main.cpp \
+    view/roaddigit.cpp \
+    view/myview.cpp \
+    TinyXML/tinystr.cpp \
+    TinyXML/tinyxml.cpp \
+    TinyXML/tinyxmlerror.cpp \
+    TinyXML/tinyxmlparser.cpp \
+    fresnl.cpp \
+    polevl.c \
+    const.cpp \
+    gnss_coordinate_convert.cpp \
+    simpleCustomEvent.cpp \
+    view/xodrscenfunc.cpp \
+    xvmainwindow2.cpp \
+    ../../common/common/xodr/xodrfunc/roadsample.cpp
+
+HEADERS += \
+    filedialogextern.h \
+    function/ivxodrtool.h \
+    roaddigit.h \
+    view/myview.h \
+    gps_type.h \
+    linedata.h \
+    TinyXML/tinystr.h \
+    TinyXML/tinyxml.h \
+    gnss_coordinate_convert.h \
+    simpleCustomEvent.h \
+    view/xodrscenfunc.h \
+    xvmainwindow2.h \
+    ../../common/common/xodr/xodrfunc/roadsample.h
+
+FORMS += \
+    xvmainwindow2.ui
+
+
+
+!include(../../common/common/xodr/OpenDrive/OpenDrive.pri ) {
+    error( "Couldn't find the OpenDrive.pri file!" )
+}
+
+!include(../../common/common/xodr/xodrfunc/xodrfunc.pri ) {
+    error( "Couldn't find the xodrfunc.pri file!" )
+}
+
+
+
+QMAKE_CXXFLAGS +=  -g
+
+
+
+DEFINES += NOTINPILOT
+
+
+DISTFILES += \
+
+
+unix:INCLUDEPATH += /usr/include/eigen3
+win32:INCLUDEPATH += D:\File\soft\eigen
+
+INCLUDEPATH += $$PWD/../../common/common/xodr
+INCLUDEPATH += $$PWD/../../common/common/license
+
+INCLUDEPATH += $$PWD/../../common/common/xodr/xodrfunc
+
+INCLUDEPATH += $$PWD/function
+INCLUDEPATH += $$PWD/view
+
+RESOURCES += \
+    opendrive.qrc

+ 4 - 0
src/tool/map_lanetoxodr/main.cpp

@@ -1,6 +1,10 @@
 
 #ifdef XODRViewer
+#ifdef XODRViewer2
+#include "xvmainwindow2.h"
+#else
 #include "xvmainwindow.h"
+#endif
 #else
 #include "mainwindow.h"
 #endif

+ 4 - 2
src/tool/map_lanetoxodr/map_lanetoxodr.pro

@@ -96,7 +96,8 @@ SOURCES += \
     excelapi.cpp \
     function/cdaproc.cpp \
     ../../include/msgtype/cdadraw.pb.cc \
-    ui/dialogroadpriority.cpp
+    ui/dialogroadpriority.cpp \
+    ../../common/common/xodr/xodrfunc/roadsample.cpp
 
 HEADERS += \
     function/autoroadcontact.h \
@@ -163,7 +164,8 @@ HEADERS += \
     excelapi.h \
     function/cdaproc.h \
     ../../include/msgtype/cdadraw.pb.h \
-    ui/dialogroadpriority.h
+    ui/dialogroadpriority.h \
+    ../../common/common/xodr/xodrfunc/roadsample.h
 
 FORMS += \
         ui/dialogaddroadfromnds.ui \

+ 285 - 0
src/tool/map_lanetoxodr/view/xodrscenfunc.cpp

@@ -159,6 +159,289 @@ std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadRefGeoItem(RoadDigit *prd)
     return xvectorgrapath;
 }
 
+
+int xodrscenfunc::DefineMarkType(std::string strmarktype)
+{
+    int nrtn = -1;
+    if(strmarktype == "solid")return 0;
+    if(strmarktype == "broken")return 1;
+    if(strmarktype == "solid solid")return 2;
+    if(strmarktype == "solid broken")return 3;
+    if(strmarktype == "broken solid")return 4;
+    if(strmarktype == "broken broken")return 5;
+    return -1;
+}
+
+std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadViewItem(iv::RoadSample * pRS)
+{
+    std::vector<QGraphicsPathItem *> xvectorgrapath;
+
+    std::vector<iv::RoadPoint> *pvectorRP = pRS->GetRoadPointVector();
+    unsigned int nsize = static_cast<unsigned int >(pvectorRP->size());
+    unsigned int i;
+
+    bool bSetBrush = false;
+    std::vector<QColor> xvectorBrush;
+    for(i=0;i<(nsize-1);i++)
+    {
+        unsigned int nLanePointSize1 = static_cast<unsigned int>(pvectorRP->at(i).mvectorLanePoint.size()) ;
+        unsigned int nLanePointSize2 = static_cast<unsigned int>(pvectorRP->at(i+1).mvectorLanePoint.size()) ;
+        if(pvectorRP->at(i).nSecNum != pvectorRP->at(i+1).nSecNum)
+        {
+            bSetBrush = false;
+            xvectorBrush.clear();
+            continue;
+        }
+
+        if(nLanePointSize1 != nLanePointSize2)
+        {
+            std::cout<<" Warning  xodrscenfunc::GetRoadViewItem nLanePointSize1 != nLanePointSize2"<<std::endl;
+            continue;
+        }
+        std::vector<iv::LaneSamplePoint> xvectorLanePoint1 = pvectorRP->at(i).mvectorLanePoint;
+        std::vector<iv::LaneSamplePoint> xvectorLanePoint2 = pvectorRP->at(i+1).mvectorLanePoint;
+        unsigned int j;
+
+        for(j=0;j<(nLanePointSize1 -1);j++)
+        {
+            QPainterPath xpath;
+            xpath.moveTo(xvectorLanePoint1[j].mx,xvectorLanePoint1[j].my*(-1));
+            xpath.lineTo(xvectorLanePoint2[j].mx,xvectorLanePoint2[j].my*(-1));
+            xpath.lineTo(xvectorLanePoint2[j+1].mx,xvectorLanePoint2[j+1].my*(-1));
+            xpath.lineTo(xvectorLanePoint1[j+1].mx,xvectorLanePoint1[j+1].my*(-1));
+
+            xpath.closeSubpath();
+            QGraphicsPathItem * pitem = new QGraphicsPathItem;
+            pitem->setPath(xpath);
+
+            QColor brushcolor = Qt::yellow;
+            if(bSetBrush == false)
+            {
+
+
+                std::string strlanetype = xvectorLanePoint1[j+1].mstrLaneType;
+
+                if(xvectorLanePoint1[j].nLane > 0)
+                {
+                    strlanetype = xvectorLanePoint1[j].mstrLaneType;
+                }
+
+                if(strlanetype == "driving")
+                {
+                    brushcolor = Qt::darkGray;
+                }
+                else
+                {
+                    if(strlanetype == "shoulder")
+                    {
+                        brushcolor = QColor(0x66,0xBF,0x00);
+                    }
+                    else
+                    {
+                        if(strlanetype == "border")
+                        {
+                            brushcolor = Qt::darkGreen;
+                        }
+                        else
+                        {
+                            if(strlanetype == "biking")
+                            {
+                                brushcolor = Qt::red;
+                            }
+                            else
+                            {
+                                if(strlanetype == "sidewalk")
+                                {
+                                    brushcolor = QColor(0xB2,0xB2,0xD6);
+                                }
+                            }
+                        }
+                    }
+                }
+                xvectorBrush.push_back(brushcolor);
+            }
+            else
+            {
+                brushcolor = xvectorBrush[j];
+            }
+
+            pitem->setBrush(brushcolor);
+            pitem->setPen(QPen(brushcolor,0.001));
+    //          mpscene->addItem(pitem);
+            xvectorgrapath.push_back(pitem);
+        }
+        bSetBrush = true;
+
+
+
+    }
+
+    bSetBrush = false;
+    std::vector<int> xvectormarktype;
+    bool bSetMarkType = false;
+    double fKeepS = 0;
+    double flmw = 0.15;
+    double fx1,fx2,fx3,fx4,fy1,fy2,fy3,fy4;
+    for(i=0;i<(nsize-1);i++)
+    {
+        unsigned int nLanePointSize1 = static_cast<unsigned int>(pvectorRP->at(i).mvectorLanePoint.size()) ;
+        unsigned int nLanePointSize2 = static_cast<unsigned int>(pvectorRP->at(i+1).mvectorLanePoint.size()) ;
+
+        if(pvectorRP->at(i).nSecNum != pvectorRP->at(i+1).nSecNum)
+        {
+            bSetBrush = false;
+            bSetMarkType = false;
+            xvectormarktype.clear();
+            xvectorBrush.clear();
+            fKeepS = 0;
+            continue;
+        }
+
+        if(nLanePointSize1 != nLanePointSize2)
+        {
+            bSetBrush = false;
+            bSetMarkType = false;
+            xvectormarktype.clear();
+            xvectorBrush.clear();
+            fKeepS = 0;
+            std::cout<<" Warning  xodrscenfunc::GetRoadViewItem nLanePointSize1 != nLanePointSize2"<<std::endl;
+            continue;
+        }
+
+        unsigned int j;
+        if(bSetMarkType == false)
+        {
+            for(j=0;j<(nLanePointSize1);j++)
+            {
+                int nMarkType =  DefineMarkType(pvectorRP->at(i).mvectorLanePoint[j].mstrroadmarktype);
+                xvectormarktype.push_back(nMarkType);
+            }
+            bSetMarkType = true;
+        }
+
+        for(j=0;j<nLanePointSize1;j++)
+        {
+            int nmarktype =  DefineMarkType(pvectorRP->at(i).mvectorLanePoint[j].mstrroadmarktype);
+            iv::LaneSamplePoint xLSP1 = pvectorRP->at(i).mvectorLanePoint[j];
+            iv::LaneSamplePoint xLSP2 = pvectorRP->at(i+1).mvectorLanePoint[j];
+            double fhdg = pvectorRP->at(i).mfHdg;
+            QPainterPath xpath;
+            int nlanecolor = -3;
+            if(xLSP1.mstrroadmarkcolor == "standard")nlanecolor = 0;
+            if(xLSP1.mstrroadmarkcolor == "blue")nlanecolor = 1;
+            if(xLSP1.mstrroadmarkcolor == "green")nlanecolor = 2;
+            if(xLSP1.mstrroadmarkcolor == "red")nlanecolor = 3;
+            if(xLSP1.mstrroadmarkcolor == "white")nlanecolor = 4;
+            if(xLSP1.mstrroadmarkcolor == "yellow")nlanecolor = 5;
+            if(xLSP1.mstrroadmarkcolor == "orange")nlanecolor = 6;
+            bool bDraw = false;
+            if(nmarktype >= 0)
+            {
+                if(nmarktype<2)
+                {
+                    if((nmarktype == 0)||(pvectorRP->at(i).mbMarkBrokenVisable))
+                    {
+
+                        fx1 = xLSP1.mx + 0.5*flmw * cos(fhdg - M_PI/2.0);
+                        fy1 = (xLSP1.my+0.5*flmw * sin(fhdg - M_PI/2.0))*(-1.0);
+                        fx2 = xLSP2.mx + 0.5*flmw * cos(fhdg - M_PI/2.0);
+                        fy2 = (xLSP2.my +0.5*flmw * sin(fhdg - M_PI/2.0))*(-1.0);
+                        fx3 = xLSP2.mx  + 0.5*flmw * cos(fhdg + M_PI/2.0);
+                        fy3 = (xLSP2.my+0.5*flmw * sin(fhdg + M_PI/2.0))*(-1.0);
+                        fx4 = xLSP1.mx+ 0.5*flmw * cos(fhdg + M_PI/2.0);
+                        fy4 = (xLSP1.my+0.5*flmw * sin(fhdg + M_PI/2.0))*(-1.0);
+                        xpath.moveTo(fx1,fy1);
+                        xpath.lineTo(fx2,fy2);
+                        xpath.lineTo(fx3,fy3);
+                        xpath.lineTo(fx4,fy4);
+                        xpath.closeSubpath();
+                        bDraw = true;
+
+                    }
+                }
+                else
+                {
+                    if((nmarktype == 2)||(nmarktype == 3)||(pvectorRP->at(i).mbMarkBrokenVisable))
+                    {
+                        xpath.moveTo(xLSP1.mx + flmw * cos(fhdg + M_PI/2.0),
+                                     (xLSP1.my+flmw * sin(fhdg + M_PI/2.0))*(-1.0));
+                        xpath.lineTo(xLSP2.mx+ flmw * cos(fhdg + M_PI/2.0),
+                                     (xLSP2.my+flmw * sin(fhdg + M_PI/2.0))*(-1.0));
+
+                        xpath.lineTo(xLSP2.mx + 2*flmw * cos(fhdg + M_PI/2.0),
+                                     (xLSP2.my+2*flmw * sin(fhdg + M_PI/2.0))*(-1.0));
+                        xpath.lineTo(xLSP1.mx+ 2*flmw * cos(fhdg + M_PI/2.0),
+                                     (xLSP1.my+2*flmw * sin(fhdg + M_PI/2.0))*(-1.0));
+                        xpath.closeSubpath();
+                        bDraw = true;
+                    }
+                    if((nmarktype == 2)||(nmarktype == 4)||(pvectorRP->at(i).mbMarkBrokenVisable))
+                    {
+                        xpath.moveTo(xLSP1.mx + flmw * cos(fhdg - M_PI/2.0),
+                                     (xLSP1.my+flmw * sin(fhdg - M_PI/2.0))*(-1.0));
+                        xpath.lineTo(xLSP2.mx+ flmw * cos(fhdg - M_PI/2.0),
+                                     (xLSP2.my+flmw * sin(fhdg - M_PI/2.0))*(-1.0));
+
+                        xpath.lineTo(xLSP2.mx + 2*flmw * cos(fhdg - M_PI/2.0),
+                                     (xLSP2.my+2*flmw * sin(fhdg - M_PI/2.0))*(-1.0));
+                        xpath.lineTo(xLSP1.mx+ 2*flmw * cos(fhdg - M_PI/2.0),
+                                     (xLSP1.my+2*flmw * sin(fhdg - M_PI/2.0))*(-1.0));
+                        xpath.closeSubpath();
+                        bDraw = true;
+                    }
+
+                }
+
+
+
+
+                if(bDraw)
+                {
+                    QGraphicsPathItem * pitem = new QGraphicsPathItem;
+                    pitem->setPath(xpath);
+                    QColor brushcolor;
+                    switch (nlanecolor) {
+                    case 0:
+                        brushcolor = Qt::white;
+                        break;
+                    case 1:
+                        brushcolor = Qt::blue;
+                        break;
+                    case 2:
+                        brushcolor = Qt::green;
+                        break;
+                    case 3:
+                        brushcolor = Qt::red;
+                        break;
+                    case 4:
+                        brushcolor = Qt::white;
+                        break;
+                    case 5:
+                        brushcolor = Qt::yellow;
+                        break;
+                    case 6:
+                        brushcolor = Qt::yellow; //orange use yellow replace
+                        break;
+                    default:
+                        brushcolor = Qt::white;
+                        break;
+                    }
+                    pitem->setBrush(brushcolor);
+                    pitem->setPen(QPen(brushcolor,0.001));
+                    //                pitem->setPos(mfViewMoveX + VIEW_WIDTH/2,-mfViewMoveY +VIEW_HEIGHT/2);
+                    //                mpscene->addItem(pitem);
+                    xvectorgrapath.push_back(pitem);
+                }
+            }
+
+        }
+
+
+    }
+
+    return xvectorgrapath;
+}
+
 std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadLaneItem(RoadDigit *prd)
 {
     std::vector<QGraphicsPathItem *> xvectorgrapath;
@@ -260,6 +543,8 @@ std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadMarkItem(RoadDigit *prd)
         {
             QPainterPath xpath;
             int ncolor = -3;
+
+
             int nmarktype = xvepre[k].mnlanemarktype;
             if(nmarktype >= 0)
             {

+ 6 - 0
src/tool/map_lanetoxodr/view/xodrscenfunc.h

@@ -9,6 +9,8 @@
 
 #include "roaddigit.h"
 
+#include "roadsample.h"
+
 
 class xodrscenfunc
 {
@@ -22,8 +24,12 @@ public:
     static std::vector<QGraphicsPathItem *> GetRoadParkingItem(RoadDigit * prd,std::vector<QGraphicsTextItem *> & xvectortext,
                                                                std::vector<QGraphicsPathItem *>  & xvectormark);
 
+    static std::vector<QGraphicsPathItem *> GetRoadViewItem(iv::RoadSample * pRS);
+
 public:
     static bool IsDrawMark(double s);
+
+    static int DefineMarkType(std::string strmarktype);
 };
 
 #endif // XODRSCENFUNC_H

+ 410 - 0
src/tool/map_lanetoxodr/xvmainwindow2.cpp

@@ -0,0 +1,410 @@
+#include "xvmainwindow2.h"
+#include "ui_xvmainwindow2.h"
+
+#include <QMessageBox>
+#include <QFileDialog>
+
+#include <string.h>
+
+#include "xodrfunc.h"
+#include "roaddigit.h"
+#include "xodrscenfunc.h"
+
+
+#define VIEW_WIDTH 5000
+#define VIEW_HEIGHT 5000
+
+static bool IsNaN(double dat)
+{
+ qint64 & ref=*(qint64 *)&dat;
+ return (ref&0x7FF0000000000000) == 0x7FF0000000000000 && (ref&0xfffffffffffff)!=0;
+}
+
+
+XVMainWindow::XVMainWindow(QWidget *parent) :
+    QMainWindow(parent),
+    ui(new Ui::XVMainWindow)
+{
+    ui->setupUi(this);
+
+    myview = new MyView(this);
+    myview->setObjectName(QStringLiteral("graphicsView"));
+    myview->setGeometry(QRect(30, 30, 600, 600));
+
+    connect(myview,SIGNAL(dbclickxy(double,double)),this,SLOT(onClickXY(double,double)));
+    connect(myview,SIGNAL(beishuchange(double)),this,SLOT(onbeishuchange(double)));
+
+    myview->setCacheMode(myview->CacheBackground);
+
+    mpscene = new  QGraphicsScene(0,0,VIEW_WIDTH,VIEW_HEIGHT);
+    mpscene->setBackgroundBrush(Qt::darkGreen);
+
+    myview->setScene(mpscene);
+    mfViewMoveX = VIEW_WIDTH/2.0;
+    mfViewMoveY = (-1.0)*VIEW_HEIGHT/2.0;
+
+    connect(&mFileDialog,SIGNAL(accepted()),this,SLOT(onFileOpen()));
+
+    setWindowTitle("ADC OpenDrive Viewer2");
+}
+
+XVMainWindow::~XVMainWindow()
+{
+
+    delete mpscene;
+    delete myview;
+    delete ui;
+}
+
+void XVMainWindow::resizeEvent(QResizeEvent *event)
+{
+    qDebug("resize");
+    QSize sizemain = ui->centralwidget->size();
+    qDebug("size x = %d y=%d",sizemain.width(),sizemain.height());
+    mfViewWidth = sizemain.width();
+    mfViewHeight = sizemain.height() - 30;
+    myview->setGeometry(0,30,sizemain.width(),sizemain.height()-30);
+}
+
+void XVMainWindow::on_actionLoad_triggered()
+{
+
+    if(mxodr.GetRoadCount() > 0)
+    {
+        QMessageBox::StandardButton button;
+        char strquest[256];
+        snprintf(strquest,256,"Do you Want to Load New File ?");
+        button=QMessageBox::question(this,"Move",strquest,QMessageBox::Yes|QMessageBox::No);
+        if(button==QMessageBox::No)
+        {
+            return;
+        }
+        else if(button==QMessageBox::Yes)
+        {
+
+        }
+    }
+
+
+#ifndef ANDROID
+    QString strpath = QFileDialog::getOpenFileName(this,"Load XODR",".","*.xodr");
+    if(strpath.isEmpty())return;
+    LoadXODR(strpath);
+    OpenDrive * pxodr = &mxodr;
+    UpdateScene();
+#else
+//    QMessageBox::warning(this,"warning","no file dialog.",QMessageBox::YesAll);
+//    QString strpath = "/storage/emulated/0/map.xodr";
+    mFileDialog.open();
+
+#endif
+
+}
+
+void XVMainWindow::LoadXODR(QString strpath)
+{
+    mxodr.Clear();
+    OpenDrive * pxodr = &mxodr;  //because add to xodr,so don't delete
+    OpenDriveXmlParser x(pxodr);
+    if(!x.ReadFile(strpath.toStdString()))
+    {
+        QMessageBox::warning(this,"warn","Can't  load xodr file.");
+        return;
+    }
+
+    int nroadnum = pxodr->GetRoadCount();
+    int i;
+    double froadlen = 0;
+    double fxmin,fxmax,fymin,fymax;
+    fxmin = std::numeric_limits<double>::max() *(1.0);
+    fxmax = std::numeric_limits<double>::max()*(-1.0);
+    fymin = std::numeric_limits<double>::max() *(1.0);
+    fymax = std::numeric_limits<double>::max()*(-1.0);
+    for(i=0;i<nroadnum;i++)
+    {
+        Road * pRoad = pxodr->GetRoad(i);
+        if(IsNaN(pRoad->GetRoadLength()))
+        {
+            pxodr->DeleteRoad(i);
+            i--;
+            nroadnum--;
+            qDebug("delete road %s because length is NaN",pRoad->GetRoadId().data());
+        }
+        else
+        {
+            froadlen = froadlen + pRoad->GetRoadLength();
+
+            iv::RoadSample xSample(pRoad);
+            mvectorRoadSample.push_back(xSample);
+
+            if(pRoad->GetGeometryBlockCount()>0)
+            {
+                double fx,fy;
+                fx = pRoad->GetGeometryBlock(0)->GetGeometryAt(0)->GetX();
+                fy = pRoad->GetGeometryBlock(0)->GetGeometryAt(0)->GetY();
+                if(fx>fxmax)fxmax = fx;
+                if(fx<fxmin)fxmin = fx;
+                if(fy>fymax)fymax = fy;
+                if(fy<fymin)fymin = fy;
+            }
+        }
+    }
+
+    double fmovex = 0;
+    double fmovey = 0;
+    if(((fxmax>1000)&&(fxmin>1000))||((fxmax<-1000)&&(fxmin<-1000)))
+    {
+        fmovex = (fxmax + fxmin)/2.0;
+    }
+
+    if(((fymax>1000)&&(fymin>1000))||((fymax<-1000)&&(fymin<-1000)))
+    {
+        fmovey = (fymax + fymin)/2.0;
+    }
+
+    mfViewMoveX = mfViewMoveX - fmovex;
+    mfViewMoveY = mfViewMoveY - fmovey;
+
+    qDebug("view move is %f",mfViewMoveX,mfViewMoveY);
+
+    char strout[256];
+    snprintf(strout,256,"Road count is %d. Total Len is %f",mxodr.GetRoadCount(),froadlen);
+    QMessageBox::information(this,"Info",strout,QMessageBox::YesAll);
+}
+
+void XVMainWindow::UpdateScene()
+{
+    int i;
+    int nsize = mvectorviewitem.size();
+    for(i=0;i<nsize;i++)
+    {
+        mpscene->removeItem(mvectorviewitem.at(i));
+        delete mvectorviewitem.at(i);
+    }
+    mvectorviewitem.clear();
+
+    nsize = static_cast<int>(mvectorRoadSample.size()) ;
+
+    for(i=0;i<nsize;i++)
+    {
+        std::vector<QGraphicsPathItem *> xvectorlanepath = xodrscenfunc::GetRoadViewItem(&(mvectorRoadSample[i]));
+        int j;
+        int ncount = xvectorlanepath.size();
+        for(j=0;j<ncount;j++)
+        {
+            QGraphicsPathItem * pitem = xvectorlanepath[j];
+//            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            pitem->setPos(mfViewMoveX,-mfViewMoveY);
+            mpscene->addItem(pitem);
+            mvectorviewitem.push_back(pitem);
+        }
+    }
+
+    return;
+
+    nsize = mxodr.GetRoadCount();
+
+
+    std::vector<RoadDigit> xvectorrd;
+    for(i=0;i<nsize;i++)
+    {
+        RoadDigit xrd(mxodr.GetRoad(i),5.0);  //Space Must <= Broken dot dis
+        xvectorrd.push_back(xrd);
+    }
+    for(i=0;i<nsize;i++)
+    {
+        std::vector<QGraphicsPathItem *> xvectorlanepath = xodrscenfunc::GetRoadLaneItem(&(xvectorrd[i]));
+        int j;
+        int ncount = xvectorlanepath.size();
+        for(j=0;j<ncount;j++)
+        {
+            QGraphicsPathItem * pitem = xvectorlanepath[j];
+//            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            pitem->setPos(mfViewMoveX,-mfViewMoveY);
+            mpscene->addItem(pitem);
+            mvectorviewitem.push_back(pitem);
+        }
+    }
+
+    for(i=0;i<nsize;i++)
+    {
+        std::vector<QGraphicsPathItem *> xvectormarkpath = xodrscenfunc::GetRoadMarkItem(&(xvectorrd[i]));
+        int j;
+        int ncount = xvectormarkpath.size();
+        for(j=0;j<ncount;j++)
+        {
+            QGraphicsPathItem * pitem = xvectormarkpath[j];
+ //           pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            pitem->setPos(mfViewMoveX,-mfViewMoveY);
+            mpscene->addItem(pitem);
+            mvectorviewitem.push_back(pitem);
+        }
+    }
+}
+
+
+void XVMainWindow::on_actionZoom_In_triggered()
+{
+    myview->zoomIn();
+}
+
+void XVMainWindow::on_actionZoom_Out_triggered()
+{
+    myview->zoomOut();
+}
+
+void XVMainWindow::on_actionZoom_One_triggered()
+{
+    myview->zoomone();
+}
+
+void XVMainWindow::onClickXY(double x, double y)
+{
+    double selx,sely;
+    double lon,lat;
+
+
+//    qDebug("  x is %f y is %f",x,y);
+//    selx = (x  - (1.0/mfbeishu) * VIEW_WIDTH/2);
+//    sely = (y  - (1.0/mfbeishu) *VIEW_HEIGHT/2) * (-1);
+
+
+//    qDebug("beishu is %f ",mfbeishu);
+//    selx = (x  - (1.0/mfbeishu) *(mfViewWidth/2) + (mfViewWidth/2)) ;
+//    sely = (y  - (1.0/mfbeishu) *(mfViewHeight/2) + (mfViewHeight/2)) * (-1);
+
+    selx = x - VIEW_WIDTH/2;
+    sely = (y - VIEW_HEIGHT/2)*(-1);
+
+
+    mfselx = selx *1.0/mfbeishu ;
+    mfsely = sely *1.0/mfbeishu;
+
+    qDebug("selx is %f sely is %f ",mfselx,mfsely);
+//    selx = x;
+//    sely = y;
+//    mfselx = selx;
+//    mfsely = sely;
+
+//    double x0,y0;
+//    GaussProjCal(glon0,glat0,&x0,&y0);
+//    GaussProjInvCal(x0+selx,y0+sely,&lon,&lat);
+
+    double rel_x,rel_y;
+
+    rel_x = selx - mfViewMoveX + VIEW_WIDTH/2 ;
+    rel_y = sely - mfViewMoveY - VIEW_HEIGHT/2;
+
+
+    Road * pRoad = 0;
+    GeometryBlock * pgeob;
+    double fdis,nearx,neary,hdg;
+    double fs;
+    int nlane;
+    if(xodrfunc::GetNearPoint(rel_x,rel_y,&mxodr,&pRoad,&pgeob,fdis,nearx,neary,hdg,50,&fs,&nlane) == 0)
+    {
+        qDebug("s:%f dis is %f nlane is %d",fs,fdis,nlane);
+        char strout[1000];
+        snprintf(strout,1000,"Road:%s s:%f dis:%f nlane:%d",pRoad->GetRoadId().data(),fs,fdis,nlane);
+ //       mpLabel_Status->setText(strout);
+        ui->statusbar->showMessage(strout,10000);
+
+    }
+    else
+    {
+        char strout[1000];
+        snprintf(strout,1000,"Click x:%f y:%f",rel_x,rel_y);
+        ui->statusbar->showMessage(strout,10000);
+        qDebug("not found near road.");
+    }
+}
+
+void XVMainWindow::on_actionSet_Move_triggered()
+{
+    QMessageBox::StandardButton button;
+    char strquest[256];
+    snprintf(strquest,256,"Want to Move Center to x:%f y:%f ?",-(mfViewMoveX - mfselx),-(mfViewMoveY-mfsely));
+    button=QMessageBox::question(this,"Move",strquest,QMessageBox::Yes|QMessageBox::No);
+    if(button==QMessageBox::No)
+    {
+        return;
+    }
+    else if(button==QMessageBox::Yes)
+    {
+
+    }
+
+    mfViewMoveX = mfViewMoveX - mfselx;
+    mfViewMoveY = mfViewMoveY - mfsely;
+
+    int nsize = mvectorviewitem.size();
+    int i;
+    for(i=0;i<nsize;i++)
+    {
+        mpscene->removeItem(mvectorviewitem.at(i));
+    }
+    for(i=0;i<nsize;i++)
+    {
+//        mvectorviewitem.at(i)->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+        mvectorviewitem.at(i)->setPos(mfViewMoveX ,-mfViewMoveY);
+        mpscene->addItem(mvectorviewitem.at(i));
+    }
+
+    myview->zoomIn();
+    myview->zoomOut();
+}
+
+void XVMainWindow::on_actionReset_Move_triggered()
+{
+    mfViewMoveX = 0;
+    mfViewMoveY = 0;
+    int nsize = mvectorviewitem.size();
+    int i;
+
+    for(i=0;i<nsize;i++)
+    {
+        mpscene->removeItem(mvectorviewitem.at(i));
+    }
+
+    for(i=0;i<nsize;i++)
+    {
+        mvectorviewitem.at(i)->setPos(mfViewMoveX ,-mfViewMoveY);
+ //       mvectorviewitem.at(i)->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+        mpscene->addItem(mvectorviewitem.at(i));
+    }
+
+
+    myview->zoomIn();
+    myview->zoomOut();
+}
+
+void XVMainWindow::paintEvent(QPaintEvent * event)
+{
+    if(mbRefresh)
+    {
+        myview->setScene(mpscene);
+        mbRefresh = false;
+    }
+}
+
+void XVMainWindow::onFileOpen()
+{
+    QString strpath = mFileDialog.currentFile();
+    if(strpath.isEmpty())return;
+    LoadXODR(strpath);
+    OpenDrive * pxodr = &mxodr;
+    UpdateScene();
+}
+
+void XVMainWindow::on_actionHelp_triggered()
+{
+    QString helpinfo = tr("Load:加载文件(后缀名为.xodr)\nZoom In:放大\nZomm Out:缩小\nZoom One:恢复默认视图\nSet Move:移动显示中心\n"
+                          "Reset Move:恢复默认显示中心\n\ntips: 在屏幕上双击选择道路(查看道路id)或者选择点(用来移动中心点 \n      "
+                          "在屏幕上可以移动查看区域");
+    QMessageBox::information(this,"Help",helpinfo,QMessageBox::Yes);
+}
+
+void XVMainWindow::onbeishuchange(double fbeishu)
+{
+    mfbeishu = fbeishu;
+}

+ 92 - 0
src/tool/map_lanetoxodr/xvmainwindow2.h

@@ -0,0 +1,92 @@
+#ifndef XVMAINWINDOW_H
+#define XVMAINWINDOW_H
+
+#include <QMainWindow>
+
+#include "myview.h"
+
+#include "roadsample.h"
+
+#include <QGraphicsScene>
+
+#include "OpenDrive/OpenDrive.h"
+#include "OpenDrive/OpenDriveXmlWriter.h"
+
+#include "OpenDrive/OpenDriveXmlParser.h"
+
+#include "filedialogextern.h"
+#ifdef ANDROID
+#include "simpleCustomEvent.h"
+#endif
+
+namespace Ui {
+class XVMainWindow;
+}
+
+class XVMainWindow : public QMainWindow
+{
+    Q_OBJECT
+
+public:
+    explicit XVMainWindow(QWidget *parent = nullptr);
+    ~XVMainWindow();
+
+private slots:
+    void on_actionLoad_triggered();
+
+    void on_actionZoom_In_triggered();
+
+    void on_actionZoom_Out_triggered();
+
+    void on_actionZoom_One_triggered();
+
+    void onClickXY(double x, double y);
+
+    void onbeishuchange(double fbeishu);
+
+    void on_actionSet_Move_triggered();
+
+    void on_actionReset_Move_triggered();
+
+    void onFileOpen();
+
+public:
+     void resizeEvent(QResizeEvent *event);
+
+private slots:
+    virtual void paintEvent(QPaintEvent *);
+
+     void on_actionHelp_triggered();
+
+private:
+     void LoadXODR(QString strpath);
+     void UpdateScene();
+
+private:
+    Ui::XVMainWindow *ui;
+    MyView *myview;
+    QGraphicsScene * mpscene;
+
+    std::vector<QGraphicsPathItem *> mvectorviewitem;
+
+    std::vector<iv::RoadSample> mvectorRoadSample;
+
+private:
+    OpenDrive mxodr;
+    double mfViewMoveX = 0;
+    double mfViewMoveY = 0;
+
+    double mfselx = 0;
+    double mfsely = 0;
+
+    bool mbRefresh = false;
+
+    FileDialogExtern mFileDialog;
+
+    double mfbeishu = 1.0;
+
+    double mfViewWidth;
+    double mfViewHeight;
+};
+
+#endif // XVMAINWINDOW_H

+ 79 - 0
src/tool/map_lanetoxodr/xvmainwindow2.ui

@@ -0,0 +1,79 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>XVMainWindow</class>
+ <widget class="QMainWindow" name="XVMainWindow">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>800</width>
+    <height>600</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>MainWindow</string>
+  </property>
+  <widget class="QWidget" name="centralwidget"/>
+  <widget class="QMenuBar" name="menubar">
+   <property name="geometry">
+    <rect>
+     <x>0</x>
+     <y>0</y>
+     <width>800</width>
+     <height>28</height>
+    </rect>
+   </property>
+   <widget class="QMenu" name="menuFile">
+    <property name="title">
+     <string>File</string>
+    </property>
+    <addaction name="actionLoad"/>
+    <addaction name="actionZoom_In"/>
+    <addaction name="actionZoom_Out"/>
+    <addaction name="actionZoom_One"/>
+    <addaction name="actionSet_Move"/>
+    <addaction name="actionReset_Move"/>
+    <addaction name="actionHelp"/>
+   </widget>
+   <addaction name="menuFile"/>
+  </widget>
+  <widget class="QStatusBar" name="statusbar"/>
+  <action name="actionLoad">
+   <property name="text">
+    <string>Load</string>
+   </property>
+  </action>
+  <action name="actionZoom_In">
+   <property name="text">
+    <string>Zoom In</string>
+   </property>
+  </action>
+  <action name="actionZoom_Out">
+   <property name="text">
+    <string>Zoom Out</string>
+   </property>
+  </action>
+  <action name="actionZoom_One">
+   <property name="text">
+    <string>Zoom One</string>
+   </property>
+  </action>
+  <action name="actionSet_Move">
+   <property name="text">
+    <string>Set Move</string>
+   </property>
+  </action>
+  <action name="actionReset_Move">
+   <property name="text">
+    <string>Reset Move</string>
+   </property>
+  </action>
+  <action name="actionHelp">
+   <property name="text">
+    <string>Help</string>
+   </property>
+  </action>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>