소스 검색

Merge branch 'master' of http://192.168.14.36:3000/adc_pilot/modularization

fujiankuan 3 년 전
부모
커밋
adc8f0f8b9
100개의 변경된 파일4646개의 추가작업 그리고 15674개의 파일을 삭제
  1. 2 2
      src/common/common/xodr/OpenDrive/OpenDrive.h
  2. 21 0
      src/common/common/xodr/OpenDrive/OpenDrive.pri
  3. 4 0
      src/common/common/xodr/OpenDrive/OpenDriveXmlParser.cpp
  4. 25 0
      src/common/common/xodr/OpenDrive/RoadGeometry.cpp
  5. 7 1
      src/common/common/xodr/OpenDrive/RoadGeometry.h
  6. 9 0
      src/common/common/xodr/TinyXML/TinyXML.pri
  7. 1160 0
      src/common/common/xodr/xodrfunc.cpp
  8. 71 0
      src/common/common/xodr/xodrfunc.h
  9. 39 4
      src/common/ivbacktrace/ivbacktrace.cpp
  10. 73 0
      src/common/ivchart/.gitignore
  11. 28 0
      src/common/ivchart/ivchart.cpp
  12. 30 0
      src/common/ivchart/ivchart.h
  13. 42 0
      src/common/ivchart/ivchart.pro
  14. 89 0
      src/common/ivchart/ivchart_impl.cpp
  15. 45 0
      src/common/ivchart/ivchart_impl.h
  16. 11 6
      src/controller/controller_yuhesen/control/control_status.cpp
  17. 2 2
      src/decition/decition_brain/decition/adc_tools/compute_00.cpp
  18. 19 8
      src/decition/decition_brain_sf/decition/adc_adapter/hapo_adapter.cpp
  19. 23 23
      src/decition/decition_brain_sf/decition/brain.cpp
  20. 28 14
      src/decition/decition_brain_sf/decition/decide_gps_00.cpp
  21. 2 0
      src/detection/detection_lidar_ukf_pda/imm_ukf_pda.cpp
  22. 5 7
      src/driver/driver_cloud_grpc_client_BS/main.cpp
  23. 21 12
      src/driver/driver_cloud_grpc_client_BS/vehicle_control.cpp
  24. 4 4
      src/driver/driver_cloud_grpc_client_BS/vehicle_control.h
  25. 23 21
      src/driver/driver_cloud_grpc_client_BS/vehicle_patrol.cpp
  26. 2 2
      src/driver/driver_cloud_grpc_client_BS/vehicle_upload.cpp
  27. 13 24
      src/driver/driver_map_xodrload/driver_map_xodrload.pro
  28. 543 295
      src/driver/driver_map_xodrload/globalplan.cpp
  29. 12 0
      src/driver/driver_map_xodrload/globalplan.h
  30. 5 1
      src/driver/driver_map_xodrload/main.cpp
  31. 405 9
      src/driver/driver_map_xodrload/xodrdijkstra.cpp
  32. 20 2
      src/driver/driver_map_xodrload/xodrdijkstra.h
  33. 2 0
      src/fusion/fusion_pointcloud_bus/lidarmerge.cpp
  34. 1 0
      src/fusion/fusion_pointcloud_bus/lidarmerge.h
  35. 8 0
      src/fusion/fusion_pointcloud_bus/main.cpp
  36. 17 0
      src/include/proto/ivchart.proto
  37. 73 0
      src/test/testivchart/.gitignore
  38. 30 0
      src/test/testivchart/main.cpp
  39. 28 0
      src/test/testivchart/testivchart.pro
  40. 4 0
      src/tool/map_lanetoxodr/OpenDrive/OpenDriveXmlParser.cpp
  41. 21 0
      src/tool/map_lanetoxodr/OpenDrive/RoadGeometry.cpp
  42. 6 0
      src/tool/map_lanetoxodr/OpenDrive/RoadGeometry.h
  43. 46 0
      src/tool/map_lanetoxodr/mainwindow.cpp
  44. 6 0
      src/tool/map_lanetoxodr/myview.cpp
  45. 3 0
      src/tool/map_lanetoxodr/myview.h
  46. 104 2
      src/tool/map_lanetoxodr/roaddigit.cpp
  47. 3 0
      src/tool/map_lanetoxodr/roaddigit.h
  48. 72 1
      src/tool/map_lanetoxodr/xodrfunc.cpp
  49. 4 0
      src/tool/map_lanetoxodr/xodrfunc.h
  50. 27 6
      src/tool/map_lanetoxodr/xodrscenfunc.cpp
  51. 79 13
      src/tool/map_lanetoxodr/xvmainwindow.cpp
  52. 7 0
      src/tool/map_lanetoxodr/xvmainwindow.h
  53. 3 0
      src/tool/map_lanetoxodr_graphscene/mainwindow.cpp
  54. 0 565
      src/tool/tool_xodrobj/OpenDrive/Junction.cpp
  55. 0 470
      src/tool/tool_xodrobj/OpenDrive/Junction.h
  56. 0 1509
      src/tool/tool_xodrobj/OpenDrive/Lane.cpp
  57. 0 773
      src/tool/tool_xodrobj/OpenDrive/Lane.h
  58. 0 0
      src/tool/tool_xodrobj/OpenDrive/ObjectSignal.cpp
  59. 0 28
      src/tool/tool_xodrobj/OpenDrive/ObjectSignal.h
  60. 0 301
      src/tool/tool_xodrobj/OpenDrive/OpenDrive.cpp
  61. 0 187
      src/tool/tool_xodrobj/OpenDrive/OpenDrive.h
  62. 0 1112
      src/tool/tool_xodrobj/OpenDrive/OpenDriveXmlParser.cpp
  63. 0 86
      src/tool/tool_xodrobj/OpenDrive/OpenDriveXmlParser.h
  64. 0 1100
      src/tool/tool_xodrobj/OpenDrive/OpenDriveXmlWriter.cpp
  65. 0 87
      src/tool/tool_xodrobj/OpenDrive/OpenDriveXmlWriter.h
  66. 0 90
      src/tool/tool_xodrobj/OpenDrive/OtherStructures.cpp
  67. 0 66
      src/tool/tool_xodrobj/OpenDrive/OtherStructures.h
  68. 0 1252
      src/tool/tool_xodrobj/OpenDrive/Road.cpp
  69. 0 489
      src/tool/tool_xodrobj/OpenDrive/Road.h
  70. 0 853
      src/tool/tool_xodrobj/OpenDrive/RoadGeometry.cpp
  71. 0 435
      src/tool/tool_xodrobj/OpenDrive/RoadGeometry.h
  72. 0 116
      src/tool/tool_xodrobj/TinyXML/tinystr.cpp
  73. 0 319
      src/tool/tool_xodrobj/TinyXML/tinystr.h
  74. 0 1856
      src/tool/tool_xodrobj/TinyXML/tinyxml.cpp
  75. 0 1802
      src/tool/tool_xodrobj/TinyXML/tinyxml.h
  76. 0 52
      src/tool/tool_xodrobj/TinyXML/tinyxmlerror.cpp
  77. 0 1635
      src/tool/tool_xodrobj/TinyXML/tinyxmlparser.cpp
  78. 91 7
      src/tool/tool_xodrobj/mainwindow.cpp
  79. 3 0
      src/tool/tool_xodrobj/mainwindow.h
  80. 10 24
      src/tool/tool_xodrobj/tool_xodrobj.pro
  81. 73 0
      src/tool/view_ivchart/.gitignore
  82. 81 0
      src/tool/view_ivchart/dialogselect.cpp
  83. 32 0
      src/tool/view_ivchart/dialogselect.h
  84. 32 0
      src/tool/view_ivchart/dialogselect.ui
  85. 132 0
      src/tool/view_ivchart/ivchartproc.cpp
  86. 43 0
      src/tool/view_ivchart/ivchartproc.h
  87. 11 0
      src/tool/view_ivchart/main.cpp
  88. 168 0
      src/tool/view_ivchart/mainwindow.cpp
  89. 51 0
      src/tool/view_ivchart/mainwindow.h
  90. 43 0
      src/tool/view_ivchart/mainwindow.ui
  91. 45 0
      src/tool/view_ivchart/view_ivchart.pro
  92. 5 1
      src/ui/ADCIntelligentShow_grpc/adcintelligentshow.cpp
  93. 1 0
      src/ui/ADCIntelligentShow_grpc/adcintelligentshow.h
  94. 2 0
      src/ui/ADCIntelligentShow_grpc/main.cpp
  95. 2 0
      src/v2x/v2xTcpClient/Readme.md
  96. 25 0
      src/v2x/v2xTcpClientWL/Readme.md
  97. 51 0
      src/v2x/v2xTcpClientWL/boost.h
  98. 203 0
      src/v2x/v2xTcpClientWL/data_type.h
  99. 61 0
      src/v2x/v2xTcpClientWL/decition_type.h
  100. 154 0
      src/v2x/v2xTcpClientWL/gnss_coordinate_convert.cpp

+ 2 - 2
src/common/common/xodr/OpenDrive/OpenDrive.h

@@ -47,8 +47,8 @@ private:
 	/**
 	 * Copy constructor, makes the object non-copyable
 	 */
-	OpenDrive (const OpenDrive& openDrive){};
-	const OpenDrive& operator=(const OpenDrive& rhs){};
+    OpenDrive (const OpenDrive& openDrive){};
+    const OpenDrive& operator=(const OpenDrive& rhs){};
 
 public:
 	/**

+ 21 - 0
src/common/common/xodr/OpenDrive/OpenDrive.pri

@@ -0,0 +1,21 @@
+HEADERS += \
+    $$PWD/Junction.h \
+    $$PWD/Lane.h \
+    $$PWD/ObjectSignal.h \
+    $$PWD/OpenDrive.h \
+    $$PWD/OpenDriveXmlParser.h \
+    $$PWD/OpenDriveXmlWriter.h \
+    $$PWD/OtherStructures.h \
+    $$PWD/Road.h \
+    $$PWD/RoadGeometry.h
+
+SOURCES += \
+    $$PWD/Junction.cpp \
+    $$PWD/Lane.cpp \
+    $$PWD/ObjectSignal.cpp \
+    $$PWD/OpenDrive.cpp \
+    $$PWD/OpenDriveXmlParser.cpp \
+    $$PWD/OpenDriveXmlWriter.cpp \
+    $$PWD/OtherStructures.cpp \
+    $$PWD/Road.cpp \
+    $$PWD/RoadGeometry.cpp

+ 4 - 0
src/common/common/xodr/OpenDrive/OpenDriveXmlParser.cpp

@@ -656,6 +656,7 @@ bool OpenDriveXmlParser::ReadLane (LaneSection* laneSection, TiXmlElement *node,
 	TiXmlElement *subNode=node->FirstChildElement("link");
 	TiXmlElement *subSubNode;
 	if (subNode)
+    {
 		subSubNode=subNode->FirstChildElement("predecessor");
 			if (subSubNode)
 			{
@@ -663,7 +664,9 @@ bool OpenDriveXmlParser::ReadLane (LaneSection* laneSection, TiXmlElement *node,
 				if (checker==TIXML_SUCCESS)
 					lane->SetPredecessor(predecessor);
 			}
+    }
 	if (subNode)
+    {
 		subSubNode=subNode->FirstChildElement("successor");
 			if (subSubNode)
 			{
@@ -671,6 +674,7 @@ bool OpenDriveXmlParser::ReadLane (LaneSection* laneSection, TiXmlElement *node,
 				if (checker==TIXML_SUCCESS)
 					lane->SetSuccessor(successor);
 			}
+    }
 
 	//Proceed to the Road width
 	subNode=node->FirstChildElement("width");

+ 25 - 0
src/common/common/xodr/OpenDrive/RoadGeometry.cpp

@@ -519,6 +519,27 @@ void GeometryPoly3::SetAll(double s, double x, double y, double hdg, double leng
 	ComputeVars();
 }
 
+//GetA to GetD, Added by Yuchuli
+double GeometryPoly3::GetA()
+{
+    return mA;
+}
+
+double GeometryPoly3::GetB()
+{
+    return mB;
+}
+
+double GeometryPoly3::GetC()
+{
+    return mC;
+}
+
+double GeometryPoly3::GetD()
+{
+    return mD;
+}
+
 
 //***********************************************************************************
 //Cubic Polynom geometry. Has to be implemented.  Added By Yuchuli
@@ -613,6 +634,10 @@ const GeometryBlock& GeometryBlock::operator=(const GeometryBlock& otherGeomBloc
 			{
 				delete poly;
 			}
+            else if(GeometryParamPoly3 * parampoly = dynamic_cast<GeometryParamPoly3 *>(*member) )
+            {
+                delete parampoly;
+            }
 		}
 		mGeometryBlockElement.clear();
 

+ 7 - 1
src/common/common/xodr/OpenDrive/RoadGeometry.h

@@ -30,7 +30,7 @@ protected:
 	double mHdg;
 	double mLength;
 	double mS2;
-    short int mGeomType;	//0-line, 1-arc, 2-spiral 3-poly3 4-parampoly3
+    short int mGeomType;	//0-line, 2-arc, 1-spiral 3-poly3 4-parampoly3
 public:
 	/**
 	 * Constructor that initializes the base properties of teh record
@@ -294,6 +294,12 @@ public:
 	 */
 	void SetAll(double s, double x, double y, double hdg, double length, double a,double b,double c,double d);
 
+
+    double GetA();
+    double GetB();
+    double GetC();
+    double GetD();
+
 };
 
 //----------------------------------------------------------------------------------

+ 9 - 0
src/common/common/xodr/TinyXML/TinyXML.pri

@@ -0,0 +1,9 @@
+HEADERS += \
+    $$PWD/tinystr.h \
+    $$PWD/tinyxml.h
+
+SOURCES += \
+    $$PWD/tinystr.cpp \
+    $$PWD/tinyxml.cpp \
+    $$PWD/tinyxmlerror.cpp \
+    $$PWD/tinyxmlparser.cpp

+ 1160 - 0
src/common/common/xodr/xodrfunc.cpp

@@ -0,0 +1,1160 @@
+#include "xodrfunc.h"
+
+#include "limits"
+#include <iostream>
+
+#include <Eigen/Dense>
+#include <Eigen/Cholesky>
+#include <Eigen/LU>
+#include <Eigen/QR>
+#include <Eigen/SVD>
+
+#include <QDebug>
+#include <QPointF>
+
+xodrfunc::xodrfunc()
+{
+
+}
+
+
+inline double xodrfunc::calcpointdis(QPointF p1,QPointF p2)
+{
+    return sqrt(pow(p1.x()-p2.x(),2)+pow(p1.y()-p2.y(),2));
+}
+
+bool xodrfunc::pointinarc(GeometryArc * parc,QPointF poingarc,QPointF point1)
+{
+    double hdg = CalcHdg(poingarc,point1);
+    if(parc->GetCurvature() >0)hdg = hdg + M_PI/2.0;
+    else hdg = hdg - M_PI/2.0;
+    if(hdg >= 2.0*M_PI)hdg = hdg - 2.0*M_PI;
+    if(hdg < 0)hdg = hdg + 2.0*M_PI;
+
+    double hdgrange = parc->GetLength()/(1.0/parc->GetCurvature());
+
+    double hdgdiff = hdg - parc->GetHdg();
+
+    if(hdgrange >= 0 )
+    {
+        if(hdgdiff < 0)hdgdiff = hdgdiff + M_PI*2.0;
+    }
+    else
+    {
+        if(hdgdiff > 0)hdgdiff = hdgdiff - M_PI*2.0;
+    }
+
+    if(fabs(hdgdiff ) < fabs(hdgrange))return true;
+    return false;
+
+}
+
+/**
+  * @brief CalcHdg
+  * 计算点0到点1的航向
+  * @param p0        Point 0
+  * @param p1        Point 1
+**/
+double xodrfunc::CalcHdg(QPointF p0, QPointF p1)
+{
+    double x0,y0,x1,y1;
+    x0 = p0.x();
+    y0 = p0.y();
+    x1 = p1.x();
+    y1 = p1.y();
+    if(x0 == x1)
+    {
+        if(y0 < y1)
+        {
+            return M_PI/2.0;
+        }
+        else
+            return M_PI*3.0/2.0;
+    }
+
+    double ratio = (y1-y0)/(x1-x0);
+
+    double hdg = atan(ratio);
+
+    if(ratio > 0)
+    {
+        if(y1 > y0)
+        {
+
+        }
+        else
+        {
+            hdg = hdg + M_PI;
+        }
+    }
+    else
+    {
+        if(y1 > y0)
+        {
+            hdg = hdg + M_PI;
+        }
+        else
+        {
+            hdg = hdg + 2.0*M_PI;
+        }
+    }
+
+    return hdg;
+}
+
+/**
+ * @brief GetParamPoly3Dis 获得点到贝塞尔曲线的距离。
+ * @param parc
+ * @param xnow
+ * @param ynow
+ * @param nearx
+ * @param neary
+ * @param nearhead
+ * @return
+ */
+double xodrfunc::GetParamPoly3Dis(GeometryParamPoly3 * parc,double xnow,double ynow,double & nearx,
+                        double & neary,double & nearhead,double & frels)
+{
+
+    double s = 0.1;
+    double fdismin = 100000.0;
+    frels = 0;
+
+    double xold,yold;
+    xold = parc->GetX();
+    yold = parc->GetY();
+
+    double fdis = calcpointdis(QPointF(parc->GetX(),parc->GetY()),QPointF(xnow,ynow));
+    if(fdis<fdismin)
+    {
+        fdismin = fdis;
+        nearhead = parc->GetHdg();
+        nearx = parc->GetX();
+        neary = parc->GetY();
+    }
+
+    while(s < parc->GetLength())
+    {
+
+        double x, y,xtem,ytem;
+        xtem = parc->GetuA() + parc->GetuB() * s + parc->GetuC() * s*s + parc->GetuD() * s*s*s;
+        ytem = parc->GetvA() + parc->GetvB() * s + parc->GetvC() * s*s + parc->GetvD() * s*s*s;
+        x = xtem*cos(parc->GetHdg()) - ytem * sin(parc->GetHdg()) + parc->GetX();
+        y = xtem*sin(parc->GetHdg()) + ytem * cos(parc->GetHdg()) + parc->GetY();
+
+        double hdg = CalcHdg(QPointF(xold,yold),QPointF(x,y));
+        double fdis = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
+        if(fdis<fdismin)
+        {
+            fdismin = fdis;
+            nearhead = hdg;
+            nearx = x;
+            neary = y;
+            frels = s;
+        }
+
+        xold = x;
+        yold = y;
+        s = s+ 0.1;
+    }
+
+    return fdismin;
+
+}
+
+
+/**
+  * @brief GetArcDis
+  * 计算点到圆弧的最短距离,首先用点和圆弧中心点的直线与圆的交点,计算点到交点的距离,如果交点在圆弧上,则最短距离是交点之一,否则计算点到圆弧两个端点的距离。
+  * @param parc        pointer to a arc geomery
+  * @param x           current x
+  * @param y           current y
+  * @param nearx       near x
+  * @param neary       near y
+  * @param nearhead    nearhead
+**/
+
+double xodrfunc::GetArcDis(GeometryArc * parc,double x,double y,double & nearx,
+                        double & neary,double & nearhead,double & frels)
+{
+
+    if((parc->GetS()>370)&&(parc->GetS()<370.1))
+    {
+        int a = 1;
+    }
+
+    if(parc->GetCurvature() == 0.0)return 1000.0;
+
+    double R = fabs(1.0/parc->GetCurvature());
+
+    frels = 0.0;
+
+    //calculate arc center
+    double x_center,y_center;
+    if(parc->GetCurvature() > 0)
+    {
+        x_center = parc->GetX() + R * cos(parc->GetHdg() + M_PI/2.0);
+        y_center = parc->GetY() + R * sin(parc->GetHdg()+ M_PI/2.0);
+    }
+    else
+    {
+        x_center = parc->GetX() + R * cos(parc->GetHdg() - M_PI/2.0);
+        y_center = parc->GetY() + R * sin(parc->GetHdg() - M_PI/2.0);
+    }
+
+    double hdgltoa = CalcHdg(QPointF(x,y),QPointF(x_center,y_center));
+
+
+    QPointF arcpoint;
+    arcpoint.setX(x_center);arcpoint.setY(y_center);
+
+    QPointF pointnow;
+    pointnow.setX(x);pointnow.setY(y);
+    QPointF point1,point2;
+    point1.setX(x_center + (R * cos(hdgltoa)));
+    point1.setY(y_center + (R * sin(hdgltoa)));
+    point2.setX(x_center + (R * cos(hdgltoa + M_PI)));
+    point2.setY(y_center + (R * sin(hdgltoa + M_PI)));
+
+    //calculat dis
+    bool bp1inarc,bp2inarc;
+    bp1inarc =pointinarc(parc,arcpoint,point1);
+    bp2inarc =pointinarc(parc,arcpoint,point2);
+    double fdis[4];
+    fdis[0] = calcpointdis(pointnow,point1);
+    fdis[1] = calcpointdis(pointnow,point2);
+    fdis[2] = calcpointdis(pointnow,QPointF(parc->GetX(),parc->GetY()));
+    QPointF pointend;
+    double hdgrange = parc->GetLength()*parc->GetCurvature();
+    double hdgend = parc->GetHdg() + hdgrange;
+    while(hdgend <0.0)hdgend = hdgend + 2.0 *M_PI;
+    while(hdgend >= 2.0*M_PI) hdgend = hdgend -2.0*M_PI;
+
+    if(parc->GetCurvature() >0)
+    {
+        pointend.setX(arcpoint.x() + R*cos(hdgend -M_PI/2.0 ));
+        pointend.setY(arcpoint.y() + R*sin(hdgend -M_PI/2.0) );
+    }
+    else
+    {
+        pointend.setX(arcpoint.x() + R*cos(hdgend +M_PI/2.0 ));
+        pointend.setY(arcpoint.y() + R*sin(hdgend +M_PI/2.0) );
+    }
+
+    fdis[3] = calcpointdis(pointnow,pointend);
+    int indexmin = -1;
+    double fdismin = 1000000.0;
+    if(bp1inarc)
+    {
+        indexmin = 0;fdismin = fdis[0];
+    }
+    if(bp2inarc)
+    {
+        if(indexmin == -1)
+        {
+            indexmin = 1;fdismin = fdis[1];
+        }
+        else
+        {
+            if(fdis[1]<fdismin)
+            {
+                indexmin = 1;fdismin = fdis[1];
+            }
+        }
+    }
+    if(indexmin == -1)
+    {
+        indexmin = 2;fdismin = fdis[2];
+    }
+    else
+    {
+        if(fdis[2]<fdismin)
+        {
+            indexmin = 2;fdismin = fdis[2];
+        }
+    }
+    if(fdis[3]<fdismin)
+    {
+        indexmin = 3;fdismin = fdis[3];
+    }
+
+    double hdgdiff;
+    switch (indexmin) {
+    case 0:
+        nearx = point1.x();
+        neary = point1.y();
+        if(parc->GetCurvature()<0)
+        {
+            nearhead = CalcHdg(arcpoint,point1) - M_PI/2.0;
+
+        }
+        else
+        {
+            nearhead = CalcHdg(arcpoint,point1) + M_PI/2.0;
+        }
+        while(nearhead>2.0*M_PI)nearhead = nearhead -2.0*M_PI;
+        while(nearhead<0)nearhead = nearhead + 2.0*M_PI;
+        hdgdiff = (nearhead-parc->GetHdg())*(parc->GetCurvature()/abs(parc->GetCurvature()));
+        if(hdgdiff>=2.0*M_PI)hdgdiff = hdgdiff - 2.0*M_PI;
+        if(hdgdiff<0)hdgdiff = hdgdiff + 2.0*M_PI;
+        frels = hdgdiff * R;
+        break;
+    case 1:
+        nearx = point2.x();
+        neary = point2.y();
+        if(parc->GetCurvature()<0)
+        {
+            nearhead = CalcHdg(arcpoint,point2) - M_PI/2.0;
+        }
+        else
+        {
+            nearhead = CalcHdg(arcpoint,point2) + M_PI/2.0;
+        }
+        while(nearhead>2.0*M_PI)nearhead = nearhead -2.0*M_PI;
+        while(nearhead<0)nearhead = nearhead + 2.0*M_PI;
+        hdgdiff = (nearhead-parc->GetHdg())*(parc->GetCurvature()/abs(parc->GetCurvature()));
+        if(hdgdiff>=2.0*M_PI)hdgdiff = hdgdiff - 2.0*M_PI;
+        if(hdgdiff<0)hdgdiff = hdgdiff + 2.0*M_PI;
+        frels = hdgdiff * R;
+        break;
+    case 2:
+        nearx = parc->GetX();
+        neary = parc->GetY();
+        nearhead = parc->GetHdg();
+        frels = 0;
+        break;
+    case 3:
+        nearx = pointend.x();
+        neary = pointend.y();
+        nearhead = hdgend;
+        frels = parc->GetLength();
+        break;
+    default:
+        std::cout<<"error in arcdis "<<std::endl;
+        break;
+    }
+
+    while(nearhead>2.0*M_PI)nearhead = nearhead -2.0*M_PI;
+    while(nearhead<0)nearhead = nearhead + 2.0*M_PI;
+    return fdismin;
+}
+
+
+double xodrfunc::GetPoly3Dis(GeometryPoly3 * ppoly,double xnow,double ynow,double & nearx,
+                        double & neary,double & nearhead,double & frels)
+{
+    double x,y,hdg;
+//    double s = 0.0;
+    double fdismin = 100000.0;
+ //   double s0 = ppoly->GetS();
+
+    x = ppoly->GetX();
+    y = ppoly->GetY();
+    double A,B,C,D;
+    A = ppoly->GetA();
+    B = ppoly->GetB();
+    C = ppoly->GetC();
+    D = ppoly->GetD();
+    const double steplim = 0.3;
+    double du = steplim;
+    double u = 0;
+    double v = 0;
+    double oldx,oldy;
+    oldx = x;
+    oldy = y;
+    double xstart,ystart;
+    xstart = x;
+    ystart = y;
+
+    frels = 0;
+
+    double hdgstart = ppoly->GetHdg();
+    double flen = 0;
+    u = u+du;
+    while(flen < ppoly->GetLength())
+    {
+        double fdis = 0;
+        v = A + B*u + C*u*u + D*u*u*u;
+        x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
+        y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
+        fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
+
+        if(fdis>(steplim*2.0))du = du/2.0;
+        flen = flen + fdis;
+        u = u + du;
+        hdg = xodrfunc::CalcHdg(QPointF(oldx,oldy),QPointF(x,y));
+
+        double fdisnow = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
+        if(fdisnow<fdismin)
+        {
+            fdismin = fdisnow;
+            nearhead = hdg;
+            nearx = x;
+            neary = y;
+            frels = flen;
+        }
+
+        oldx = x;
+        oldy = y;
+    }
+
+    return fdismin;
+}
+
+double xodrfunc::GetSpiralDis(GeometrySpiral * pspiral,double xnow,double ynow,double & nearx,
+                        double & neary,double & nearhead,double & frels)
+{
+
+    double x,y,hdg;
+    double s = 0.0;
+    double fdismin = 100000.0;
+    double s0 = pspiral->GetS();
+
+    frels = 0;
+    while(s<pspiral->GetLength())
+    {
+        pspiral->GetCoords(s0+s,x,y,hdg);
+
+
+        double fdis = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
+        if(fdis<fdismin)
+        {
+            fdismin = fdis;
+            nearhead = hdg;
+            nearx = x;
+            neary = y;
+            frels = s;
+        }
+        s = s+0.1;
+    }
+
+    return fdismin;
+}
+
+/**
+ * @brief GetLineDis 获得点到直线Geometry的距离。
+ * @param pline
+ * @param x
+ * @param y
+ * @param nearx
+ * @param neary
+ * @param nearhead
+ * @return
+ */
+double xodrfunc::GetLineDis(GeometryLine * pline,const double x,const double y,double & nearx,
+                         double & neary,double & nearhead,double & frels)
+{
+    double fRtn = 1000.0;
+
+    double a1,a2,a3,a4,b1,b2;
+    double ratio = pline->GetHdg();
+    while(ratio >= 2.0* M_PI)ratio = ratio-2.0*M_PI;
+    while(ratio<0)ratio = ratio+2.0*M_PI;
+
+    double dis1,dis2,dis3;
+    double x1,x2,x3,y1,y2,y3;
+    x1 = pline->GetX();y1=pline->GetY();
+    if((ratio == 0)||(ratio == M_PI))
+    {
+        a1 = 0;a4=0;
+        a2 = 1;b1= pline->GetY();
+        a3 = 1;b2= x;
+    }
+    else
+    {
+        if((ratio == 0.5*M_PI)||(ratio == 1.5*M_PI))
+        {
+            a2=0;a3=0;
+            a1=1,b1=pline->GetX();
+            a4 = 1;b2 = y;
+        }
+        else
+        {
+            a1 = tan(ratio) *(-1.0);
+            a2 = 1;
+            a3 = tan(ratio+M_PI/2.0)*(-1.0);
+            a4 = 1;
+            b1 = a1*pline->GetX() + a2 * pline->GetY();
+            b2 = a3*x+a4*y;
+        }
+    }
+
+    y2 = y1 + pline->GetLength() * sin(ratio);
+    x2 = x1 + pline->GetLength() * cos(ratio);
+
+    Eigen::Matrix2d A;
+    A<<a1,a2,
+            a3,a4;
+    Eigen::Vector2d B(b1,b2);
+
+    Eigen::Vector2d opoint  = A.lu().solve(B);
+
+    x3 = opoint(0);
+    y3 = opoint(1);
+
+    dis1 = sqrt(pow(x1-x,2)+pow(y1-y,2));
+    dis2 = sqrt(pow(x2-x,2)+pow(y2-y,2));
+    dis3 = sqrt(pow(x3-x,2)+pow(y3-y,2));
+
+
+    if((dis1>pline->GetLength())||(dis2>pline->GetLength()))  //Outoff line
+    {
+ //       std::cout<<" out line"<<std::endl;
+        if(dis1<dis2)
+        {
+            fRtn = dis1;
+            nearx = x1;neary=y1;nearhead = pline->GetHdg();
+        }
+        else
+        {
+            fRtn = dis2;
+            nearx = x2;neary=y2;nearhead = pline->GetHdg();
+        }
+    }
+    else
+    {
+        fRtn = dis3;
+        nearx = x3;neary=y3;nearhead = pline->GetHdg();
+    }
+
+    frels = sqrt(pow(nearx - pline->GetX(),2)+pow(neary - pline->GetY(),2));
+
+    return fRtn;
+
+
+
+}
+
+
+namespace iv {
+struct nearoption
+{
+    Road * pRoad;
+    GeometryBlock * pgeob;
+    double fdis;
+    double nearx;
+    double neary;
+    double nearhead;
+    double fs;
+    int nlane;
+    double fgeodis;
+};
+}
+
+int xodrfunc::GetNearPoint(const double x, const double y, OpenDrive *pxodr, Road **pObjRoad, GeometryBlock **pgeo,
+                           double &fdis, double &nearx, double &neary, double &nearhead,
+                           const double nearthresh,double * pfs,int * pnlane,bool bnotuselane)
+{
+    double dismin = std::numeric_limits<double>::infinity();
+    fdis = dismin;
+    unsigned int i;
+    *pObjRoad = 0;
+    std::vector<iv::nearoption> xvectornearopt;
+    for(i=0;i<pxodr->GetRoadCount();i++)
+    {
+        unsigned int j;
+        Road * proad = pxodr->GetRoad(i);
+        double nx,ny,nh,frels;
+
+        for(j=0;j<proad->GetGeometryBlockCount();j++)
+        {
+            GeometryBlock * pgb = proad->GetGeometryBlock(j);
+            double dis;
+            RoadGeometry * pg;
+            int nlane = 1000;
+            pg = pgb->GetGeometryAt(0);
+
+            if((sqrt(pow(x-pg->GetX(),2)+pow(y- pg->GetY(),2))-pg->GetLength())>nearthresh)
+            {
+                continue;
+            }
+
+            switch (pg->GetGeomType()) {
+            case 0:   //line
+                dis = GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh,frels);
+                break;
+            case 1:
+                dis = GetSpiralDis((GeometrySpiral *)pg,x,y,nx,ny,nh,frels);
+                break;
+            case 2:  //arc
+                dis = GetArcDis((GeometryArc *)pg,x,y,nx,ny,nh,frels);
+                break;
+
+            case 3:
+                dis = GetPoly3Dis((GeometryPoly3 *)pg,x,y,nx,ny,nh,frels);
+                break;
+            case 4:
+                dis = GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh,frels);
+                break;
+            default:
+                dis = 100000.0;
+                break;
+            }
+
+            double fgeodis;
+
+            fgeodis = dis;
+            if((dis < 100)&&(bnotuselane == false))
+            {
+                double faccuratedis;
+                faccuratedis = GetAcurateDis(x,y,proad,frels+pg->GetS(),nx,ny,nh,&nlane);
+                if(faccuratedis < dis)dis = faccuratedis;
+
+            }
+
+            if(dis == 0)
+            {
+                iv::nearoption xopt;
+                xopt.fdis = dis;
+                xopt.fgeodis = fgeodis;
+                xopt.fs = frels +pg->GetS();
+                xopt.nearhead = nh;
+                xopt.nearx = nx;
+                xopt.neary = ny;
+                xopt.nlane = nlane;
+                xopt.pgeob = pgb;
+                xopt.pRoad = proad;
+                xvectornearopt.push_back(xopt);
+            }
+
+            if(dis < dismin)
+            {
+                dismin = dis;
+                nearx = nx;
+                neary = ny;
+                nearhead = nh;
+                fdis = dis;
+                *pObjRoad = proad;
+                *pgeo = pgb;
+                if(pfs != 0)*pfs = frels +pg->GetS();
+                if(pnlane != 0)*pnlane = nlane;
+            }
+        }
+    }
+
+    if(xvectornearopt.size() > 1)
+    {
+        double fgeodismin = 1000;
+        int nindex = 0;
+        for(i=0;i<xvectornearopt.size();i++)
+        {
+            if(xvectornearopt.at(i).fgeodis < fgeodismin)
+            {
+                fgeodismin = xvectornearopt.at(i).fgeodis;
+                nindex = i;
+            }
+        }
+        dismin = xvectornearopt.at(nindex).fdis;
+        nearx = xvectornearopt.at(nindex).nearx;
+        neary = xvectornearopt.at(nindex).neary;
+        nearhead = xvectornearopt.at(nindex).nearhead;
+        fdis = dismin;
+        *pObjRoad = xvectornearopt.at(nindex).pRoad;
+        *pgeo = xvectornearopt.at(nindex).pgeob;
+        if(pfs != 0)*pfs = xvectornearopt.at(nindex).fs;
+        if(pnlane != 0)*pnlane = xvectornearopt.at(nindex).nlane;
+
+    }
+
+
+    if(fdis > nearthresh)return -1;
+    return 0;
+}
+
+
+std::vector<iv::LanePoint> xodrfunc::GetAllLanePoint(Road *pRoad,  const double s,const double x, const double y,const double fhdg)
+{
+    int i;
+    int nLSCount = pRoad->GetLaneSectionCount();
+    double s_section = 0;
+
+
+    std::vector<iv::LanePoint> xvectorlanepoint;
+    for(i=0;i<nLSCount;i++)
+    {
+//        if((pRoad->GetRoadId() == "30012")&&(s>35))
+//        {
+//            int a= 1;
+//        }
+        LaneSection * pLS = pRoad->GetLaneSection(i);
+        if(i<(nLSCount -1))
+        {
+            if(pRoad->GetLaneSection(i+1)->GetS()<s)
+            {
+                continue;
+            }
+        }
+        s_section = pLS->GetS();
+        int nlanecount = pLS->GetLaneCount();
+        int j;
+        for(j=0;j<nlanecount;j++)
+        {
+            Lane * pLane = pLS->GetLane(j);
+
+            int nlanemarktype = -1; //default no lanetype
+            int nlanetype = 2; //driving
+            int nlanecolor = 0;
+            int k;
+            double s_lane = s-s_section;
+            for(k=0;k<pLane->GetLaneRoadMarkCount();k++)
+            {
+                 LaneRoadMark * plrm = pLane->GetLaneRoadMark(k);
+                 if(k<(pLane->GetLaneRoadMarkCount()-1))
+                 {
+                     if(pLane->GetLaneRoadMark(k+1)->GetS()<s_lane)
+                     {
+                         continue;
+                     }
+                 }
+                 else
+                 {
+                     if(s_lane<plrm->GetS())
+                     {
+                         continue;
+                     }
+                 }
+                 if(plrm->GetType() == "solid")
+                 {
+                     nlanemarktype = 0;
+                 }
+                 if(plrm->GetType() == "broken")
+                 {
+                     nlanemarktype = 1;
+                 }
+                 if(plrm->GetType() == "solid solid")
+                 {
+                     nlanemarktype = 2;
+                 }
+                 if(plrm->GetType() == "solid broken")
+                 {
+                     nlanemarktype = 3;
+                 }
+                 if(plrm->GetType() == "broken solid")
+                 {
+                     nlanemarktype = 4;
+                 }
+                 if(plrm->GetType() == "broken broken")
+                 {
+                     nlanemarktype = 5;
+                 }
+
+                 if(plrm->GetColor() == "standard")nlanecolor = 0;
+                 if(plrm->GetColor() == "blue")nlanecolor = 1;
+                 if(plrm->GetColor() == "green")nlanecolor = 2;
+                 if(plrm->GetColor() == "red")nlanecolor = 3;
+                 if(plrm->GetColor() == "white")nlanecolor = 4;
+                 if(plrm->GetColor() == "yellow")nlanecolor = 5;
+                 if(plrm->GetColor() == "orange")nlanecolor = 6;
+                 break;
+            }
+
+            if(pLane->GetType() == "shoulder")
+            {
+                nlanetype = 0;
+            }
+            if(pLane->GetType() == "border")
+            {
+                nlanetype = 1;
+            }
+            if(pLane->GetType() == "driving")
+            {
+                nlanetype = 2;
+            }
+            if(pLane->GetType() == "none")
+            {
+                nlanetype = 4;
+            }
+            if(pLane->GetType() == "biking")
+            {
+                nlanetype = 8;
+            }
+            if(pLane->GetType() == "sidewalk")
+            {
+                nlanetype = 9;
+            }
+
+
+            if(pLane->GetId() != 0)
+            {
+
+//                        if((pRoad->GetRoadId() == "10012")&&(pLane->GetId()==1))
+//                        {
+//                            int a= 1;
+//                        }
+
+//                int k;
+//                double s_lane = 0;
+                for(k=0;k<pLane->GetLaneWidthCount();k++)
+                {
+                    if(k<(pLane->GetLaneWidthCount()-1))
+                    {
+                        if((pLane->GetLaneWidth(k+1)->GetS()+s_section)<s)
+                        {
+                            continue;
+                        }
+                    }
+                    s_lane = pLane->GetLaneWidth(k)->GetS();
+                    break;
+                }
+                LaneWidth * pLW  = pLane->GetLaneWidth(k);
+                if(pLW == 0)
+                {
+                    std::cout<<"not find LaneWidth"<<std::endl;
+                    break;
+                }
+
+
+
+                iv::LanePoint lp;
+                lp.mnlanetype = nlanetype;
+                lp.mnlanemarktype = nlanemarktype;
+                lp.mnlanecolor = nlanecolor;
+                lp.mnlane = pLane->GetId();
+                lp.mnLaneSection = i;
+                double fds = s - s_lane - s_section;
+                lp.mflanewidth = pLW->GetA() + pLW->GetB() * fds
+                        +pLW->GetC() * pow(fds,2) + pLW->GetD() * pow(fds,3);
+                lp.mflanetocenter = 0;
+                lp.mnlanetype = nlanetype;
+                lp.mfhdg = fhdg;
+                lp.mS = s;
+                lp.mfGeoX = x;
+                lp.mfGeoY = y;
+                xvectorlanepoint.push_back(lp);
+
+            }
+            else
+            {
+                iv::LanePoint lp;
+                lp.mnlanetype = nlanetype;
+                lp.mnlanemarktype = nlanemarktype;
+                lp.mnlanecolor = nlanecolor;
+                lp.mnlane = 0;
+                lp.mnLaneSection = i;
+                lp.mflanewidth = 0;
+                lp.mflanetocenter = 0;
+                lp.mfhdg = fhdg;
+                lp.mS = s;
+                lp.mfGeoX = x;
+                lp.mfGeoY = y;
+                xvectorlanepoint.push_back(lp);
+            }
+        }
+
+        for(j=0;j<xvectorlanepoint.size();j++)
+        {
+            int k;
+            for(k=0;k<xvectorlanepoint.size();k++)
+            {
+                if(abs(xvectorlanepoint[k].mnlane)>abs((xvectorlanepoint[j].mnlane)))
+                {
+                    continue;
+                }
+                if(xvectorlanepoint[k].mnlane * xvectorlanepoint[j].mnlane <= 0)
+                {
+                    continue;
+                }
+                xvectorlanepoint[j].mflanetocenter = xvectorlanepoint[j].mflanetocenter + xvectorlanepoint[k].mflanewidth;
+            }
+        }
+
+        for(j=0;j<xvectorlanepoint.size();j++)
+        {
+            if(xvectorlanepoint[j].mnlane < 0)
+            {
+                xvectorlanepoint[j].mfX = x + xvectorlanepoint[j].mflanetocenter * cos(fhdg-M_PI/2.0);
+                xvectorlanepoint[j].mfY = y + xvectorlanepoint[j].mflanetocenter * sin(fhdg-M_PI/2.0);
+            }
+            else
+            {
+                xvectorlanepoint[j].mfX = x + xvectorlanepoint[j].mflanetocenter * cos(fhdg+M_PI/2.0);
+                xvectorlanepoint[j].mfY = y + xvectorlanepoint[j].mflanetocenter * sin(fhdg+M_PI/2.0);
+            }
+        }
+
+        break;
+
+    }
+
+    std::vector<iv::LanePoint> xvectorlanepointrtn;
+    bool bIsSort = true;
+    for(i=0;i<(xvectorlanepoint.size()-1);i++)
+    {
+        if(xvectorlanepoint[i].mnlane < xvectorlanepoint[i+1].mnlane)
+        {
+            bIsSort = false;
+            break;
+        }
+    }
+    if(bIsSort == false)
+    {
+        while(xvectorlanepoint.size() > 0)
+        {
+            int nlanemin;
+            nlanemin = 0;
+            int nlanenum = xvectorlanepoint[0].mnlane;
+            for(i=1;i<xvectorlanepoint.size();i++)
+            {
+                if(xvectorlanepoint[i].mnlane >= nlanenum)
+                {
+                    nlanenum = xvectorlanepoint[i].mnlane;
+                    nlanemin = i;
+                }
+            }
+            xvectorlanepointrtn.push_back(xvectorlanepoint[nlanemin]);
+            xvectorlanepoint.erase(xvectorlanepoint.begin() + nlanemin);
+        }
+    }
+    else
+    {
+        xvectorlanepointrtn = xvectorlanepoint;
+    }
+    return xvectorlanepointrtn;
+
+}
+
+double xodrfunc::GetAcurateDis(const double x, const double y, Road *pRoad,  const double s, const double nearx, const double neary, const double nearhead,int * pnlane)
+{
+    double fdismin = 1000;
+    if(pRoad->GetLaneSectionCount() < 1)return 1000;
+
+    std::vector<iv::LanePoint> xvectorlanepoint = GetAllLanePoint(pRoad,s,nearx,neary,nearhead);
+
+    double fdistoref = sqrt(pow(x-nearx,2)+pow(y-neary,2));
+
+    int i;
+    std::vector<double> xvectordis;
+    int nsize = xvectorlanepoint.size();
+    for(i=0;i<nsize;i++)
+    {
+        double fdis = sqrt(pow(x-xvectorlanepoint[i].mfX,2)+pow(y-xvectorlanepoint[i].mfY,2));
+        xvectordis.push_back(fdis);
+        if(fdismin>fdis)fdismin = fdis;
+
+    }
+    int nlane = -1000;
+    for(i=0;i<nsize;i++)
+    {
+        if((xvectordis[i]<=xvectorlanepoint[i].mflanewidth)&&(fdistoref <= xvectorlanepoint[i].mflanetocenter))
+        {
+            nlane = xvectorlanepoint[i].mnlane;
+            fdismin = 0; //On Lane, is very near.
+            break;
+        }
+    }
+
+    if(pnlane != 0)*pnlane = nlane;
+
+    return fdismin;
+
+
+}
+
+
+
+int xodrfunc::GetLineXY(GeometryLine *pline, double soff, double &x, double &y, double &hdg)
+{
+    if(soff<0)return -1;
+
+    hdg = pline->GetHdg();
+    x = pline->GetX() + soff*cos(hdg);
+    y = pline->GetY() + soff*sin(hdg);
+    return 0;
+}
+
+Road * xodrfunc::GetRoadByID(OpenDrive * pxodr,std::string strroadid)
+{
+    Road * pRoad = 0;
+    int nroadcount = pxodr->GetRoadCount();
+    int i;
+    for(i=0;i<nroadcount;i++)
+    {
+        if(pxodr->GetRoad(i)->GetRoadId() == strroadid)
+        {
+            pRoad = pxodr->GetRoad(i);
+            break;
+        }
+    }
+    return pRoad;
+}
+
+int xodrfunc::GetSpiralXY(GeometrySpiral *pspira, double soff, double &x, double &y, double &hdg)
+{
+    pspira->GetCoords(pspira->GetS() + soff,x,y,hdg);
+    return 0;
+}
+
+int xodrfunc::GetArcXY(GeometryArc *parc, double soff, double &x, double &y, double &hdg)
+{
+    if(parc->GetCurvature() == 0)return -1;
+    double R = fabs(1.0/parc->GetCurvature());
+
+    //calculate arc center
+    double x_center = parc->GetX() + (1.0/parc->GetCurvature()) * cos(parc->GetHdg() + M_PI/2.0);
+    double y_center = parc->GetY() + (1.0/parc->GetCurvature()) * sin(parc->GetHdg()+ M_PI/2.0);
+
+    double arcdiff = soff/R;
+
+    if(parc->GetCurvature() > 0)
+    {
+        x = x_center + R * cos(parc->GetHdg() + arcdiff - M_PI/2.0);
+        y = y_center + R * sin(parc->GetHdg() + arcdiff - M_PI/2.0);
+        hdg = parc->GetHdg() + arcdiff;
+    }
+    else
+    {
+        x = x_center + R * cos(parc->GetHdg() -arcdiff + M_PI/2.0);
+        y = y_center + R * sin(parc->GetHdg() -arcdiff + M_PI/2.0);
+        hdg = parc->GetHdg() - arcdiff;
+    }
+
+
+
+    return 0;
+}
+
+int xodrfunc::GetParamPoly3XY(GeometryParamPoly3 *pparam3d, double soff, double &x, double &y, double &hdg)
+{
+    double xtem,ytem;
+    double ua,ub,uc,ud,va,vb,vc,vd;
+    ua = pparam3d->GetuA();ub= pparam3d->GetuB();uc= pparam3d->GetuC();ud = pparam3d->GetuD();
+    va = pparam3d->GetvA();vb= pparam3d->GetvB();vc= pparam3d->GetvC();vd = pparam3d->GetvD();
+//        xtem = parc->GetuA() + parc->GetuB() * s * len + parc->GetuC() * s*s *pow(len,2) + parc->GetuD() * s*s*s *pow(len,3);
+//        ytem = parc->GetvA() + parc->GetvB() * s* len + parc->GetvC() * s*s *pow(len,2) + parc->GetvD() * s*s*s *pow(len,3);
+    xtem = ua + ub * soff  + uc * soff * soff  + ud * soff *soff*soff ;
+    ytem = va + vb * soff + vc * soff*soff  + vd * soff*soff*soff ;
+    x = xtem*cos(pparam3d->GetHdg()) - ytem * sin(pparam3d->GetHdg()) + pparam3d->GetX();
+    y = xtem*sin(pparam3d->GetHdg()) + ytem * cos(pparam3d->GetHdg()) + pparam3d->GetY();
+    if(soff<0.3)hdg = pparam3d->GetHdg();
+    else
+    {
+        double soff1 = soff - 0.1;
+        double x1,y1;
+        xtem = ua + ub * soff1  + uc * soff1 * soff1  + ud * soff1 *soff1*soff1 ;
+        ytem = va + vb * soff1 + vc * soff1*soff1  + vd * soff1*soff1*soff1 ;
+        x1 = xtem*cos(pparam3d->GetHdg()) - ytem * sin(pparam3d->GetHdg()) + pparam3d->GetX();
+        y1 = xtem*sin(pparam3d->GetHdg()) + ytem * cos(pparam3d->GetHdg()) + pparam3d->GetY();
+        hdg = CalcHdg(QPointF(x1,y1),QPointF(x,y));
+    }
+    return 0;
+}
+
+int xodrfunc::GetRoadXYByS(Road *pRoad, const double s, double &x, double &y, double &hdg)
+{
+    if(s<0)return -1;
+    if(s>(pRoad->GetRoadLength()+0.1))return -2;
+    if(pRoad == 0)return -3;
+    if(pRoad->GetGeometryBlockCount()<1)return -4;
+    int i;
+    int nroadgeosize = pRoad->GetGeometryBlockCount();
+    RoadGeometry * pgeosel = pRoad->GetGeometryBlock(nroadgeosize -1)->GetGeometryAt(0);
+    for(i=0;i<(nroadgeosize-1);i++)
+    {
+        if(s<pRoad->GetGeometryBlock(i+1)->GetGeometryAt(0)->GetS())
+        {
+
+            pgeosel = pRoad->GetGeometryBlock(0)->GetGeometryAt(0);
+            break;
+        }
+    }
+
+
+    switch (pgeosel->GetGeomType()) {
+    case 0:
+        return GetLineXY((GeometryLine *)pgeosel,(s-pgeosel->GetS()),x,y,hdg);
+        break;
+    case 1:
+        return GetSpiralXY((GeometrySpiral *)pgeosel,(s-pgeosel->GetS()),x,y,hdg);
+        break;
+    case 2:
+        return GetArcXY((GeometryArc *)pgeosel,(s-pgeosel->GetS()),x,y,hdg);
+
+        break;
+    case 3:
+        break;
+    case 4:
+        return GetParamPoly3XY((GeometryParamPoly3 *)pgeosel,(s-pgeosel->GetS()),x,y,hdg);
+        break;
+    default:
+        break;
+    }
+    return -5;
+}
+
+int xodrfunc::GetRoadIndex(OpenDrive * pxodr, Road *pRoad)
+{
+    int nroadcount = pxodr->GetRoadCount();
+    int i;
+    for(i=0;i<nroadcount;i++)
+    {
+        if(pxodr->GetRoad(i) == pRoad)
+        {
+            return i;
+        }
+    }
+    return -1;
+}
+
+int xodrfunc::GetDrivingLane(Road *pRoad, const int nLS, const int nsuggestlane)
+{
+    int nrtn = nsuggestlane;
+    int nLSCount = pRoad->GetLaneSectionCount();
+    if(nLS<0)
+    {
+        qDebug("xodrfunc::GetDrivingLane nLS=%d is Error.",nLS);
+        return nrtn;
+
+    }
+
+    if(nLS>=(nLSCount))
+    {
+        qDebug("xodrfunc::GetDrivingLane nLS=%d is Error. LaneSection Count is %d.",nLS,nLSCount);
+        return nrtn;;
+    }
+
+    LaneSection * pLS = pRoad->GetLaneSection(nLS);
+    int nLaneCount = pLS->GetLaneCount();
+    int i;
+    for(i=0;i<nLaneCount;i++)
+    {
+        if(pLS->GetLane(i)->GetId() == nsuggestlane)
+        {
+            if(pLS->GetLane(i)->GetType() == "driving")
+            {
+                return nsuggestlane;
+                break;
+            }
+        }
+    }
+
+    nrtn = 1000;
+    int ndiff;
+    for(i=0;i<nLaneCount;i++)
+    {
+        Lane * pLane = pLS->GetLane(i);
+        if((pLane->GetId()*nsuggestlane>0)&&(pLane->GetType() == "driving"))
+        {
+            ndiff = pLane->GetId() - nrtn;
+            int xdiff = pLane->GetId() - nsuggestlane;
+            if(abs(xdiff)<abs(ndiff))
+            {
+                nrtn = pLane->GetId();
+            }
+        }
+    }
+    return nrtn;
+}
+
+Lane * xodrfunc::GetLaneByID(LaneSection *pLS, int nlane)
+{
+    int nlanecount = pLS->GetLaneCount();
+    int i;
+    for(i=0;i<nlanecount;i++)
+    {
+        if(pLS->GetLane(i)->GetId() == nlane)
+        {
+            return pLS->GetLane(i);
+        }
+    }
+    return 0;
+}

+ 71 - 0
src/common/common/xodr/xodrfunc.h

@@ -0,0 +1,71 @@
+#ifndef XODRFUNC_H
+#define XODRFUNC_H
+
+#include <OpenDrive/OpenDrive.h>
+
+#include <QPointF>
+
+
+namespace iv {
+struct LanePoint
+{
+    int mnlane;
+    int mnLaneSection;
+    double mS;
+    double mflanewidth;
+    double mflanetocenter;
+    double mfX;
+    double mfY;
+    double mfhdg;
+    int mnlanetype;  //0 driving 1 border 2 none 3 bike
+    int mnlanemarktype; // -1 no 0 solid 1 broken 2 solidsolid
+    int mnlanecolor;
+    double mfGeoX;
+    double mfGeoY;
+
+};
+
+}
+
+class xodrfunc
+{
+public:
+    xodrfunc();
+
+public:
+    static inline double calcpointdis(QPointF p1,QPointF p2);
+    static bool pointinarc(GeometryArc * parc,QPointF poingarc,QPointF point1);
+    static double CalcHdg(QPointF p0, QPointF p1);
+    static double GetParamPoly3Dis(GeometryParamPoly3 * parc,double xnow,double ynow,double & nearx,
+                            double & neary,double & nearhead,double & frels);
+    static double GetArcDis(GeometryArc * parc,double x,double y,double & nearx,
+                            double & neary,double & nearhead,double & frels);
+    static double GetPoly3Dis(GeometryPoly3 * ppoly,double xnow,double ynow,double & nearx,
+                            double & neary,double & nearhead,double & frels);
+    static double GetSpiralDis(GeometrySpiral * pspiral,double xnow,double ynow,double & nearx,
+                            double & neary,double & nearhead,double & frels);
+    static double GetLineDis(GeometryLine * pline,const double x,const double y,double & nearx,
+                             double & neary,double & nearhead,double & frels);
+    static int GetNearPoint(const double x,const double y,OpenDrive * pxodr,Road ** pObjRoad,GeometryBlock ** pgeo, double & fdis,double & nearx,
+                     double & neary,double & nearhead,const double nearthresh,double * pfs=0,int * pnlane= 0,bool bnotuselane = false);
+
+    static double GetAcurateDis(const double x,const double y,Road * pRoad,const  double  s,const double nearx,
+                                const double neary,const double nearhead,int * pnlane= 0);
+
+    static int GetDrivingLane(Road * pRoad,const int nLS,const int nsuggestlane);
+    static Lane * GetLaneByID(LaneSection * pLS,int nlane);
+    static std::vector<iv::LanePoint> GetAllLanePoint(Road * pRoad,const double s,const double x, const double y,const double fhdg);
+
+public:
+    static Road * GetRoadByID(OpenDrive * pxodr,std::string strroadid);
+    static int GetRoadXYByS(Road * pRoad,const double s,double &x, double & y, double & hdg);
+
+    static int GetLineXY(GeometryLine * pline,double soff,double &x, double & y, double & hdg);
+    static int GetSpiralXY(GeometrySpiral * pspira,double soff,double &x, double & y, double & hdg);
+    static int GetArcXY(GeometryArc * parc,double soff,double &x, double & y, double & hdg);
+    static int GetParamPoly3XY(GeometryParamPoly3 * pparam3d,double soff,double &x, double & y, double & hdg);
+
+    static int GetRoadIndex(OpenDrive * pxodr, Road * pRoad);
+};
+
+#endif // XODRFUNC_H

+ 39 - 4
src/common/ivbacktrace/ivbacktrace.cpp

@@ -108,9 +108,10 @@ void savetofile(char * stroutput)
 
     if(file != nullptr)
     {
-        fwrite(stroutput,strnlen(stroutput,1024),1,file);
+        fwrite(stroutput,strnlen(stroutput,6000),1,file);
     }
 
+
     fclose(file);
 }
 
@@ -170,6 +171,30 @@ static void output_addrline(char addr[],char * strtem)
     pclose(file);
 }
 
+static void proc_addrline(int64_t xaddr,char * strtem)
+{
+    char cmd[256];
+    char line[256];
+    FILE* file;
+
+    snprintf(strtem,1000," ");
+    snprintf(cmd, sizeof(cmd), "addr2line -e /proc/%d/exe %x ", getpid(), xaddr);
+    qDebug("%s\n",cmd);
+
+    file = popen(cmd, "r");
+    if(NULL != fgets(line, 256, file))
+    {
+        printf("%s\n", line);
+        snprintf(strtem,1000,"%s\n",line);
+    }
+    if(strnlen(line,255) == 0)
+    {
+        printf("no addr.\n");
+    }
+    pclose(file);
+
+}
+
 void out_stack(char *sig)
 {
     void *array[32];
@@ -212,9 +237,19 @@ void out_stack(char *sig)
     {
 //        qDebug("i is %d",i);
         printf("%s\n",strings[i]);
-        snprintf(strtem,1000,"%s\n",strings[i]);
+//        snprintf(strtem,1000,"%s\n",strings[i]);
+//        strncat(stroutput,strtem,6000);
+//        output_addrline(strings[i],strtem);
+//        strncat(stroutput,strtem,6000);
+    }
+
+    for(i=0;i<size;i++)
+    {
+        int64_t xaddr = (int64_t)((int *)array[i]);
+        printf("addr is %x\n", xaddr);
+        snprintf(strtem,1000,"addr is %x\n", xaddr);
         strncat(stroutput,strtem,6000);
-        output_addrline(strings[i],strtem);
+        proc_addrline(xaddr,strtem);
         strncat(stroutput,strtem,6000);
     }
 
@@ -225,7 +260,7 @@ void out_stack(char *sig)
 
     QTime x;
     x.start();
-    while((unsigned int)(x.elapsed())<size)
+    while((unsigned int)(x.elapsed())<100)
     {
  //       qDebug("hello");
     }

+ 73 - 0
src/common/ivchart/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 28 - 0
src/common/ivchart/ivchart.cpp

@@ -0,0 +1,28 @@
+#include "ivchart.h"
+
+
+#include "ivchart_impl.h"
+
+namespace iv {
+
+Ivchart::Ivchart()
+{
+    ivchart_impl * p = new ivchart_impl();
+    p->start();
+    mpimpl = (void *)p;
+}
+
+Ivchart::~Ivchart()
+{
+    ivchart_impl * p = (ivchart_impl *)mpimpl;
+    delete p;
+}
+
+
+void Ivchart::chartvalue(std::string varname, const double fvalue,const double fvalue_RangeMin ,const double fvalue_RangeMax)
+{
+    ivchart_impl * p = (ivchart_impl *)mpimpl;
+    p->chartvalue(varname,fvalue,fvalue_RangeMin,fvalue_RangeMax);
+}
+
+}

+ 30 - 0
src/common/ivchart/ivchart.h

@@ -0,0 +1,30 @@
+#ifndef IVCHART_H
+#define IVCHART_H
+
+#include <QtCore/qglobal.h>
+
+#include <string>
+
+#if defined(IVCHART_LIBRARY)
+#  define IVCHART_EXPORT Q_DECL_EXPORT
+#else
+#  define IVCHART_EXPORT Q_DECL_IMPORT
+#endif
+
+namespace iv {
+
+
+class IVCHART_EXPORT Ivchart
+{
+public:
+    Ivchart();
+    ~Ivchart();
+public:
+    void chartvalue(std::string varname,const double fvalue,const double fvalue_RangeMin = 0.0,const double fvalue_RangeMax = 1.0);
+private:
+    void * mpimpl;
+};
+
+}
+
+#endif // IVCHART_H

+ 42 - 0
src/common/ivchart/ivchart.pro

@@ -0,0 +1,42 @@
+QT -= gui
+
+QT += dbus
+
+TEMPLATE = lib
+DEFINES += IVCHART_LIBRARY
+
+CONFIG += c++11
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked 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
+
+# You can also make your code fail to compile if it uses 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 += \
+    ../../include/msgtype/ivchart.pb.cc \
+    ivchart.cpp \
+    ivchart_impl.cpp
+
+HEADERS += \
+    ../../include/msgtype/ivchart.pb.h \
+    ivchart.h \
+    ivchart_impl.h
+
+# Default rules for deployment.
+unix {
+    target.path = /usr/lib
+}
+!isEmpty(target.path): INSTALLS += target
+
+INCLUDEPATH += $$PWD/../../include/msgtype
+
+unix: LIBS += -lprotobuf
+
+win32: LIBS += $$PWD\..\..\..\thirdpartylib\protobuf\lib\libprotobuf.a
+win32: INCLUDEPATH+= $$PWD\..\..\..\thirdpartylib\protobuf\src

+ 89 - 0
src/common/ivchart/ivchart_impl.cpp

@@ -0,0 +1,89 @@
+#include "ivchart_impl.h"
+
+
+namespace  iv {
+
+
+ivchart_impl::ivchart_impl()
+{
+
+    mmsg = QDBusMessage::createSignal("/catarc/adc",  "adciv.interface", "ivchart");
+    mmsg<<1;
+}
+
+ivchart_impl::~ivchart_impl()
+{
+    requestInterruption();
+    int i;
+    for(i=0;i<100;i++)
+    {
+        if(isFinished())
+            break;
+        msleep(1);
+    }
+}
+
+void ivchart_impl::chartvalue(std::string varname, const double fvalue, const double fvalue_RangeMin, const double fvalue_RangeMax)
+{
+    iv::ivchart::ivchartunit xivchartunit;
+    xivchartunit.set_strvarname(varname);
+    xivchartunit.set_timex(QDateTime::currentMSecsSinceEpoch());
+    xivchartunit.set_fvalue(fvalue);
+    xivchartunit.set_fvalue_rangemin(fvalue_RangeMin);
+    xivchartunit.set_fvalue_rangemax(fvalue_RangeMax);
+
+    if(mvectorchart.xivchartunit_size() > 10000)
+    {
+        qDebug("ivchart_impl::chartvalue ivchartunit is big value is %d ",mvectorchart.xivchartunit_size());
+        return;
+    }
+
+    mMutexVector.lock();
+    iv::ivchart::ivchartunit * p = mvectorchart.add_xivchartunit();
+    p->CopyFrom(xivchartunit);
+    mMutexVector.unlock();
+}
+
+int ivchart_impl::writechart(iv::ivchart::ivchartarray *pxvectorchart)
+{
+    char * str;
+    int ndatasize = pxvectorchart->ByteSize();
+    str = new char[ndatasize];
+    std::shared_ptr<char> pstr;
+    pstr.reset(str);
+    if(!pxvectorchart->SerializeToArray(str,ndatasize))
+    {
+        qDebug("ivchart_impl::writechart SerializeToArray error.");
+        return -1;
+    }
+    QByteArray ba;
+    ba.append(str,ndatasize);
+
+    QList<QVariant> x;
+    x<<ba;
+    mmsg.setArguments(x);
+    QDBusConnection::sessionBus().send(mmsg);
+    return 0;
+}
+
+void ivchart_impl::run()
+{
+    iv::ivchart::ivchartarray xvectorchart;
+    while(!QThread::isInterruptionRequested())
+    {
+        mWaitMutex.lock();
+        mwc.wait(&mWaitMutex,50);
+        mWaitMutex.unlock();
+        mMutexVector.lock();
+        xvectorchart.Clear();
+        xvectorchart.CopyFrom(mvectorchart);
+        mvectorchart.Clear();
+        mMutexVector.unlock();
+        if(xvectorchart.xivchartunit_size()>0)
+        {
+            writechart(&xvectorchart);
+        }
+    }
+}
+
+}

+ 45 - 0
src/common/ivchart/ivchart_impl.h

@@ -0,0 +1,45 @@
+#ifndef IVCHART_IMPL_H
+#define IVCHART_IMPL_H
+
+#include <QDateTime>
+#include <QtDBus/qdbusmessage.h>
+#include <QtDBus/QDBusConnection>
+
+#include <QThread>
+#include <QWaitCondition>
+#include <QMutex>
+#include <vector>
+#include <memory>
+#include <iostream>
+
+#include <unistd.h>
+
+#include "ivchart.pb.h"
+
+
+namespace  iv {
+
+
+
+class ivchart_impl : public QThread
+{
+public:
+    ivchart_impl();
+    ~ivchart_impl();
+
+public:
+    void chartvalue(std::string varname,const double fvalue,const double fvalue_RangeMin = 0.0,const double fvalue_RangeMax = 1.0);
+
+private:
+    QDBusMessage mmsg;
+    void run();
+    QWaitCondition mwc;
+    QMutex mWaitMutex;
+    iv::ivchart::ivchartarray mvectorchart;
+    QMutex mMutexVector;
+    int writechart(iv::ivchart::ivchartarray * pxvectorchart);
+};
+
+}
+
+#endif // IVCHART_IMPL_H

+ 11 - 6
src/controller/controller_yuhesen/control/control_status.cpp

@@ -1,5 +1,10 @@
 #include <control/control_status.h>
 
+
+#define GET_HIGH_BYTE(x)  ((x >> 8) & 0xFF) 
+#define GET_LOW_BYTE(x)   (x & 0xFF)
+
+
 void iv::control::ControlStatus::set_head()
 {
     command.bit.head = 0xEB;
@@ -8,20 +13,20 @@ void iv::control::ControlStatus::set_head()
 void iv::control::ControlStatus::set_wheel_angle(float angle)
 {
     int ang = (int)(angle * 100);
-    command.bit.ang_H = (ang) >> 8;
-    command.bit.ang_L = (ang) % 256;
+    command.bit.ang_H = get_HIGH_BYTE(ang);
+    command.bit.ang_L = get_LOW_BYTE(ang);
 }
 
 void iv::control::ControlStatus::set_brake(bool enable)
 {
-    command.bit.brake=(unsigned)enable;
+    command.bit.brake=(unsigned char)enable;
 }
 
 void iv::control::ControlStatus::set_velocity(float vel)
 {
     int v = (int)(vel * 1000);
-    command.bit.vel_H = v >> 8;
-    command.bit.vel_L = v % 256;
+    command.bit.vel_H = get_HIGH_BYTE(v);
+    command.bit.vel_L = get_LOW_BYTE(v);
 }
 
 void iv::control::ControlStatus::set_left_light(bool enable)
@@ -42,7 +47,7 @@ void iv::control::ControlStatus::set_right_light(bool enable)
 
 void iv::control::ControlStatus::set_highbeam(bool enable)
 {
-    command.bit.high_beam = (char)enable;
+    command.bit.high_beam = (unsigned char)enable;
 }
 
 void iv::control::ControlStatus::set_dangwei(int dangwei)

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

@@ -107,11 +107,11 @@ int iv::decition::Compute00::getDesiredSpeed(std::vector<GPSData> gpsMap)
                                 {
                                 if(MarkingCount<150)
                                 {
-                                     if((BackAveFive-FrontAveFive)<=4.0)
+                                     if((BackAveFive-FrontAveFive)<=3.5)
                                      {
                                            (*gpsMap[MarkingIndex]).roadMode=14;   //弯道,2米,14
                                      }
-                                     else if((BackAveFive-FrontAveFive)>4.0)
+                                     else if((BackAveFive-FrontAveFive)>3.5)
                                      {
                                            (*gpsMap[MarkingIndex]).roadMode=15;
                                      }

+ 19 - 8
src/decition/decition_brain_sf/decition/adc_adapter/hapo_adapter.cpp

@@ -5,6 +5,8 @@
 #include <iostream>
 #include <fstream>
 
+#include "ivlog.h"
+extern iv::Ivlog * givlog;
 
 using namespace std;
 
@@ -41,7 +43,7 @@ iv::decition::Decition iv::decition::HapoAdapter::getAdapterDeciton(GPS_INS now_
         controlSpeed=0;
         controlBrake=u; //102
         if(obsDistance>0 && obsDistance<10){
-            controlBrake= u*1.5;
+            controlBrake= u*1.0;     //1.5    zj-1.2
         }
          if(abs(dSpeed-realSpeed)<3 &&(obsDistance>40 || obsDistance<0)&&ttc>8 && dSpeed>0 && turn_around
                  && dSpeed>0 && lastBrake==0){
@@ -164,33 +166,42 @@ iv::decition::Decition iv::decition::HapoAdapter::getAdapterDeciton(GPS_INS now_
     }
 
     if(controlSpeed>0){
-        controlSpeed=max(controlSpeed,2.4f);
+        controlSpeed=max(controlSpeed,4.6f);
     }
 
+
+
+
+
+
+
     //0227 10m nei xianzhi shache
-    if(obsDistance<10 &&obsDistance>0){
+    if(obsDistance<18 &&obsDistance>0){
         controlSpeed=0;
-        controlBrake=max(controlBrake,0.8f);
-    }
+        controlBrake=max(controlBrake,0.6f);//0.8   zj-0.6
+        controlBrake=min(controlBrake,0.8f);
 
+    }
 
     if(DecideGps00::minDecelerate<0){
         controlBrake = max((0-DecideGps00::minDecelerate),controlBrake);
         controlSpeed=0;
     }
 
+
     controlBrake=limitBrake(realSpeed,controlBrake,dSpeed,obsDistance,ttc);
 
     controlSpeed = limitSpeed(realSpeed, controlBrake, dSpeed, controlSpeed);
 
    // (*decition)->brake = controlBrake*10;
-      (*decition)->brake = controlBrake*9;
+      (*decition)->brake = controlBrake*8;//9     zj-6
 
     (*decition)->torque=controlSpeed;
       lastBrake= (*decition)->brake;
 
 
-
+      givlog->debug("brain_decition","brake: %f, torque: %f,obsDistance: %f",
+                    (*decition)->brake,(*decition)->torque,obsDistance);
 
 
     lastTorque=(*decition)->torque;
@@ -209,7 +220,7 @@ iv::decition::Decition iv::decition::HapoAdapter::getAdapterDeciton(GPS_INS now_
     (*decition)->angleEnable=true;
     (*decition)->speedEnable=true;
     (*decition)-> brakeEnable=true;
-    (*decition)->air_enable = true;
+    (*decition)->air_enable = false;
     (*decition)->driveMode=1;
     (*decition)->brakeType=0;
     (*decition)->angSpeed=60;

+ 23 - 23
src/decition/decition_brain_sf/decition/brain.cpp

@@ -494,31 +494,31 @@ void iv::decition::BrainDecition::run() {
 
         eyes->getSensorObstacle(obs_radar_, obs_camera_,gps_data_, obs_lidar_grid_);	//从传感器线程临界区交换数据
 
+/*
+        if(obs_lidar_grid_!= NULL)
+        {
+            std::cout<<"receive fusion date"<<std::endl;
+            int i,j;
+            for(i=0;i<iv::grx;i++)
+            {
+                for(j=0;j<iv::gry;j++)
+                {
+                 if(obs_lidar_grid_[i*iv::gry+j].ob == 2){
+                     std::cout<<"ok"<<std::endl;
+                     if(obs_lidar_grid_[i*iv::gry+j].id > 10)
+                     {
+                         int xx = obs_lidar_grid_[i*iv::gry+j].id;
+                         xx++;
+                     }
+                      std::cout<<obs_lidar_grid_[i*iv::gry+j].id<<std::endl;
+                 }
 
-//        if(obs_lidar_grid_!= NULL)
-//        {
-//            std::cout<<"receive fusion date"<<std::endl;
-//            int i,j;
-//            for(i=0;i<iv::grx;i++)
-//            {
-//                for(j=0;j<iv::gry;j++)
-//                {
-//                 if(obs_lidar_grid_[i*iv::gry+j].ob == 2){
-//                     std::cout<<"ok"<<std::endl;
-//                     if(obs_lidar_grid_[i*iv::gry+j].id > 10)
-//                     {
-//                         int xx = obs_lidar_grid_[i*iv::gry+j].id;
-//                         xx++;
-//                     }
-//                      std::cout<<obs_lidar_grid_[i*iv::gry+j].id<<std::endl;
-//                 }
-
-
-//                }
-//            }
-//              std::cout<<"print fusion date end"<<std::endl;
-//        }
 
+                }
+            }
+              std::cout<<"print fusion date end"<<std::endl;
+        }
+*/
 
         ServiceLidar.copylidarperto(lidar_per);
 

+ 28 - 14
src/decition/decition_brain_sf/decition/decide_gps_00.cpp

@@ -978,11 +978,13 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
         roadSum = gpsMapLine[PathPoint]->roadSum*3;
     }
 
+
     if(roadNowStart){
         roadNow=roadOri;
         roadNowStart=false;
     }
 
+
     if(ServiceCarStatus.avoidObs){
          gpsMapLine[PathPoint]->runMode=1;
     }else{
@@ -1517,7 +1519,7 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
     }
 
     //shiyanbizhang 0929
-    if(obsDistance>0&& (obsDistance<ServiceCarStatus.socfDis+20.0) &&(abs(realspeed)<1.0) &&
+    if(obsDistance>0&& (obsDistance<ServiceCarStatus.aocfDis) &&(abs(realspeed)<5.0) &&
             (vehState==normalRun||vehState==backOri || vehState==avoiding) &&(ObsTimeStart==-1)
             && (gpsMapLine[PathPoint]->runMode==1)){
         ObsTimeStart=GetTickCount();
@@ -1537,7 +1539,7 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
         cout<<"\n====================preAvoid time count finish==================\n"<<endl;
     }
 
-    if(obsDistance<0 ||obsDistance>ServiceCarStatus.socfDis){
+    if(obsDistance<0 ||obsDistance>ServiceCarStatus.aocfDis){
         ObsTimeStart=-1;
         ObsTimeEnd=-1;
         ObsTimeSpan=-1;
@@ -1581,6 +1583,11 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
     }
 
 
+
+      givlog->debug("brain_decition","mfRoadwidth: %f",
+                   gpsMapLine[PathPoint]->mfLaneWidth );
+
+
     if (vehState == preAvoid)
     {
         cout<<"\n====================preAvoid==================\n"<<endl;
@@ -1899,7 +1906,12 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
    // if(obsDistance>6.5){
      //   obsDistance=500;
     //}
-    if(obsDistance>0 && obsDistance<10){
+
+    if(ServiceCarStatus.msysparam.mvehtype=="hapo"){
+        if(obsDistance>0 && obsDistance<8){
+                dSpeed=0;
+            }
+    }else if(obsDistance>0 && obsDistance<15){
         dSpeed=0;
     }
     //  obsDistance=-1; //1227
@@ -2555,10 +2567,12 @@ void iv::decition::DecideGps00::computeObsOnRoad(iv::LidarGridPtr lidarGridPtr,
         obsSpeed=obsSd;
     }
 
-
-
+    if(obsDistance<500&&obsDistance>0){
+     std::cout <<ServiceCarStatus.mRunTime.elapsed()<<"ms:"<< "obsDistance<500:" << obsDistance << std::endl;
+    }
     std::cout <<ServiceCarStatus.mRunTime.elapsed()<<"ms:"<< "最终得出的obsDistance:" << obsDistance << std::endl;
 
+
     ServiceCarStatus.mObs = obsDistance;
     if(ServiceCarStatus.mObs>100){
         ServiceCarStatus.mObs =-1;
@@ -2903,7 +2917,7 @@ int iv::decition::DecideGps00::chooseBackRoad(iv::LidarGridPtr lidarGridPtr, GPS
 
     //if ((GetDistance(now_gps_ins, startAvoid_gps_ins)>avoidRunDistance)&&
     //(checkReturnEnable(avoidX, lidarGridPtr,roadOri)))
-    if ((GetDistance(now_gps_ins, startAvoidGpsInsVector[roadOri])>max(avoidMinDistanceVector[roadOri],30.0)) &&
+    if ((GetDistance(now_gps_ins, startAvoidGpsInsVector[roadOri])>max(avoidMinDistanceVector[roadOri],20.0)) &&
             (checkReturnEnable(avoidX, lidarGridPtr, roadOri)))
     {
         roadPre = roadOri;
@@ -3344,7 +3358,7 @@ void iv::decition::DecideGps00::getEsrObsDistanceByFrenet(const std::vector<Poin
 void iv::decition::DecideGps00::getV2XTrafficPositionVector(const std::vector<GPSData> gpsMapLine){
     v2xTrafficVector.clear();
     for (int var = 0; var < gpsMapLine.size(); var++) {
-        if(gpsMapLine[var]->roadMode==6){
+        if(gpsMapLine[var]->roadMode==6|| gpsMapLine[var]->mode2==1000001){
             v2xTrafficVector.push_back(var);
         }
     }
@@ -3473,28 +3487,28 @@ float iv::decition::DecideGps00::computeAvoidX(int roadAim,int roadOri,GPSData g
         return 0;
     }
     float x=0;
-    float veh_to_roadSide=(gps->mfRoadWidth- ServiceCarStatus.msysparam.vehWidth)*0.5;
+    float veh_to_roadSide=(gps->mfLaneWidth- ServiceCarStatus.msysparam.vehWidth)*0.5;
     float roadSide_to_roadSide=ServiceCarStatus.msysparam.vehWidth;
     if(!ServiceCarStatus.inRoadAvoid){
-        x= (roadOri-roadAim)*gps->mfRoadWidth;
+        x= (roadOri-roadAim)*gps->mfLaneWidth;
     }else{
         int num=roadOri-roadAim;
         switch (abs(num)%3) {
         case 0:
-            x=(num/3)*gps->mfRoadWidth;
+            x=(num/3)*gps->mfLaneWidth;
             break;
         case 1:
             if(num>0){
-                x=(num/3)*gps->mfRoadWidth +veh_to_roadSide;
+                x=(num/3)*gps->mfLaneWidth +veh_to_roadSide;
             }else{
-                x=(num/3)*gps->mfRoadWidth -veh_to_roadSide;
+                x=(num/3)*gps->mfLaneWidth -veh_to_roadSide;
             }
             break;
         case 2:
             if(num>0){
-                x=(num/3)*gps->mfRoadWidth +veh_to_roadSide+roadSide_to_roadSide;
+                x=(num/3)*gps->mfLaneWidth +veh_to_roadSide+roadSide_to_roadSide;
             }else{
-                x=(num/3)*gps->mfRoadWidth -veh_to_roadSide-roadSide_to_roadSide;
+                x=(num/3)*gps->mfLaneWidth -veh_to_roadSide-roadSide_to_roadSide;
             }
 
             break;

+ 2 - 0
src/detection/detection_lidar_ukf_pda/imm_ukf_pda.cpp

@@ -690,6 +690,8 @@ void ImmUkfPda::makeOutput(const iv::lidar::objectarray & input,
     double tyaw = targets_[i].x_merge_(3);
     double tyaw_rate = targets_[i].x_merge_(4);
 
+    std::cout<<"          v     tyaw :      "<<tv<<"  "   <<tyaw<<std::endl;
+
     while (tyaw > M_PI)
       tyaw -= 2. * M_PI;
     while (tyaw < -M_PI)

+ 5 - 7
src/driver/driver_cloud_grpc_client_BS/main.cpp

@@ -43,8 +43,8 @@ mainloop::mainloop(VehicleControlClient *pCC,DataExchangeClient *pUC)
 void mainloop::run()
 {
     while (1) {
-        msleep(100);
-//        if(pControlClient->get_isNeedMap() == true)
+//        msleep(100);
+        if(pControlClient->get_isNeedMap() == true)
         {
             std::cout<<"patrol path calculating"<<std::endl;
             QFile mapfile("/home/samuel/Documents/path1.txt");
@@ -64,12 +64,10 @@ void mainloop::run()
                     somePoints.append(onePoint);
                 }
             }
-//            pUploadClient->updatePath(pControlClient->get_patrolPathID(),somePoints);
-            pUploadClient->updatePath("testpath1",somePoints);
+            pUploadClient->updatePath(pControlClient->get_patrolPathID(),somePoints);
             pUploadClient->uploadPath();
             pControlClient->set_isNeedMap(false);
         }
-//        std::cout<<"thread running"<<std::endl;
     }
 }
 
@@ -157,10 +155,10 @@ int main(int argc, char *argv[])
     std::string upload_str = gstrserverip+":";
     upload_str = upload_str + gstruploadPort ;
 
-    VehicleControlClient *vehiclecontrol = new VehicleControlClient(grpc::CreateChannel(control_str, grpc::InsecureChannelCredentials()));
-
     DataExchangeClient *vehicleupload = new DataExchangeClient(grpc::CreateChannel(upload_str, grpc::InsecureChannelCredentials()));
 
+    VehicleControlClient *vehiclecontrol = new VehicleControlClient(grpc::CreateChannel(control_str, grpc::InsecureChannelCredentials()));
+
     VehiclePatrolExceptionClient vehiclepatrol(grpc::CreateChannel(patrol_str, grpc::InsecureChannelCredentials()));
 
     mainloop loop(vehiclecontrol,vehicleupload);

+ 21 - 12
src/driver/driver_cloud_grpc_client_BS/vehicle_control.cpp

@@ -19,11 +19,11 @@ VehicleControlClient::VehicleControlClient(std::shared_ptr<Channel> channel)
     stub_ = VehicleControl::NewStub(channel);
 
     controlTimer = new QTimer();
-    connect(controlTimer,SIGNAL(timeout()),this,SLOT(controlTimeout()));
-//    controlTimer->start(std::atoi(gstrcontrolInterval.c_str()));
+    connect(controlTimer,&QTimer::timeout,this,&VehicleControlClient::controlTimeout);
+    controlTimer->start(std::atoi(gstrcontrolInterval.c_str()));
 
     uploadMapTimer = new QTimer();
-    connect(uploadMapTimer,SIGNAL(timeout()),this,SLOT(uploadMapTimeout()));
+    connect(uploadMapTimer,&QTimer::timeout,this,&VehicleControlClient::uploadMapTimeout);
     uploadMapTimer->start(std::atoi(gstruploadMapInterval.c_str()));
 }
 
@@ -56,8 +56,17 @@ std::string VehicleControlClient::vehicleControl(void)
             shiftCMD = reply.shiftcmd();
             steeringWheelAngleCMD = reply.steeringwheelanglecmd();
             throttleCMD = reply.throttlecmd();
+            std::cout<<"throttle:"<<reply.throttlecmd()<<std::endl;
             brakeCMD = reply.brakecmd();
         }
+        else
+        {
+//            std::cout<<"id:"<<reply.id()<<std::endl;
+//            if(throttleCMD > 0)throttleCMD -= 1.5;
+//            if(throttleCMD <= 0)throttleCMD = 0;
+//            if(brakeCMD > 0)brakeCMD -= 1.5;
+//            if(brakeCMD <= 0)brakeCMD = 0;
+        }
         return "vehicleControl RPC successed";
     } else {
         std::cout << status.error_code() << ": " << status.error_message()
@@ -86,19 +95,19 @@ std::string VehicleControlClient::uploadMap(void)
     if (status.ok()) {
         if(reply.id() == gstrid)
         {
-            std::cout<<reply.id()<<std::endl;
+//            std::cout<<reply.id()<<std::endl;
             isNeedMap = false;
             patrolPathID = "noPath";
             POIPoints.clear();
 
             isNeedMap = reply.isneedmap();
-            std::cout<<reply.isneedmap()<<std::endl;
+//            std::cout<<reply.isneedmap()<<std::endl;
             patrolPathID = reply.patrolpathid();
-            std::cout<<reply.patrolpathid()<<std::endl;
+//            std::cout<<reply.patrolpathid()<<std::endl;
             for(int i = 0;i < reply.mappoints_size();i++)
             {
                 POIPoints.append(reply.mappoints(i));
-                std::cout<<reply.mappoints(i).index()<<std::endl;
+//                std::cout<<reply.mappoints(i).index()<<std::endl;
             }
         }
         return "UploadMap RPC successed";
@@ -155,18 +164,18 @@ void VehicleControlClient::updateMapPOIData(void)
 
 void VehicleControlClient::updateCtrolMode(void)
 {
-    std::cout<<"modeCMD:"<<modeCMD<<std::endl;
+//    std::cout<<"modeCMD:"<<modeCMD<<std::endl;
 }
 
 void VehicleControlClient::controlTimeout(void)
 {
     std::string reply = changeCtrlMode();
-    std::cout<< reply <<std::endl;
+//    std::cout<< reply <<std::endl;
     updateCtrolMode();
 
     reply = vehicleControl();
-    std::cout<< reply <<std::endl;
-    if(modeCMD == CtrlMode::CMD_REMOTE)
+//    std::cout<< reply <<std::endl;
+    if(modeCMD == CtrlMode::CMD_REMOTE || modeCMD == CtrlMode::CMD_CLOUD_PLATFORM)
     {
         updateControlData();
     }
@@ -177,7 +186,7 @@ void VehicleControlClient::uploadMapTimeout(void)
     if(isNeedMap == false)
     {
         std::string reply = uploadMap();
-        std::cout<< reply <<std::endl;
+//        std::cout<< reply <<std::endl;
         if(isNeedMap == true)
         {
             updateMapPOIData();

+ 4 - 4
src/driver/driver_cloud_grpc_client_BS/vehicle_control.h

@@ -45,10 +45,10 @@ public:
 private:
     std::unique_ptr<VehicleControl::Stub> stub_;
 
-    org::jeecg::defsControl::grpc::ShiftStatus shiftCMD;
-    double steeringWheelAngleCMD;
-    double throttleCMD;
-    double brakeCMD;
+    org::jeecg::defsControl::grpc::ShiftStatus shiftCMD = org::jeecg::defsControl::grpc::ShiftStatus::SHIFT_PARKING;
+    double steeringWheelAngleCMD = 0;
+    double throttleCMD = 0;
+    double brakeCMD = 0;
 
     bool isNeedMap = false;
     std::string patrolPathID;

+ 23 - 21
src/driver/driver_cloud_grpc_client_BS/vehicle_patrol.cpp

@@ -16,7 +16,7 @@ VehiclePatrolExceptionClient::VehiclePatrolExceptionClient(std::shared_ptr<Chann
     stub_ = VehiclePatrolException::NewStub(channel);
 
     patrolTimer = new QTimer();
-    connect(patrolTimer,SIGNAL(timeout()),this,SLOT(patrolTimeout()));
+    connect(patrolTimer,&QTimer::timeout,this,&VehiclePatrolExceptionClient::patrolTimeout);
 //    patrolTimer->start(std::atoi(gstrpatrolInterval.c_str()));
 }
 
@@ -34,6 +34,7 @@ std::string VehiclePatrolExceptionClient::uploadVehiclePatrolInfo(void)
     request.set_violationstatus(violationStatus);
     request.set_vehiclelicensenumber(vehicleLicenseNumber);
     request.set_violationimage(violationImage.data(),violationImage.size());
+    request.set_violationtime(violationTime);
     request.mutable_violationposition()->CopyFrom(violationPosition);
 
     request.set_isfsm(isFSM);
@@ -78,13 +79,13 @@ void VehiclePatrolExceptionClient::updatePatrolData(void)
     violationStatus = 2;
     vehicleLicenseNumber = "津B654321";
 
-//    QFile xFile;
-//    xFile.setFileName("/home/samuel/Pictures/123.jpg");
-//    if(xFile.open(QIODevice::ReadOnly))
-//    {
-//        violationImage = xFile.readAll();
-//    }
-//    xFile.close();
+    QFile xFile;
+    xFile.setFileName("/home/samuel/Pictures/123.jpg");
+    if(xFile.open(QIODevice::ReadOnly))
+    {
+        violationImage = xFile.readAll();
+    }
+    xFile.close();
 
     violationTime = QDateTime::currentMSecsSinceEpoch();
     violationPosition.set_height(0.1);
@@ -94,12 +95,12 @@ void VehiclePatrolExceptionClient::updatePatrolData(void)
     isFSM = true;
     fireStatus = 1;
 
-//    xFile.setFileName("/home/samuel/Pictures/123.jpg");
-//    if(xFile.open(QIODevice::ReadOnly))
-//    {
-//        fireImage = xFile.readAll();
-//    }
-//    xFile.close();
+    xFile.setFileName("/home/samuel/Pictures/123.jpg");
+    if(xFile.open(QIODevice::ReadOnly))
+    {
+        fireImage = xFile.readAll();
+    }
+    xFile.close();
 
     fireTime = QDateTime::currentMSecsSinceEpoch();
     firePosition.set_height(0.1);
@@ -109,12 +110,12 @@ void VehiclePatrolExceptionClient::updatePatrolData(void)
     isTSGM = true;
     gateStatus = 2;
 
-//    xFile.setFileName("/home/samuel/Pictures/123.jpg");
-//    if(xFile.open(QIODevice::ReadOnly))
-//    {
-//        gateImage = xFile.readAll();
-//    }
-//    xFile.close();
+    xFile.setFileName("/home/samuel/Pictures/123.jpg");
+    if(xFile.open(QIODevice::ReadOnly))
+    {
+        gateImage = xFile.readAll();
+    }
+    xFile.close();
 
     gateTime = QDateTime::currentMSecsSinceEpoch();
     gatePosition.set_height(0.1);
@@ -127,5 +128,6 @@ void VehiclePatrolExceptionClient::updatePatrolData(void)
 void VehiclePatrolExceptionClient::patrolTimeout(void)
 {
     updatePatrolData();
-    uploadVehiclePatrolInfo();
+    std::string reply = uploadVehiclePatrolInfo();
+    std::cout<< reply <<std::endl;
 }

+ 2 - 2
src/driver/driver_cloud_grpc_client_BS/vehicle_upload.cpp

@@ -21,7 +21,7 @@ DataExchangeClient::DataExchangeClient(std::shared_ptr<Channel> channel)
     stub_ = DataExchange::NewStub(channel);
 
     uploadTimer = new QTimer();
-    connect(uploadTimer,SIGNAL(timeout()),this,SLOT(uploadTimeout()));
+    connect(uploadTimer,&QTimer::timeout,this,&DataExchangeClient::uploadTimeout);
     uploadTimer->start(std::atoi(gstruploadInterval.c_str()));
 }
 
@@ -203,5 +203,5 @@ void DataExchangeClient::uploadTimeout(void)
 {
     updateData();
     std::string reply = uploadVehicleInfo();
-    std::cout<< reply <<std::endl;
+//    std::cout<< reply <<std::endl;
 }

+ 13 - 24
src/driver/driver_map_xodrload/driver_map_xodrload.pro

@@ -12,26 +12,16 @@ CONFIG -= app_bundle
 # deprecated API in order to know how to port your code away from it.
 DEFINES += QT_DEPRECATED_WARNINGS
 
+QMAKE_CXXFLAGS +=  -g
+
 # 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 += main.cpp     \
+    ../../common/common/xodr/xodrfunc.cpp \
     ../../include/msgtype/v2x.pb.cc \
-    ../../common/common/xodr/OpenDrive/OpenDriveXmlWriter.cpp \
-    ../../common/common/xodr/OpenDrive/OtherStructures.cpp \
-    ../../common/common/xodr/OpenDrive/OpenDrive.cpp \
-    ../../common/common/xodr/OpenDrive/Road.cpp \
-    ../../common/common/xodr/OpenDrive/Junction.cpp \
-    ../../common/common/xodr/OpenDrive/Lane.cpp \
-    ../../common/common/xodr/OpenDrive/OpenDriveXmlParser.cpp \
-    ../../common/common/xodr/OpenDrive/ObjectSignal.cpp \
-    ../../common/common/xodr/OpenDrive/RoadGeometry.cpp \
-    ../../common/common/xodr/TinyXML/tinyxml.cpp \
-    ../../common/common/xodr/TinyXML/tinyxmlparser.cpp \
-    ../../common/common/xodr/TinyXML/tinystr.cpp \
-    ../../common/common/xodr/TinyXML/tinyxmlerror.cpp \
     fresnl.cpp \
     const.cpp \
     polevl.c \
@@ -45,18 +35,8 @@ SOURCES += main.cpp     \
 
 HEADERS += \
     ../../../include/ivexit.h \
+    ../../common/common/xodr/xodrfunc.h \
     ../../include/msgtype/v2x.pb.h \
-    ../../common/common/xodr/OpenDrive/OpenDriveXmlParser.h \
-    ../../common/common/xodr/OpenDrive/RoadGeometry.h \
-    ../../common/common/xodr/OpenDrive/Road.h \
-    ../../common/common/xodr/OpenDrive/Junction.h \
-    ../../common/common/xodr/OpenDrive/OpenDriveXmlWriter.h \
-    ../../common/common/xodr/OpenDrive/Lane.h \
-    ../../common/common/xodr/OpenDrive/OtherStructures.h \
-    ../../common/common/xodr/OpenDrive/OpenDrive.h \
-    ../../common/common/xodr/OpenDrive/ObjectSignal.h \
-    ../../common/common/xodr/TinyXML/tinyxml.h \
-    ../../common/common/xodr/TinyXML/tinystr.h \
     mconf.h \
     globalplan.h \
     gps_type.h \
@@ -86,4 +66,13 @@ HEADERS += \
 
 INCLUDEPATH += $$PWD/../../common/common/xodr
 
+!include(../../common/common/xodr/OpenDrive/OpenDrive.pri ) {
+    error( "Couldn't find the OpenDrive.pri file!" )
+}
+
+!include(../../common/common/xodr/TinyXML/TinyXML.pri ) {
+    error( "Couldn't find the TinyXML.pri file!" )
+}
+
+
 

파일 크기가 너무 크기때문에 변경 상태를 표시하지 않습니다.
+ 543 - 295
src/driver/driver_map_xodrload/globalplan.cpp


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

@@ -4,6 +4,8 @@
 
 #include <vector>
 
+#include "xodrfunc.h"
+
 #include "xodrdijkstra.h"
 class PlanPoint
 {
@@ -33,6 +35,16 @@ public:
     int nSignal = -1;   //if 0 no signal point
 
     int nRoadID =-1;
+
+    double mfSecx;
+    double mfSecy;
+    int nlrchange; //1 left 2 right
+};
+
+class LaneChangePoint
+{
+    int nRoadID = -1;
+    double mS = 0;
 };
 
 int GetNearPoint(const double x,const double y,OpenDrive * pxodr,Road ** pObjRoad,GeometryBlock ** pgeo, double & s,double & nearx,

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

@@ -27,6 +27,8 @@
 
 #include "ivversion.h"
 
+#include "ivbacktrace.h"
+
 OpenDrive mxodr;
 xodrdijkstra * gpxd;
 bool gmapload = false;
@@ -79,7 +81,6 @@ bool LoadXODR(std::string strpath)
     }
 
 
-
     xodrdijkstra * pxd = new xodrdijkstra(&mxodr);
     gpxd = pxd;
 //    std::vector<int> xpath = pxd->getpath(10001,2,30012,2);
@@ -795,6 +796,9 @@ int main(int argc, char *argv[])
     showversion("driver_map_xodrload");
     QCoreApplication a(argc, argv);
 
+    RegisterIVBackTrace();
+
+
     gfault = new iv::Ivfault("driver_map_xodrload");
     givlog = new iv::Ivlog("driver_map_xodrload");
 

+ 405 - 9
src/driver/driver_map_xodrload/xodrdijkstra.cpp

@@ -94,6 +94,7 @@ Road * xodrdijkstra::GetRoadByID(int nRoadID)
     }
 
     std::cout<<"xodrdijkstra::GetRoadByID "<<nRoadID<<"  Fail."<<std::endl;
+    return 0;
 }
 
 
@@ -137,13 +138,47 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
 
             if(px->GetLaneSection(j)->GetLeftLaneCount()>0)
             {
-                roadedge xroad(atoi(px->GetRoadId().data()),atoi(px->GetRoadJunction().data()),px->GetRoadLength(),1,j,px);
+
+                double fseclen = 0;
+                if(j<(px->GetLaneSectionCount() -1))
+                {
+
+                    fseclen = px->GetLaneSection(j+1)->GetS() - px->GetLaneSection(j)->GetS();
+
+                }
+                else
+                {
+                    fseclen = px->GetRoadLength() - px->GetLaneSection(j)->GetS();
+                }
+
+                roadedge xroad(atoi(px->GetRoadId().data()),atoi(px->GetRoadJunction().data()),fseclen,1,j,px);
+//                roadedge xroad(atoi(px->GetRoadId().data()),atoi(px->GetRoadJunction().data()),px->GetRoadLength(),1,j,px);
+
+
                 //           xroad.mpx = px;
                 mroadedge.push_back(xroad);
             }
             if(px->GetLaneSection(j)->GetRightLaneCount()>0)
             {
-                roadedge xroad(atoi(px->GetRoadId().data()),atoi(px->GetRoadJunction().data()),px->GetRoadLength(),2,j,px);
+                double fseclen = 0;
+                if(j<(px->GetLaneSectionCount() -1))
+                {
+
+                    fseclen = px->GetLaneSection(j+1)->GetS() - px->GetLaneSection(j)->GetS();
+
+                }
+                else
+                {
+                    fseclen = px->GetRoadLength() - px->GetLaneSection(j)->GetS();
+                }
+//                if((px->GetRoadId() == "10019")||(px->GetRoadId() == "10020"))
+//                {
+//                    int axy = 1;
+//                }
+                roadedge xroad(atoi(px->GetRoadId().data()),atoi(px->GetRoadJunction().data()),fseclen,2,j,px);
+
+//                roadedge xroad(atoi(px->GetRoadId().data()),atoi(px->GetRoadJunction().data()),px->GetRoadLength(),2,j,px);
+
                 //           xroad.mpx = px;
                 mroadedge.push_back(xroad);
             }
@@ -192,6 +227,9 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
 
             int road_from = atoi(pjc->GetIncomingRoad().data());
             int road_to = atoi(pjc->GetConnectingRoad().data());
+
+            Road * pRoad_From = GetRoadByID(road_from);
+            Road * pRoad_To = GetRoadByID(road_to);
             int k;
             for(k=0;k<pjc->GetJunctionLaneLinkCount();k++)
             {
@@ -234,6 +272,8 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
 //                    if(lr_from == 2)
                     if(lr_to == 1)
                     {
+                        fromedge = getroadedge(road_from,lr_from,pRoad_From->GetLaneSectionCount() -1);
+                        toedge = getroadedge(road_to,lr_to);
                         a = mroadedge[fromedge].mvertexend;
                         b = mroadedge[toedge].mvertexstart;
                         lnu.mpFromRoad = GetRoadByID(road_from);
@@ -245,6 +285,8 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
                     }
                     else
                     {
+                        fromedge = getroadedge(road_from,lr_from);
+                        toedge = getroadedge(road_to,lr_to,pRoad_To->GetLaneSectionCount() -1);
                         a = mroadedge[fromedge].mvertexstart;
                         b = mroadedge[toedge].mvertexend;
                         lnu.mpFromRoad = GetRoadByID(road_to);
@@ -262,6 +304,8 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
  //                   if(lr_from == 1)
                     if(lr_to == 2)
                     {
+                        fromedge = getroadedge(road_from,lr_from,pRoad_From->GetLaneSectionCount() -1);
+                        toedge = getroadedge(road_to,lr_to);
                         a = mroadedge[fromedge].mvertexend;
                         b = mroadedge[toedge].mvertexstart;
                         lnu.mpFromRoad = GetRoadByID(road_from);
@@ -273,6 +317,8 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
                     }
                     else
                     {
+                        fromedge = getroadedge(road_from,lr_from);
+                        toedge = getroadedge(road_to,lr_to,pRoad_To->GetLaneSectionCount() -1);
                         a = mroadedge[fromedge].mvertexstart;
                         b = mroadedge[toedge].mvertexend;
                         lnu.mpFromRoad = GetRoadByID(road_to);
@@ -504,6 +550,14 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
                     int nroadpre = atoi(px->GetPredecessor()->GetElementId().data());
                     int nroadcur = atoi(px->GetRoadId().data());
 
+                    Road * pRoad_Pre = GetRoadByID(nroadpre);
+
+                    if(pRoad_Pre == 0)
+                    {
+                        qDebug("Pre Road Missing.");
+                        continue;
+                    }
+
 
 //                    if(nroadcur == 30012)
 //                    {
@@ -527,7 +581,7 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
                             {
                                 if(npre < 0)
                                 {
-                                    int nedgepre = getroadedge(nroadpre,2);
+                                    int nedgepre = getroadedge(nroadpre,2,pRoad_Pre->GetLaneSectionCount()-1);
                                     a = mroadedge[nedgepre].mvertexend;
                                     lnu.mpFromRoad = GetRoadByID(nroadpre);
                                     lnu.mpToRoad = GetRoadByID(nroadcur);
@@ -538,7 +592,7 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
                                 }
                                 else
                                 {
-                                    int nedgepre = getroadedge(nroadpre,1);
+                                    int nedgepre = getroadedge(nroadpre,1,pRoad_Pre->GetLaneSectionCount()-1);
                                     a = mroadedge[nedgepre].mvertexstart;
                                     lnu.mpFromRoad = GetRoadByID(nroadcur);
                                     lnu.mpToRoad = GetRoadByID(nroadpre);
@@ -939,6 +993,35 @@ xodrdijkstra::xodrdijkstra(OpenDrive  * pxodr)
     int nvertexnum = xvalidvertex.size(); //vertex num
     mvertexnum = nvertexnum;
 
+    mvectorvertexedge.clear();
+
+    int nmaxvertex = 0;
+    for(i=0;i<nvertexnum;i++)
+    {
+        if(xvalidvertex[i]>nmaxvertex)nmaxvertex = xvalidvertex[i];
+    }
+
+//    for(i=0;i<mroadedge.size();i++)
+//    {
+//        if(mroadedge[i].mvertexstart>nmaxvertex)nmaxvertex = mroadedge[i].mvertexstart;
+//    }
+
+    for(i=0;i<=nmaxvertex;i++)
+    {
+        vertexedge x;
+        mvectorvertexedge.push_back(x);
+    }
+
+    for(i=0;i<mroadedge.size();i++)
+    {
+        mvectorvertexedge[mroadedge[i].mvertexstart].mvectorroadedge.push_back(&mroadedge[i]);
+    }
+
+    std::cout<<" max is "<<nmaxvertex<<" num is "<<nvertexnum<<std::endl;
+    nmaxvertex = nmaxvertex + 0;
+
+
+
 
 }
 
@@ -949,6 +1032,15 @@ int xodrdijkstra::getroadedge(int nroad,int leftright,int nsection )
     int nrtn = -1;
 
     int i;
+
+//    for(i=0;i<mroadedge.size();i++)
+//    {
+//        if((mroadedge[i].mroadid == nroad) &&(mroadedge[i].mnleftright == leftright) )
+//        {
+//            qDebug("equal, road %d edge %d ",nroad,i);
+//        }
+//    }
+
     for(i=0;i<mroadedge.size();i++)
     {
         if((mroadedge[i].mroadid == nroad) &&(mroadedge[i].mnleftright == leftright) &&(nsection == mroadedge[i].mnsectionid))
@@ -969,6 +1061,17 @@ inline double xodrdijkstra::getedgedis(int vs, int vd)
 
     std::vector<roadedge > * proadedge = &mroadedge;
     double dis = std::numeric_limits<double>::max();
+
+    for(i=0;i<mvectorvertexedge[vs].mvectorroadedge.size();i++)
+    {
+        if((vs == mvectorvertexedge[vs].mvectorroadedge[i]->mvertexstart)&&(vd == mvectorvertexedge[vs].mvectorroadedge[i]->mvertexend))
+        {
+            dis = mroadedge[i].mlen;
+            return dis;
+        }
+    }
+    return dis;
+
     for(i=0;i<mroadedge.size();i++)
     {
         if((vs == mroadedge[i].mvertexstart)&&(vd == mroadedge[i].mvertexend))
@@ -980,15 +1083,57 @@ inline double xodrdijkstra::getedgedis(int vs, int vd)
     return dis;
 }
 
-std::vector<int> xodrdijkstra::getpath(int srcroadid, int nsrclr, int dstroadid, int ndstlr)
+int xodrdijkstra::GetRoadSectionIndexByS(Road *pRoad, const double s)
+{
+    int nrtn = -1;
+    if(s<0)return nrtn;
+    if(s>pRoad->GetRoadLength())return nrtn;
+    int i;
+    int nseccount = pRoad->GetLaneSectionCount();
+    if(nseccount== 1)return 0;
+    for(i=0;i<(nseccount-1);i++)
+    {
+        if(s<(pRoad->GetLaneSection(i+1)->GetS()))
+        {
+            break;
+        }
+    }
+    return i;
+}
+
+double xodrdijkstra::getpathlength(std::vector<int> xvectorpath)
+{
+    int i;
+    int nsize = xvectorpath.size();
+    double flen = 0;
+    for(i=0;i<nsize;i++)
+    {
+        flen = flen + mroadedge[xvectorpath[i]].mlen;
+    }
+    return flen;
+}
+
+std::vector<int> xodrdijkstra::getpath(int srcroadid, int nsrclr, int dstroadid, int ndstlr,const double s_src ,const double s_obj )
 {
 
     std::vector<int> rtnpath;
     int nvertexnum = mvertexnum;
     int i;
 
-    int srcedge = getroadedge(srcroadid,nsrclr);
-    int dstedge = getroadedge(dstroadid,ndstlr);
+    int nsecsrc =0;
+    int nsecdst =0;
+    nsecsrc = GetRoadSectionIndexByS(GetRoadByID(srcroadid),s_src);
+    nsecdst = GetRoadSectionIndexByS(GetRoadByID(dstroadid),s_obj);
+    if((nsecsrc<0)||(nsecdst<0))
+    {
+        qDebug("getpath section error.");
+        return rtnpath;
+    }
+    int srcedge = getroadedge(srcroadid,nsrclr,nsecsrc);
+    int dstedge = getroadedge(dstroadid,ndstlr,nsecdst);
+
+//    roadedge * px1 = &mroadedge[srcedge];
+//    roadedge * px2 = &mroadedge[dstedge];
 
     if((srcedge == -1)||(dstedge == -1))
     {
@@ -1026,6 +1171,7 @@ std::vector<int> xodrdijkstra::getpath(int srcroadid, int nsrclr, int dstroadid,
     // 遍历G.vexnum-1次;每次找出一个顶点的最短路径。
     for (i = 1; i < nvertexnum; i++)
     {
+ //       qDebug("i = %d",i);
         int k,j;
         // 寻找当前最小的路径;
         // 即,在未获取最短路径的顶点中,找到离vs最近的顶点(k)。
@@ -1112,6 +1258,8 @@ std::vector<int> xodrdijkstra::getpath(int srcroadid, int nsrclr, int dstroadid,
     {
         givlog->debug("%d %d %d %d",i,mroadedge[rtnpath[rtnpath.size()-1-i]].mroadid,mroadedge[rtnpath[rtnpath.size()-1-i]].mnleftright,
                 mroadedge[rtnpath[rtnpath.size()-1-i]].mnsectionid);
+//        qDebug("%d %d %d %d",i,mroadedge[rtnpath[rtnpath.size()-1-i]].mroadid,mroadedge[rtnpath[rtnpath.size()-1-i]].mnleftright,
+//                mroadedge[rtnpath[rtnpath.size()-1-i]].mnsectionid);
         rtnpath2.push_back(rtnpath[rtnpath.size()-1-i]);
     }
 
@@ -1131,12 +1279,26 @@ int xodrdijkstra::getroadedgefromvertex(int nstart, int nend)
 {
     int i;
     int nrtn = -1;
+    double flen = -1;
+//    int nlast = -1;
     for(i=0;i<mroadedge.size();i++)
     {
         if((nstart == mroadedge[i].mvertexstart)&&(nend == mroadedge[i].mvertexend))
         {
-            nrtn = i;
-            break;
+            if(flen >0)
+            {
+                if(mroadedge[i].mlen < flen)
+                {
+                    flen = mroadedge[i].mlen;
+                    nrtn = i;
+                }
+            }
+            else
+            {
+                flen = mroadedge[i].mlen;
+                nrtn = i;
+            }
+ //           break;
         }
     }
     return nrtn;
@@ -1254,6 +1416,240 @@ std::vector<pathsection> xodrdijkstra::getgpspoint(int srcroadid, int nsrclr, in
     //First Get Every Path's lane section for calculate point.
     int i;
     int nsize = xvectorpath.size();
+
+    for(i=0;i<nsize;i++)
+    {
+         Road * pRoad = mroadedge[xvectorpath[i]].mpx;
+         qDebug("road %d is %s",i,pRoad->GetRoadId().data());
+    }
+
+    Road * pLastRoad = mroadedge[xvectorpath[nsize-1]].mpx;
+
+
+
+    for(i=0;i<nsize;i++)
+    {
+        pathsection xps;
+        Road * pRoad = mroadedge[xvectorpath[i]].mpx;
+        int nsuggest = nSel;
+        if(mroadedge[xvectorpath[i]].mnleftright == 2)nsuggest  = nsuggest *(-1);
+        int nlane = xodrfunc::GetDrivingLane(pRoad,mroadedge[xvectorpath[i]].mnsectionid,nsuggest);
+        xps.mainsel = nlane;
+        xps.mnStartLaneSel = nlane;
+        xps.mnEndLaneSel = nlane;
+        xps.mainselindex = 0;//mainselindex;
+        xps.mroadid = mroadedge[xvectorpath[i]].mroadid;
+        xps.msectionid = mroadedge[xvectorpath[i]].mnsectionid;
+        xps.mnroadedgeid = xvectorpath[i];
+        xps.mpRoad = pRoad;
+        xpathsection.push_back(xps);
+    }
+
+    for(i=(nsize-1);i>0;i--)
+    {
+        Road * pRoad = mroadedge[xvectorpath[i]].mpx;
+        LaneSection * pLS = pRoad->GetLaneSection(mroadedge[xvectorpath[i]].mnsectionid);
+        Lane * pLane = xodrfunc::GetLaneByID(pLS,xpathsection[i].mainsel);
+
+        Road * pRoad2 = mroadedge[xvectorpath[i-1]].mpx;
+        LaneSection * pLS2 = pRoad2->GetLaneSection(mroadedge[xvectorpath[i-1]].mnsectionid);
+        Lane * pLane2 = xodrfunc::GetLaneByID(pLS2,xpathsection[i-1].mainsel);
+
+        int nlr = mroadedge[xvectorpath[i]].mnleftright;
+
+        bool bNeedChangeLane = true;
+        if(nlr == 2)
+        {
+            if(pLane2->IsSuccessorSet())
+            {
+                if(pLane2->GetSuccessor() != xpathsection[i].mainsel)
+                {
+                    bool bfindgood = false;
+                    int ngoodlane = 0;
+                    int j;
+                    for(j=0;j<pLS2->GetLaneCount();j++)
+                    {
+                        if(pLS2->GetLane(j)->IsSuccessorSet())
+                        {
+                            if(pLS2->GetLane(j)->GetSuccessor() == xpathsection[i].mainsel)
+                            {
+                                ngoodlane = pLS2->GetLane(j)->GetId();
+                                bfindgood = true;
+                                break;
+                            }
+                        }
+                    }
+                    if(bfindgood)
+                    {
+                        xpathsection[i-1].mainsel = ngoodlane;
+                        xpathsection[i-1].mnStartLaneSel = ngoodlane;
+                        xpathsection[i-1].mnEndLaneSel = ngoodlane;
+                        bNeedChangeLane = false;
+                    }
+                }
+                else
+                {
+                    bNeedChangeLane = false;
+                }
+            }
+            else
+            {
+                if(pLane->IsPredecessorSet())
+                {
+                    if(pLane->GetPredecessor() != xpathsection[i-1].mainsel)
+                    {
+                        xpathsection[i-1].mainsel = pLane->GetPredecessor();
+                        xpathsection[i-1].mnStartLaneSel = pLane->GetPredecessor();
+                        xpathsection[i-1].mnEndLaneSel = pLane->GetPredecessor();
+                        bNeedChangeLane = false;
+                    }
+
+                }
+            }
+        }
+        else
+        {
+            if(pLane2->IsPredecessorSet())
+            {
+                if(pLane2->GetPredecessor() != xpathsection[i].mainsel)
+                {
+                    bool bfindgood = false;
+                    int ngoodlane = 0;
+                    int j;
+                    for(j=0;j<pLS2->GetLaneCount();j++)
+                    {
+                        if(pLS2->GetLane(j)->IsPredecessorSet())
+                        {
+                            if(pLS2->GetLane(j)->GetPredecessor() == xpathsection[i].mainsel)
+                            {
+                                ngoodlane = pLS2->GetLane(j)->GetId();
+                                bfindgood = true;
+                                break;
+                            }
+                        }
+                    }
+                    if(bfindgood)
+                    {
+                        xpathsection[i-1].mainsel = ngoodlane;
+                        xpathsection[i-1].mnStartLaneSel = ngoodlane;
+                        xpathsection[i-1].mnEndLaneSel = ngoodlane;
+                        bNeedChangeLane = false;
+                    }
+                }
+                else
+                {
+                    bNeedChangeLane = false;
+                }
+            }
+            else
+            {
+                if(pLane->IsSuccessorSet())
+                {
+                    if(pLane->GetSuccessor() != xpathsection[i-1].mainsel)
+                    {
+                        xpathsection[i-1].mainsel = pLane->GetSuccessor();
+                        xpathsection[i-1].mnStartLaneSel = pLane->GetSuccessor();
+                        xpathsection[i-1].mnEndLaneSel = pLane->GetSuccessor();
+                        bNeedChangeLane = false;
+                    }
+
+                }
+            }
+
+        }
+
+        if(bNeedChangeLane == true)
+        {
+            std::cout<<" Road "<<pRoad->GetRoadId()<<" need change lane "<<std::endl;
+            if(pRoad == pRoad2)
+            {
+                std::cout<<" Lane Change in road inter. "<<std::endl;
+            }
+            else
+            {
+                if(nlr == 2)
+                {
+                    if(pLane2->IsSuccessorSet())
+                    {
+                        xpathsection[i].secondsel = pLane2->GetSuccessor();
+                    }
+                    else
+                    {
+                        int k;
+                        int xlanecount = pLS->GetLaneCount();
+                        for(k=0;k<xlanecount;k++)
+                        {
+                            if(pLS->GetLane(k)->IsPredecessorSet())
+                            {
+                                if(pLS->GetLane(k)->GetPredecessor() == pLane2->GetSuccessor())
+                                {
+                                    xpathsection[i].secondsel = k;
+                                    break;
+                                }
+                            }
+                        }
+                    }
+                }
+                else
+                {
+                    if(pLane2->IsPredecessorSet())
+                    {
+                        xpathsection[i].secondsel = pLane2->GetPredecessor();
+                    }
+                    else
+                    {
+                        int k;
+                        int xlanecount = pLS->GetLaneCount();
+                        for(k=0;k<xlanecount;k++)
+                        {
+                            if(pLS->GetLane(k)->IsSuccessorSet())
+                            {
+                                if(pLS->GetLane(k)->GetSuccessor() == pLane2->GetPredecessor())
+                                {
+                                    xpathsection[i].secondsel = k;
+                                    break;
+                                }
+                            }
+                        }
+                    }
+
+                }
+
+            }
+
+            int k;
+            for(k=(nsize-1);k>i;k--)
+            {
+                if(xpathsection[k].mpRoad == xpathsection[i].mpRoad)
+                {
+                    xpathsection[k].secondsel = xpathsection[i].secondsel;
+                }
+            }
+
+        }
+        else
+        {
+            xpathsection[i].secondsel = xpathsection[i].mainsel;
+            xpathsection[i-1].secondsel = xpathsection[i-1].mainsel;
+        }
+
+    }
+
+    for(i=0;i<xpathsection.size();i++)
+    {
+        std::cout<<"path "<<i<<" road:"<<xpathsection[i].mroadid<<" section "<<xpathsection[i].msectionid
+                <<"  lane  "<<xpathsection[i].mainsel<<" sec lane is "<<xpathsection[i].secondsel<<std::endl;
+    }
+
+    return xpathsection;
+
+
+//    for(i=(nsize-1);i>=0;i--)
+//    {
+//        Road * pRoad = mroadedge[xvectorpathi]
+//    }
+
+
     for(i=0;i<nsize;i++)
     {
         Road * pRoad = mroadedge[xvectorpath[i]].mpx;

+ 20 - 2
src/driver/driver_map_xodrload/xodrdijkstra.h

@@ -10,6 +10,7 @@
 #include "ivfault.h"
 #include "ivlog.h"
 
+#include "xodrfunc.h"
 
 class roadedge
 {
@@ -68,6 +69,15 @@ public:
 
 
 
+
+
+};
+
+
+class vertexedge
+{
+public:
+    std::vector<roadedge *> mvectorroadedge;
 };
 
 
@@ -87,7 +97,7 @@ class pathsection
   public:
     int mroadid;
     int msectionid;
-    int mainsel;       //lane 1 -1 eq.
+    int mainsel = -1;       //lane 1 -1 eq.
     int mainselindex;   //index of lane, 无效
     bool mbStartToMainChange = false;  //Is Start  To Main have Change.
     int mnStartLaneSel;
@@ -97,6 +107,7 @@ class pathsection
     int mnMainToEndLeftRight = 0;  // 1 To Left  2 To Right 0 No Change
     int mnroadedgeid;
     Road * mpRoad;
+    int secondsel = -1; //if not change lane mainsel equal secondsel
 };
 
 class xodrdijkstra
@@ -104,10 +115,12 @@ class xodrdijkstra
 public:
     xodrdijkstra(OpenDrive  * pxodr);
 
-    std::vector<int> getpath(int srcroadid,int nsrclr,int dstroadid,int ndstlr);  //nsrclr 1 left 2 right ndstlr 1 left 2 right
+    std::vector<int> getpath(int srcroadid,int nsrclr,int dstroadid,int ndstlr,const double s_src = 0,const double s_obj = 0);  //nsrclr 1 left 2 right ndstlr 1 left 2 right
 
     std::vector<pathsection> getgpspoint(int srcroadid,int nsrclr,int dstroadid,int ndstlr,std::vector<int> xvectorpath,int nSel);
 
+    double getpathlength(std::vector<int> xvectorpath);
+
 private:
     OpenDrive * mpxodr;
 
@@ -131,6 +144,8 @@ private:
 
     Road * GetRoadByID(int nRoadID);
 
+    int GetRoadSectionIndexByS(Road * pRoad ,const double s);
+
     std::vector<lanenetunit> GetLaneNet(Road * p1,int nsec1,Road * p2,int nsec2);
 
     bool IsInLaneNet(std::vector<lanenetunit> xln,Road * p1,int nsec1,int nlane1,Road * p2,int nsec2,int nlane2);
@@ -139,6 +154,9 @@ private:
 
 
 
+    std::vector<vertexedge> mvectorvertexedge;
+
+
 //private:
 //    bool roadhaveleft( Road * px);  //A road have left lane
 //    bool roadhaveright(Road * px);  //A road have right lane

+ 2 - 0
src/fusion/fusion_pointcloud_bus/lidarmerge.cpp

@@ -46,6 +46,8 @@ pcl::PointCloud<pcl::PointXYZI>::Ptr mergefunc(std::vector<iv::lidar_data> xvect
                 if(point.x>xvectorlidar[i].fmax_x)continue;
                 if(point.y>xvectorlidar[i].fmax_y)continue;
                 if(point.z>xvectorlidar[i].fmax_z)continue;
+                if(point.z > xvectorlidar[i].fignore_zmax) continue;
+//                std::cout<<"  fignore  zmax  "<<xvectorlidar[i].fignore_zmax<<std::endl;
 
                 if(point.x<xvectorlidar[i].fmin_x)continue;
                 if(point.y<xvectorlidar[i].fmin_y)continue;

+ 1 - 0
src/fusion/fusion_pointcloud_bus/lidarmerge.h

@@ -24,6 +24,7 @@ struct lidar_data
     double fignore_ymax = 0;
     double fignore_xmin = 0;
     double fignore_ymin = 0;
+    double fignore_zmax = 0;
     pcl::PointCloud<pcl::PointXYZI>::Ptr mpoint_cloud = NULL;
     int64_t mupdatetime = 0;
     pcl::PointCloud<pcl::PointXYZI>::Ptr mpoint_cloud_old = NULL;

+ 8 - 0
src/fusion/fusion_pointcloud_bus/main.cpp

@@ -68,6 +68,7 @@ void dec_yaml(const char * stryamlpath)
     double fignore_ymax = 0;
     double fignore_xmin = 0;
     double fignore_ymin = 0;
+    double fignore_zmax = 0;
 
     if(config["ignore"]["xmin"])
     {
@@ -92,6 +93,11 @@ void dec_yaml(const char * stryamlpath)
         strtem = config["ignore"]["ymax"].as<std::string>();
         fignore_ymax = atof(strtem.data());
     }
+    if(config["ignore"]["zmax"])
+    {
+        strtem = config["ignore"]["zmax"].as<std::string>();
+        fignore_zmax = atof(strtem.data());
+    }
 
 
     for(i=0;i<nlidarsize;i++)
@@ -144,6 +150,8 @@ void dec_yaml(const char * stryamlpath)
                 xlidardata.fignore_ymax = fignore_ymax;
                 xlidardata.fignore_xmin = fignore_xmin;
                 xlidardata.fignore_ymin = fignore_ymin;
+                xlidardata.fignore_zmax = fignore_zmax;
+
 
                 strncpy(xlidardata.strmemname,strmemname.data(),255);
                 gvectorlidar.push_back(xlidardata);

+ 17 - 0
src/include/proto/ivchart.proto

@@ -0,0 +1,17 @@
+syntax = "proto2";
+
+package iv.ivchart;
+
+message ivchartunit
+{
+  required string strvarname = 1;
+  required int64 timex = 2;
+  required double fvalue = 3;
+  required double fvalue_RangeMin = 4;
+  required double fvalue_RangeMax = 5;
+};
+
+message ivchartarray
+{
+	repeated ivchartunit xivchartunit = 1;
+};

+ 73 - 0
src/test/testivchart/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 30 - 0
src/test/testivchart/main.cpp

@@ -0,0 +1,30 @@
+#include <QCoreApplication>
+
+#include <thread>
+
+#include "ivchart.h"
+
+#include <math.h>
+
+iv::Ivchart * givchart;
+bool gbrun = true;
+
+void testthread(std::string varname,int ninter,double fratio,double foff)
+{
+    int index = 0;
+    while(gbrun)
+    {
+        givchart->chartvalue(varname,foff + fratio*sin(index*2.0*M_PI/100),-1,1);
+        index = index + 1;
+        std::this_thread::sleep_for(std::chrono::milliseconds(ninter));
+    }
+}
+
+int main(int argc, char *argv[])
+{
+    QCoreApplication a(argc, argv);
+
+    givchart = new iv::Ivchart();
+    std::thread * pthread = new std::thread(testthread,"test",10,1.0,0.0);
+    return a.exec();
+}

+ 28 - 0
src/test/testivchart/testivchart.pro

@@ -0,0 +1,28 @@
+QT -= gui
+
+QT += dbus
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked 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
+
+# You can also make your code fail to compile if it uses 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 += \
+        main.cpp
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+INCLUDEPATH +=$$PWD/../../common/ivchart
+
+LIBS += -L$$PWD/../../common/build-ivchart-Debug -livchart

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

@@ -656,6 +656,7 @@ bool OpenDriveXmlParser::ReadLane (LaneSection* laneSection, TiXmlElement *node,
 	TiXmlElement *subNode=node->FirstChildElement("link");
 	TiXmlElement *subSubNode;
 	if (subNode)
+    {
 		subSubNode=subNode->FirstChildElement("predecessor");
 			if (subSubNode)
 			{
@@ -663,7 +664,9 @@ bool OpenDriveXmlParser::ReadLane (LaneSection* laneSection, TiXmlElement *node,
 				if (checker==TIXML_SUCCESS)
 					lane->SetPredecessor(predecessor);
 			}
+    }
 	if (subNode)
+    {
 		subSubNode=subNode->FirstChildElement("successor");
 			if (subSubNode)
 			{
@@ -671,6 +674,7 @@ bool OpenDriveXmlParser::ReadLane (LaneSection* laneSection, TiXmlElement *node,
 				if (checker==TIXML_SUCCESS)
 					lane->SetSuccessor(successor);
 			}
+    }
 
 	//Proceed to the Road width
 	subNode=node->FirstChildElement("width");

+ 21 - 0
src/tool/map_lanetoxodr/OpenDrive/RoadGeometry.cpp

@@ -519,6 +519,27 @@ void GeometryPoly3::SetAll(double s, double x, double y, double hdg, double leng
 	ComputeVars();
 }
 
+//GetA to GetD, Added by Yuchuli
+double GeometryPoly3::GetA()
+{
+    return mA;
+}
+
+double GeometryPoly3::GetB()
+{
+    return mB;
+}
+
+double GeometryPoly3::GetC()
+{
+    return mC;
+}
+
+double GeometryPoly3::GetD()
+{
+    return mD;
+}
+
 
 //***********************************************************************************
 //Cubic Polynom geometry. Has to be implemented.  Added By Yuchuli

+ 6 - 0
src/tool/map_lanetoxodr/OpenDrive/RoadGeometry.h

@@ -294,6 +294,12 @@ public:
 	 */
 	void SetAll(double s, double x, double y, double hdg, double length, double a,double b,double c,double d);
 
+
+    double GetA();
+    double GetB();
+    double GetC();
+    double GetD();
+
 };
 
 //----------------------------------------------------------------------------------

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

@@ -199,6 +199,7 @@ void MainWindow::ExecPainter()
             GeometryArc * parc;
             GeometryParamPoly3 * ppp3;
             GeometrySpiral *pSpiral;
+            GeometryPoly3 *ppoly;
             double rel_x,rel_y,rel_hdg;
             pg = pgeob->GetGeometryAt(0);
 
@@ -296,6 +297,49 @@ void MainWindow::ExecPainter()
                     y_draw = y_draw + mfViewMoveY;
                     painter->drawPoint(x_draw * mnfac ,y_draw * mnfac *(-1));
                 }
+                }
+                break;
+            case 3:
+                {
+
+                ppoly = (GeometryPoly3 *)pg;
+                x = pg->GetX();
+                y = pg->GetY();
+                double A,B,C,D;
+                A = ppoly->GetA();
+                B = ppoly->GetB();
+                C = ppoly->GetC();
+                D = ppoly->GetD();
+                const double steplim = 0.1;
+                double du = steplim;
+                double u = 0;
+                double v = 0;
+                double oldx,oldy;
+                oldx = x;
+                oldy = y;
+                double xstart,ystart;
+                xstart = x;
+                ystart = y;
+                double hdgstart = ppoly->GetHdg();
+                double flen = 0;
+                while(flen < ppoly->GetLength())
+                {
+                    double fdis = 0;
+                    v = A + B*u + C*u*u + D*u*u*u;
+                    x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
+                    y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
+                    fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
+                    oldx = x;
+                    oldy = y;
+                    if(fdis>(steplim*2.0))du = du/2.0;
+                    flen = flen + fdis;
+                    u = u + du;
+                    std::cout<<" x: "<<x<<" y:"<<y<<std::endl;
+                    x = x + mfViewMoveX;
+                    y = y + mfViewMoveY;
+                    painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
+                }
+
                 }
                 break;
             case 4:
@@ -359,6 +403,8 @@ void MainWindow::ExecPainter()
             GaussProjCal(lon,lat,&x,&y);
             x = x-x0;
             y= y-y0;
+            x = x + mfViewMoveX;
+            y = y + mfViewMoveY;
             painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
         }
     }

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

@@ -82,6 +82,8 @@ void MyView::zoomIn()
 
     centerOn(centerx,centery);
 
+    emit beishuchange(beishu);
+
 
 
 //    QPoint x = viewport()->rect().center();
@@ -117,6 +119,8 @@ void MyView::zoomOut()
 
 
     centerOn(centerx,centery);
+
+    emit beishuchange(beishu);
 }
 
 void MyView::zoomone()
@@ -125,6 +129,8 @@ void MyView::zoomone()
     scale(1 /beishu, 1 / beishu);
     beishu  = 1.0;
 
+    emit beishuchange(beishu);
+
 }
 
 void MyView::mouseDoubleClickEvent(QMouseEvent *event)

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

@@ -37,6 +37,7 @@ public Q_SLOTS:
 
 signals:
     void dbclickxy(double x,double y);
+    void beishuchange(double beishu);
 
 private:
     bool bottonstatus = false;
@@ -47,6 +48,8 @@ private:
     void pinchTriggered(QPinchGesture*);
 
     bool mbInPinch = false;
+
+
 };
 
 #endif // MYVIEW_H

+ 104 - 2
src/tool/map_lanetoxodr/roaddigit.cpp

@@ -22,12 +22,28 @@ void RoadDigit::UpdateSpace(double fspace)
     CalcLane();
 }
 
+int RoadDigit::GetSectionIndex(Road *pRoad, double s)
+{
+    int nrtn = 0;
+    int nsectioncount = pRoad->GetLaneSectionCount();
+    if(nsectioncount == 1)return 0;
+    int i;
+    for(i=0;i<(nsectioncount-1);i++)
+    {
+        if(pRoad->GetLaneSection(i+1)->GetS()>s)
+        {
+            break;
+        }
+    }
+    nrtn = i;
+    return nrtn;
+}
+
 void RoadDigit::CalcLine(double fspace)
 {
     unsigned int j;
     iv::RoadDigitUnit rdu;
 
-
     bool bLastGeo = false;
     for(j=0;j<mpRoad->GetGeometryBlockCount();j++)
     {
@@ -40,6 +56,7 @@ void RoadDigit::CalcLine(double fspace)
         GeometryArc * parc;
         GeometryParamPoly3 * ppp3;
         GeometrySpiral *pSpiral;
+        GeometryPoly3 *ppoly;
         double rel_x,rel_y,rel_hdg;
         pg = pgeob->GetGeometryAt(0);
         x = pg->GetX();
@@ -60,14 +77,34 @@ void RoadDigit::CalcLine(double fspace)
             rdu.mfHdg = pg->GetHdg();
             mvectorRDU.push_back(rdu);
             int ncount = pg->GetLength() /fspace;
+//            int nsec1 = GetSectionIndex(mpRoad,pg->GetS());
+//            int nsec2 = GetSectionIndex(mpRoad,pg->GetS() + pg->GetLength());
+//            if(nsec1 != nsec2)
+//            {
+//                if((nsec2-nsec1)>1)
+//                {
+//                    ncount = pg->GetLength()/0.5;
+//                }
+//                else
+//                {
+//                    LaneSection * psec1 = mpRoad->GetLaneSection(nsec1);
+//                    LaneSection * psec2 = mpRoad->GetLaneSection(nsec2);
+//                    if(psec1->GetLaneCount() != psec2->GetLaneCount())
+//                    {
+//                        ncount = pg->GetLength()/0.1;
+//                    }
+//                }
+//            }
+
             if(ncount<2)ncount = 2;
             double fstep;
             if(ncount > 0)fstep = pg->GetLength()/ncount;
             int i;
             if(bLastGeo )ncount = ncount+1;
+            double xtem,ytem;
             for(i=1;i<ncount;i++)
             {
-                double xtem,ytem;
+
                 xtem = x + (i*fstep)*cos(pg->GetHdg());
                 ytem = y + (i*fstep)*sin(pg->GetHdg());
 
@@ -78,6 +115,21 @@ void RoadDigit::CalcLine(double fspace)
                 mvectorRDU.push_back(rdu);
 
             }
+//            if(bLastGeo == false)
+//            {
+//                double fx = ncount*fstep -0.1;
+//                if((fx < pg->GetLength())&&(fx> ((ncount -1 )*fstep)))
+//                {
+//                    xtem = x + fx*cos(pg->GetHdg());
+//                    ytem = y + fx*sin(pg->GetHdg());
+
+//                    rdu.mS = pg->GetS() + fx;
+//                    rdu.mX = xtem;
+//                    rdu.mY = ytem;
+//                    rdu.mfHdg = pg->GetHdg();
+//                    mvectorRDU.push_back(rdu);
+//                }
+//            }
         }
             break;
 
@@ -192,6 +244,56 @@ void RoadDigit::CalcLine(double fspace)
 
 
 
+            }
+            }
+            break;
+        case 3:
+            {
+            ppoly = (GeometryPoly3 *)pg;
+            x = pg->GetX();
+            y = pg->GetY();
+            double A,B,C,D;
+            A = ppoly->GetA();
+            B = ppoly->GetB();
+            C = ppoly->GetC();
+            D = ppoly->GetD();
+            const double steplim = 0.3;
+            double du = steplim;
+            double u = 0;
+            double v = 0;
+            double oldx,oldy;
+            oldx = x;
+            oldy = y;
+            double xstart,ystart;
+            xstart = x;
+            ystart = y;
+            rdu.mS = pg->GetS();
+            rdu.mX = pg->GetX();
+            rdu.mY = pg->GetY();
+            rdu.mfHdg = pg->GetHdg();
+            mvectorRDU.push_back(rdu);
+            double hdgstart = ppoly->GetHdg();
+            double flen = 0;
+            u = u+du;
+            while(flen < ppoly->GetLength())
+            {
+                double fdis = 0;
+                v = A + B*u + C*u*u + D*u*u*u;
+                x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
+                y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
+                fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
+
+                if(fdis>(steplim*2.0))du = du/2.0;
+                flen = flen + fdis;
+                u = u + du;
+                rdu.mS = pg->GetS() + flen;
+                rdu.mX = x;
+                rdu.mY = y;
+                rdu.mfHdg = xodrfunc::CalcHdg(QPointF(oldx,oldy),QPointF(x,y));
+
+                mvectorRDU.push_back(rdu);
+                oldx = x;
+                oldy = y;
             }
             }
             break;

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

@@ -51,6 +51,9 @@ private:
 public:
     std::vector<iv::RoadDigitUnit> * GetRDU();
     void UpdateSpace(double fspace);
+
+private:
+    int GetSectionIndex(Road * pRoad,double s);
 };
 
 #endif // ROADDIGIT_H

+ 72 - 1
src/tool/map_lanetoxodr/xodrfunc.cpp

@@ -339,6 +339,68 @@ double xodrfunc::GetArcDis(GeometryArc * parc,double x,double y,double & nearx,
     return fdismin;
 }
 
+
+double xodrfunc::GetPoly3Dis(GeometryPoly3 * ppoly,double xnow,double ynow,double & nearx,
+                        double & neary,double & nearhead,double & frels)
+{
+    double x,y,hdg;
+//    double s = 0.0;
+    double fdismin = 100000.0;
+ //   double s0 = ppoly->GetS();
+
+    x = ppoly->GetX();
+    y = ppoly->GetY();
+    double A,B,C,D;
+    A = ppoly->GetA();
+    B = ppoly->GetB();
+    C = ppoly->GetC();
+    D = ppoly->GetD();
+    const double steplim = 0.3;
+    double du = steplim;
+    double u = 0;
+    double v = 0;
+    double oldx,oldy;
+    oldx = x;
+    oldy = y;
+    double xstart,ystart;
+    xstart = x;
+    ystart = y;
+
+    frels = 0;
+
+    double hdgstart = ppoly->GetHdg();
+    double flen = 0;
+    u = u+du;
+    while(flen < ppoly->GetLength())
+    {
+        double fdis = 0;
+        v = A + B*u + C*u*u + D*u*u*u;
+        x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
+        y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
+        fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
+
+        if(fdis>(steplim*2.0))du = du/2.0;
+        flen = flen + fdis;
+        u = u + du;
+        hdg = xodrfunc::CalcHdg(QPointF(oldx,oldy),QPointF(x,y));
+
+        double fdisnow = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
+        if(fdisnow<fdismin)
+        {
+            fdismin = fdisnow;
+            nearhead = hdg;
+            nearx = x;
+            neary = y;
+            frels = flen;
+        }
+
+        oldx = x;
+        oldy = y;
+    }
+
+    return fdismin;
+}
+
 double xodrfunc::GetSpiralDis(GeometrySpiral * pspiral,double xnow,double ynow,double & nearx,
                         double & neary,double & nearhead,double & frels)
 {
@@ -502,6 +564,11 @@ int xodrfunc::GetNearPoint(const double x, const double y, OpenDrive *pxodr, Roa
             int nlane = 1000;
             pg = pgb->GetGeometryAt(0);
 
+            if((sqrt(pow(x-pg->GetX(),2)+pow(y- pg->GetY(),2))-pg->GetLength())>nearthresh)
+            {
+                continue;
+            }
+
             switch (pg->GetGeomType()) {
             case 0:   //line
                 dis = GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh,frels);
@@ -514,7 +581,7 @@ int xodrfunc::GetNearPoint(const double x, const double y, OpenDrive *pxodr, Roa
                 break;
 
             case 3:
-                dis = 100000.0;
+                dis = GetPoly3Dis((GeometryPoly3 *)pg,x,y,nx,ny,nh,frels);
                 break;
             case 4:
                 dis = GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh,frels);
@@ -751,6 +818,8 @@ std::vector<iv::LanePoint> xodrfunc::GetAllLanePoint(Road *pRoad,  const double
                 lp.mnlanetype = nlanetype;
                 lp.mfhdg = fhdg;
                 lp.mS = s;
+                lp.mfGeoX = x;
+                lp.mfGeoY = y;
                 xvectorlanepoint.push_back(lp);
 
             }
@@ -766,6 +835,8 @@ std::vector<iv::LanePoint> xodrfunc::GetAllLanePoint(Road *pRoad,  const double
                 lp.mflanetocenter = 0;
                 lp.mfhdg = fhdg;
                 lp.mS = s;
+                lp.mfGeoX = x;
+                lp.mfGeoY = y;
                 xvectorlanepoint.push_back(lp);
             }
         }

+ 4 - 0
src/tool/map_lanetoxodr/xodrfunc.h

@@ -20,6 +20,8 @@ struct LanePoint
     int mnlanetype;  //0 driving 1 border 2 none 3 bike
     int mnlanemarktype; // -1 no 0 solid 1 broken 2 solidsolid
     int mnlanecolor;
+    double mfGeoX;
+    double mfGeoY;
 
 };
 
@@ -38,6 +40,8 @@ public:
                             double & neary,double & nearhead,double & frels);
     static double GetArcDis(GeometryArc * parc,double x,double y,double & nearx,
                             double & neary,double & nearhead,double & frels);
+    static double GetPoly3Dis(GeometryPoly3 * ppoly,double xnow,double ynow,double & nearx,
+                            double & neary,double & nearhead,double & frels);
     static double GetSpiralDis(GeometrySpiral * pspiral,double xnow,double ynow,double & nearx,
                             double & neary,double & nearhead,double & frels);
     static double GetLineDis(GeometryLine * pline,const double x,const double y,double & nearx,

+ 27 - 6
src/tool/map_lanetoxodr/xodrscenfunc.cpp

@@ -15,18 +15,33 @@ std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadLaneItem(RoadDigit *prd)
     {
         std::vector<iv::LanePoint> xvepre = pvectorrdu->at(i).mvectorLanePoint;
         std::vector<iv::LanePoint> xvenxt = pvectorrdu->at(i+1).mvectorLanePoint;
-        if((xvepre.size()<2)||(xvenxt.size()<2)||(xvenxt.size() != xvepre.size()))
+        if((xvepre.size()<2)||(xvenxt.size()<2))
         {
             continue;
         }
+
         unsigned int k;
         for(k=0;k<(xvepre.size()-1);k++)
         {
             QPainterPath xpath;
-            xpath.moveTo(xvepre.at(k).mfX,xvepre.at(k).mfY*(-1));
-            xpath.lineTo(xvenxt.at(k).mfX,xvenxt.at(k).mfY*(-1));
-            xpath.lineTo(xvenxt.at(k+1).mfX,xvenxt.at(k+1).mfY*(-1));
-            xpath.lineTo(xvepre.at(k+1).mfX,xvepre.at(k+1).mfY*(-1));
+            if((xvenxt.size() != xvepre.size()))
+            {
+                double fdis = sqrt(pow(xvenxt.at(0).mfGeoX-xvepre.at(0).mfGeoX,2)
+                                   +pow(xvenxt.at(0).mfGeoY - xvepre.at(0).mfGeoY,2));
+                double fhdg = xvepre.at(0).mfhdg;
+                xpath.moveTo(xvepre.at(k).mfX,xvepre.at(k).mfY*(-1));
+                xpath.lineTo(xvepre.at(k).mfX + fdis*cos(fhdg),(xvepre.at(k).mfY + fdis*sin(fhdg))*(-1));
+                xpath.lineTo(xvepre.at(k+1).mfX + fdis*cos(fhdg),(xvepre.at(k+1).mfY + fdis*sin(fhdg))*(-1));
+                xpath.lineTo(xvepre.at(k+1).mfX,xvepre.at(k+1).mfY*(-1));
+
+            }
+            else
+            {
+                xpath.moveTo(xvepre.at(k).mfX,xvepre.at(k).mfY*(-1));
+                xpath.lineTo(xvenxt.at(k).mfX,xvenxt.at(k).mfY*(-1));
+                xpath.lineTo(xvenxt.at(k+1).mfX,xvenxt.at(k+1).mfY*(-1));
+                xpath.lineTo(xvepre.at(k+1).mfX,xvepre.at(k+1).mfY*(-1));
+            }
             xpath.closeSubpath();
             QGraphicsPathItem * pitem = new QGraphicsPathItem;
             pitem->setPath(xpath);
@@ -35,6 +50,12 @@ std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadLaneItem(RoadDigit *prd)
             if(xvepre.at(k).mnlane<=0)nlanetype = xvepre.at(k+1).mnlanetype;
             QColor brushcolor = Qt::darkGray;
             switch (nlanetype) {
+            case 0:
+                brushcolor = QColor(0x66,0xBF,0x00);
+                break;
+            case 1:
+                brushcolor = Qt::darkGreen;
+                break;
             case 2:
                 brushcolor = Qt::darkGray;
                 break;
@@ -45,7 +66,7 @@ std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadLaneItem(RoadDigit *prd)
                 brushcolor = QColor(0xB2,0xB2,0xD6);
                 break;
             default:
-                brushcolor = Qt::darkGreen;
+                brushcolor = Qt::yellow;//Qt::darkGreen;
                 break;
             }
             pitem->setBrush(brushcolor);

+ 79 - 13
src/tool/map_lanetoxodr/xvmainwindow.cpp

@@ -10,8 +10,8 @@
 #include "roaddigit.h"
 #include "xodrscenfunc.h"
 
-#define VIEW_WIDTH 2000
-#define VIEW_HEIGHT 2000
+#define VIEW_WIDTH 5000
+#define VIEW_HEIGHT 5000
 
 static bool IsNaN(double dat)
 {
@@ -31,7 +31,7 @@ XVMainWindow::XVMainWindow(QWidget *parent) :
     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);
 
@@ -39,6 +39,8 @@ XVMainWindow::XVMainWindow(QWidget *parent) :
     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()));
 
@@ -55,6 +57,8 @@ 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);
 }
 
@@ -106,6 +110,11 @@ void XVMainWindow::LoadXODR(QString strpath)
     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);
@@ -119,9 +128,37 @@ void XVMainWindow::LoadXODR(QString strpath)
         else
         {
             froadlen = froadlen + pRoad->GetRoadLength();
+
+            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);
@@ -154,7 +191,8 @@ void XVMainWindow::UpdateScene()
         for(j=0;j<ncount;j++)
         {
             QGraphicsPathItem * pitem = xvectorlanepath[j];
-            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+//            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            pitem->setPos(mfViewMoveX,-mfViewMoveY);
             mpscene->addItem(pitem);
             mvectorviewitem.push_back(pitem);
         }
@@ -168,7 +206,8 @@ void XVMainWindow::UpdateScene()
         for(j=0;j<ncount;j++)
         {
             QGraphicsPathItem * pitem = xvectormarkpath[j];
-            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+ //           pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            pitem->setPos(mfViewMoveX,-mfViewMoveY);
             mpscene->addItem(pitem);
             mvectorviewitem.push_back(pitem);
         }
@@ -195,19 +234,39 @@ void XVMainWindow::onClickXY(double x, double y)
 {
     double selx,sely;
     double lon,lat;
-    selx = (x - VIEW_WIDTH/2);
-    sely = (y - VIEW_HEIGHT/2) * (-1);
 
-    mfselx = selx;
-    mfsely = sely;
+
+//    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;
-    rel_y = sely - mfViewMoveY;
+
+    rel_x = selx - mfViewMoveX + VIEW_WIDTH/2 ;
+    rel_y = sely - mfViewMoveY - VIEW_HEIGHT/2;
+
 
     Road * pRoad = 0;
     GeometryBlock * pgeob;
@@ -258,7 +317,8 @@ void XVMainWindow::on_actionSet_Move_triggered()
     }
     for(i=0;i<nsize;i++)
     {
-        mvectorviewitem.at(i)->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+//        mvectorviewitem.at(i)->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+        mvectorviewitem.at(i)->setPos(mfViewMoveX ,-mfViewMoveY);
         mpscene->addItem(mvectorviewitem.at(i));
     }
 
@@ -280,7 +340,8 @@ void XVMainWindow::on_actionReset_Move_triggered()
 
     for(i=0;i<nsize;i++)
     {
-        mvectorviewitem.at(i)->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+        mvectorviewitem.at(i)->setPos(mfViewMoveX ,-mfViewMoveY);
+ //       mvectorviewitem.at(i)->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
         mpscene->addItem(mvectorviewitem.at(i));
     }
 
@@ -313,3 +374,8 @@ void XVMainWindow::on_actionHelp_triggered()
                           "在屏幕上可以移动查看区域");
     QMessageBox::information(this,"Help",helpinfo,QMessageBox::Yes);
 }
+
+void XVMainWindow::onbeishuchange(double fbeishu)
+{
+    mfbeishu = fbeishu;
+}

+ 7 - 0
src/tool/map_lanetoxodr/xvmainwindow.h

@@ -40,6 +40,8 @@ private slots:
 
     void onClickXY(double x, double y);
 
+    void onbeishuchange(double fbeishu);
+
     void on_actionSet_Move_triggered();
 
     void on_actionReset_Move_triggered();
@@ -76,6 +78,11 @@ private:
     bool mbRefresh = false;
 
     FileDialogExtern mFileDialog;
+
+    double mfbeishu = 1.0;
+
+    double mfViewWidth;
+    double mfViewHeight;
 };
 
 #endif // XVMAINWINDOW_H

+ 3 - 0
src/tool/map_lanetoxodr_graphscene/mainwindow.cpp

@@ -290,6 +290,9 @@ void MainWindow::ExecPainter()
                 }
                 }
                 break;
+            case 3:
+                qDebug("poly3");
+                break;
             case 4:
                 {
                 ppp3 = (GeometryParamPoly3 * )pg;

+ 0 - 565
src/tool/tool_xodrobj/OpenDrive/Junction.cpp

@@ -1,565 +0,0 @@
-#include "Junction.h"
-
-/**
-* Junction class. Holds all the junction information
-*
-*
-*
-*
-*/
-
-/**
-* Constructor. Sets basic junction parameters
-* @param name Name of the junction
-* @param id Unique ID of the junction
-*/
-Junction::Junction(	string name, string id)
-{
-	mName=name;
-	mId=id;
-}
-
-/**
-* Sets the name parameter
-*/
-void Junction::SetName(string name)
-{	mName=name;	}
-
-/**
-* Sets the ID parameter
-*/
-void Junction::SetId(string id)
-{	mId=id;	}
-
-
-/**
-* Adds a junction connection to the junction
-* @param id ID within the junction
-* @param incomingRoad ID of the incoming road
-* @param connectingRoad ID of the connecting path
-* @param contactPoint Contact point on the connecting road (start or end)
-*/
-unsigned int Junction::AddJunctionConnection(	string id,	string incomingRoad, string connectingRoad, string contactPoint)
-{	
-	// Adds a new junction connection
-	mJunctionConnectionVector.push_back(JunctionConnection(id, incomingRoad, connectingRoad, contactPoint));	
-	// Saves the index of the newly added junction connection
-	mLastAddedJunctionConnection = mJunctionConnectionVector.size()-1;
-	return mLastAddedJunctionConnection;
-}
-
-
-/**
-* Adds a priority parameter to the junction
-* @param high ID of the connecting road with higher priority
-* @param low ID of the connecting road with lower priority
-*/
-unsigned int Junction::AddJunctionPriority ( string high, string low)
-{	
-	// Check the first method in the group for details
-
-	mJunctionPriorityVector.push_back(JunctionPriorityRoad(high,low));	
-	mLastAddedJunctionPriority = mJunctionPriorityVector.size()-1;
-	return mLastAddedJunctionPriority;
-}
-
-/**
-* Adds a controller to the junction
-* @param id ID of the controller to add
-* @param type Type of control
-*/
-unsigned int Junction::AddJunctionController ( string id, string type)
-{	
-	mJunctionControllerVector.push_back(JunctionController(id,type));	
-	mLastAddedJunctionController = mJunctionControllerVector.size()-1;
-	return mLastAddedJunctionController;
-}
-//--------------
-
-/**
- * Methods used to clone child records in the respective vectors
- */
-unsigned int Junction::CloneJunctionConnection(unsigned int index)
-{
-	// Clone the object and insert it in the middle of the vector
-	if(index<mJunctionConnectionVector.size()-1)
-		mJunctionConnectionVector.insert(mJunctionConnectionVector.begin()+index+1, mJunctionConnectionVector[index]);
-	// or just push it to the back
-	else if(index==mJunctionConnectionVector.size()-1)
-		mJunctionConnectionVector.push_back(mJunctionConnectionVector[index]);
-	// Save the last added record index
-	mLastAddedJunctionConnection=index+1;
-	return mLastAddedJunctionConnection;
-}
-unsigned int Junction::CloneJunctionPriority(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mJunctionPriorityVector.size()-1)
-		mJunctionPriorityVector.insert(mJunctionPriorityVector.begin()+index+1, mJunctionPriorityVector[index]);
-	else if(index==mJunctionPriorityVector.size()-1)
-		mJunctionPriorityVector.push_back(mJunctionPriorityVector[index]);
-	mLastAddedJunctionPriority=index+1;
-	return mLastAddedJunctionPriority;
-}
-unsigned int Junction::CloneJunctionController(unsigned int index)
-{
-	if(index<mJunctionControllerVector.size()-1)
-		mJunctionControllerVector.insert(mJunctionControllerVector.begin()+index+1, mJunctionControllerVector[index]);
-	else if(index==mJunctionControllerVector.size()-1)
-		mJunctionControllerVector.push_back(mJunctionControllerVector[index]);
-	mLastAddedJunctionController=index+1;
-	return mLastAddedJunctionController;
-}
-
-/**
- * Methods used to delete child records from the respective vectors
- */
-void Junction::DeleteJunctionConnection(unsigned int index)
-{
-	mJunctionConnectionVector.erase(mJunctionConnectionVector.begin()+index);
-}
-void Junction::DeleteJunctionPriority(unsigned int index)
-{
-	mJunctionPriorityVector.erase(mJunctionPriorityVector.begin()+index);
-}
-void Junction::DeleteJunctionController(unsigned int index)
-{
-	mJunctionControllerVector.erase(mJunctionControllerVector.begin()+index);
-}
-
-/**
-* Return the name of the junction
-*/
-string Junction::GetName()
-{	return mName;	}
-
-/**
-* Return the id of the junction
-*/
-string Junction::GetId()
-{	return mId;	}
-
-/**
-* Return the vector that stores junction connections
-* @return A pointer to std::vector of JunctionConnection type that stores junction connections
-*/
-std::vector<JunctionConnection>* Junction::GetJunctionConnectionVector ()
-{	return &mJunctionConnectionVector;	}
-
-/**
-* Return the number of junction connections
-* @return An unsigned int that stores the number of junction connections
-*/
-unsigned int Junction::GetJunctionConnectionCount()
-{	return mJunctionConnectionVector.size();	}
-
-/**
-* Return the pointer to a junction connection at provided index
-* @param i Index to the junction connection that is returned
-* @return A pointer to JunctionConnection object
-*/
-JunctionConnection* Junction::GetJunctionConnection(unsigned int i)
-{	return &mJunctionConnectionVector.at(i);	}
-
-/**
-* Return the pointer to the last junction connection
-* @return A pointer to JunctionConnection object
-*/
-JunctionConnection* Junction::GetLastJunctionConnection()
-{	
-	if(mJunctionConnectionVector.size()>0)
-		return &mJunctionConnectionVector.at(mJunctionConnectionVector.size()-1);	
-	else
-		return NULL;
-}
-/**
-* Return the pointer to the last added junction connection (which might not be the one from the end of the vector)
-* @return A pointer to JunctionConnection object
-*/
-JunctionConnection* Junction::GetLastAddedJunctionConnection()
-{	
-	if(mLastAddedJunctionConnection<mJunctionConnectionVector.size())
-		return &mJunctionConnectionVector.at(mLastAddedJunctionConnection);
-	else
-		return NULL;
-}
-
-/**
-* Return the vector that stores junction priority records
-* @return A pointer to std::vector of JunctionPriorityRoad type that stores junction priority records
-*/
-std::vector<JunctionPriorityRoad>* Junction::GetJunctionPriorityVector()
-{	return &mJunctionPriorityVector;	}
-
-/**
-* Return the number of junction priority records
-* @return An unsigned int that stores the number of junction priority records
-*/
-unsigned int Junction::GetJunctionPriorityCount()
-{	return mJunctionPriorityVector.size();	}
-
-/**
-* Return the pointer to a junction priority record at provided index
-* @param i Index to the junction priority record that is returned
-* @return A pointer to JunctionPriorityRoad object
-*/
-JunctionPriorityRoad* Junction::GetJunctionPriority(unsigned int i)
-{	return &mJunctionPriorityVector.at(i);	}
-
-/**
-* Return the pointer to the last junction priority record
-* @return A pointer to JunctionPriorityRoad object
-*/
-JunctionPriorityRoad* Junction::GetLastJunctionPriority()
-{	
-	if(mJunctionPriorityVector.size()>0)
-		return &mJunctionPriorityVector.at(mJunctionPriorityVector.size()-1);	
-	else 
-		return NULL;
-}
-
-/**
-* Return the pointer to the last added junction priority record (which might not be the one from the end of the vector)
-* @return A pointer to JunctionPriorityRoad object
-*/
-JunctionPriorityRoad* Junction::GetLastAddedJunctionPriority()
-{	
-	if(mLastAddedJunctionPriority<mJunctionPriorityVector.size())
-		return &mJunctionPriorityVector.at(mLastAddedJunctionPriority);
-	else
-		return NULL;
-}
-
-
-/**
-* Return the vector that stores junction controller records
-* @return A pointer to std::vector of JunctionController type that stores junction controller records
-*/
-std::vector<JunctionController>* Junction::GetJunctionControllerVector()
-{	return &mJunctionControllerVector;	}
-
-/**
-* Return the number of junction controller records
-* @return An unsigned int that stores the number of junction controller records
-*/
-unsigned int  Junction::GetJunctionControllerCount()
-{	return mJunctionControllerVector.size();	}
-
-/**
-* Return the pointer to a junction controller record at provided index
-* @param i Index to the junction controller record that is returned
-* @return A pointer to JunctionController object
-*/
-JunctionController* Junction::GetJunctionController(unsigned int i)
-{	return &mJunctionControllerVector.at(i);	}
-
-/**
-* Return the pointer to the last junction controller record
-* @return A pointer to JunctionController object
-*/
-JunctionController* Junction::GetLastJunctionController()
-{	
-	if(mJunctionControllerVector.size()>0)
-		return &mJunctionControllerVector.at(mJunctionControllerVector.size()-1);	
-	else
-		return NULL;
-}
-
-/**
-* Return the pointer to the last added junction controller record (which might not be the one from the end of the vector)
-* @return A pointer to JunctionController object
-*/
-JunctionController* Junction::GetLastAddedJunctionController()
-{	
-	if(mLastAddedJunctionController<mJunctionControllerVector.size())
-		return &mJunctionControllerVector.at(mLastAddedJunctionController);
-	else
-		return NULL;
-}
-//--------------
-
-
-/**
-* Junction connection class. Holds all the information for a connection record
-*
-*
-*
-*
-*/
-
-/**
-* Constructor. Sets basic junction connection parameters
-* @param id ID within the junction
-* @param incomingRoad ID of the incoming road
-* @param connectingRoad ID of the connecting path
-* @param contactPoint Contact point on the connecting road (start / end)
-*/
-JunctionConnection::JunctionConnection(	string id, string incomingRoad, string connectingRoad, string contactPoint	)
-{
-	mId=id;
-	mIncomingRoad=incomingRoad;
-	mConnectingRoad=connectingRoad;
-	mContactPoint=contactPoint;	
-}
-
-/**
-* Set the ID parameter
-*/
-void JunctionConnection::SetId(string id)
-{	mId=id;	}
-
-/**
-* Set the ID of the incoming road 
-*/
-void JunctionConnection::SetIncomingRoad(string incomingRoad)
-{	mIncomingRoad=incomingRoad;	}
-
-/**
-* Set the ID of the connecting path
-*/
-void JunctionConnection::SetConnectingRoad(string connectingRoad)
-{	mConnectingRoad=connectingRoad;	}
-
-/**
-* Set the contact point parameter
-* @param contactPoint Contact point of the connecting road. Can be either start or end
-*/
-void JunctionConnection::SetContactPoint(string contactPoint)
-{	mContactPoint=contactPoint;	}
-
-/**
-* Add a lane link record
-* @param from ID of the incoming lane
-* @param to ID of the connecting lane
-*/
-unsigned int JunctionConnection::AddJunctionLaneLink(int from, int to)
-{	
-	mJunctionLaneLinkVector.push_back(JunctionLaneLink(from, to));	
-	mLastAddedJunctionLaneLink = mJunctionLaneLinkVector.size()-1;
-	return mLastAddedJunctionLaneLink;
-}
-//--------------
-
-/**
- * Method used to clone child record in the respective vectors
- */
-unsigned int JunctionConnection::CloneJunctionLaneLink(unsigned int index)
-{
-	// Clone the object and insert it in the middle of the vector
-	if(index<mJunctionLaneLinkVector.size()-1)
-		mJunctionLaneLinkVector.insert(mJunctionLaneLinkVector.begin()+index+1, mJunctionLaneLinkVector[index]);
-	// or just push it to the back
-	else if(index==mJunctionLaneLinkVector.size()-1)
-		mJunctionLaneLinkVector.push_back(mJunctionLaneLinkVector[index]);
-	// Save the last added record index
-	mLastAddedJunctionLaneLink=index+1;
-	return mLastAddedJunctionLaneLink;
-}
-
-/**
-* Delete the lane link parameter at the provided index
-*/
-void JunctionConnection::DeleteJunctionLaneLink(unsigned int index)
-{
-	mJunctionLaneLinkVector.erase(mJunctionLaneLinkVector.begin()+index);
-}
-
-
-/**
-* Get the ID parameter
-*/
-string JunctionConnection::GetId()
-{	return mId;	}
-
-/**
-* Get the ID fo the incoming road
-*/
-string JunctionConnection::GetIncomingRoad()
-{	return mIncomingRoad;	}
-
-/**
-* Get the ID of the connecting road
-*/
-string JunctionConnection::GetConnectingRoad()
-{	return mConnectingRoad;	}
-
-/**
-* Get the contact point parameter
-*/
-string JunctionConnection::GetContactPoint()
-{	return mContactPoint;	}
-
-/**
-* Return the vector that stores junction lane link records
-* @return A pointer to std::vector of JunctionLaneLink type that stores junction lane link records
-*/
-std::vector<JunctionLaneLink>* JunctionConnection::GetJunctionLaneLinkVector()
-{	return &mJunctionLaneLinkVector;	}
-
-/**
-* Return the number of junction lane link records
-* @return An unsigned int that stores the number of junction lane link records
-*/
-unsigned int JunctionConnection::GetJunctionLaneLinkCount()
-{	return mJunctionLaneLinkVector.size();	}
-
-/**
-* Return the pointer to a junction lane link record at provided index
-* @param i Index to the junction lane link record that is returned
-* @return A pointer to JunctionLaneLink object
-*/
-JunctionLaneLink* JunctionConnection::GetJunctionLaneLink(unsigned int i)
-{	return &mJunctionLaneLinkVector.at(i);	}
-
-/**
-* Return the pointer to the last junction lane link record
-* @return A pointer to JunctionLaneLink object
-*/
-JunctionLaneLink* JunctionConnection::GetLastJunctionLaneLink()
-{	
-	if(mJunctionLaneLinkVector.size()>0)
-		return &mJunctionLaneLinkVector.at(mJunctionLaneLinkVector.size()-1);	
-	else
-		return NULL;
-}
-
-/**
-* Return the pointer to the last added junction lane link record (which might not be the one from the end of the vector)
-* @return A pointer to JunctionLaneLink object
-*/
-JunctionLaneLink* JunctionConnection::GetLastAddedJunctionLaneLink()
-{	
-	if(mLastAddedJunctionLaneLink<mJunctionLaneLinkVector.size())
-		return &mJunctionLaneLinkVector.at(mLastAddedJunctionLaneLink);
-	else
-		return NULL;
-}
-
-
-
-/**
-* Junction lane link class. Holds all the information for a lane link record
-*
-*
-*
-*
-*/
-
-/**
-* Constructor. Initializes the parameters
-* @param from ID of the incoming lane
-* @param to ID of the connecting lane
-*/
-JunctionLaneLink::JunctionLaneLink(int from, int to)
-{	mFrom=from; mTo=to;	}
-
-
-/**
-* Set the ID of the incoming lane
-*/
-void JunctionLaneLink::SetFrom (int from)
-{	mFrom=from;	}
-
-/**
-* Set the ID of the connecting lane
-*/
-void JunctionLaneLink::SetTo (int to)
-{	mTo=to;	}
-
-/**
-* Get the ID of the incoming lane
-*/
-int JunctionLaneLink::GetFrom()
-{	return mFrom;	}
-
-/**
-* Get the ID of the connecting lane
-*/
-int JunctionLaneLink::GetTo()
-{	return mTo;	}
-
-
-/**
-* Junction priority class. Holds all the information for a priority record
-*
-*
-*
-*
-*/
-
-/**
-* Constructor. Initializes the parameters
-* @param high ID of the connecting road with higher priority
-* @param low ID of the connecting road with lower priority
-*/
-JunctionPriorityRoad::JunctionPriorityRoad(string high, string low)
-{
-	mHigh=high;
-	mLow=low;
-}
-
-/**
-* Set the ID of the connecting road with higher priority
-*/
-void JunctionPriorityRoad::SetHigh (string high)
-{	mHigh=high;	}
-
-/**
-* Set the ID of the connecting road with lower priority
-*/
-void JunctionPriorityRoad::SetLow (string low)
-{	mLow=low;	}
-
-/**
-* Get the ID of the connecting road with higher priority
-*/
-string JunctionPriorityRoad::GetHigh()
-{	return mHigh;	}
-
-/**
-* Get the ID of the connecting road with lower priority
-*/
-string JunctionPriorityRoad::GetLow()
-{	return mLow;	}
-
-
-/**
-* Junction controller class. Holds all the information for a priority record
-*
-*
-*
-*
-*/
-
-/**
-* Constructor. Initializes the parameters
-* @param id ID of the controller to add
-* @param type Type of control
-*/
-JunctionController::JunctionController(string id, string type)
-{	mId=id; mType=type;	}
-
-/**
-* Set the ID of the controller to add
-*/
-void JunctionController::SetId (string id)
-{	mId=id;	}
-
-/**
-* Set the type of control
-*/
-void JunctionController::SetType (string type)
-{	mType=type;	}
-
-/**
-* Get the ID of the controller to add
-*/
-string JunctionController::GetId()
-{	return mId;	}
-
-/**
-* Get the type of control
-*/
-string JunctionController::GetType()
-{	return mType;	}

+ 0 - 470
src/tool/tool_xodrobj/OpenDrive/Junction.h

@@ -1,470 +0,0 @@
-#ifndef JUNCTION_H
-#define JUNCTION_H
-
-#include <string>
-#include <vector>
-using std::string;
-
-//Prototypes
-class Junction;
-class JunctionConnection;
-class JunctionLaneLink;
-class JunctionController;
-class JunctionPriorityRoad;
-
-/**
- * Junction class. Holds all the junction information
- *
- *
- *
- *
- */
-class Junction
-{
-private:
-	/**
-	 * Junction parameters
-	 */
-	std::string mName;
-	std::string mId;
-
-	/**
-	 * Vector based parameters of the junction
-	 */
-	std::vector<JunctionConnection> mJunctionConnectionVector;
-	std::vector<JunctionPriorityRoad> mJunctionPriorityVector;
-	std::vector<JunctionController> mJunctionControllerVector;
-
-public:
-
-	/**
-	 * Indices of the last added records
-	 */
-	unsigned int mLastAddedJunctionConnection;
-	unsigned int mLastAddedJunctionPriority;
-	unsigned int mLastAddedJunctionController;
-
-	/**
-	 * Constructor. Sets basic junction parameters
-	 * @param name Name of the junction
-	 * @param id Unique ID of the junction
-	 */
-	Junction(string name, string id);
-
-	/**
-	 * Sets the name parameter
-	 */
-	void SetName(string name);
-	/**
-	 * Sets the ID parameter
-	 */
-	void SetId(string id);
-
-	/**
-	 * Adds a junction connection to the junction
-	 * @param id ID within the junction
-	 * @param incomingRoad ID of the incoming road
-	 * @param connectingRoad ID of the connecting path
-	 * @param contactPoint Contact point on the connecting road (start or end)
-	 */
-	unsigned int AddJunctionConnection(string id,	string incomingRoad, string connectingRoad, string contactPoint);
-
-	/**
-	 * Adds a priority parameter to the junction
-	 * @param high ID of the connecting road with higher priority
-	 * @param low ID of the connecting road with lower priority
-	 */
-	unsigned int AddJunctionPriority(string high, string low);
-
-	/**
-	 * Adds a controller to the junction
-	 * @param id ID of the controller to add
-	 * @param type Type of control
-	 */
-	unsigned int AddJunctionController(string id, string type);
-
-	/**
-	 * Clone the connection record
-	 * @param index Index of the record to clone
-	 */
-	unsigned int CloneJunctionConnection(unsigned int index);
-	unsigned int CloneJunctionPriority(unsigned int index);
-	unsigned int CloneJunctionController(unsigned int index);
-
-
-	void DeleteJunctionConnection(unsigned int index);
-	void DeleteJunctionPriority(unsigned int index);
-	void DeleteJunctionController(unsigned int index);
-
-	/**
-	 * Return the name of the junction
-	 */
-	string GetName();
-
-	/**
-	 * Return the id of the junction
-	 */
-	string GetId();
-
-	/**
-	 * Return the vector that stores junction connections
-	 * @return A pointer to std::vector of JunctionConnection type that stores junction connections
-	 */
-	std::vector<JunctionConnection>* GetJunctionConnectionVector ();
-
-	/**
-	 * Return the number of junction connections
-	 * @return An unsigned int that stores the number of junction connections
-	 */
-	unsigned int GetJunctionConnectionCount();
-
-	/**
-	 * Return the pointer to a junction connection at provided index
-	 * @param i Index to the junction connection that is returned
-	 * @return A pointer to JunctionConnection object
-	 */
-	JunctionConnection* GetJunctionConnection(unsigned int i);
-
-	/**
-	 * Return the pointer to the last junction connection
-	 * @return A pointer to JunctionConnection object
-	 */
-    JunctionConnection* GetLastJunctionConnection();
-
-	/**
-	 * Return the pointer to the last added junction connection (which might not be the one from the end of the vector)
-	 * @return A pointer to JunctionConnection object
-	 */
-    JunctionConnection* GetLastAddedJunctionConnection();
-	
-	/**
-	 * Return the vector that stores junction priority records
-	 * @return A pointer to std::vector of JunctionPriorityRoad type that stores junction priority records
-	 */
-	std::vector<JunctionPriorityRoad>* GetJunctionPriorityVector();
-
-	/**
-	 * Return the number of junction priority records
-	 * @return An unsigned int that stores the number of junction priority records
-	 */
-	unsigned int GetJunctionPriorityCount();
-
-	/**
-	 * Return the pointer to a junction priority record at provided index
-	 * @param i Index to the junction priority record that is returned
-	 * @return A pointer to JunctionPriorityRoad object
-	 */
-	JunctionPriorityRoad* GetJunctionPriority(unsigned int i);
-
-	/**
-	 * Return the pointer to the last junction priority record
-	 * @return A pointer to JunctionPriorityRoad object
-	 */
-    JunctionPriorityRoad* GetLastJunctionPriority();
-
-	
-	/**
-	 * Return the pointer to the last added junction priority record (which might not be the one from the end of the vector)
-	 * @return A pointer to JunctionPriorityRoad object
-	 */
-    JunctionPriorityRoad* GetLastAddedJunctionPriority();
-
-	/**
-	 * Return the vector that stores junction controller records
-	 * @return A pointer to std::vector of JunctionController type that stores junction controller records
-	 */
-	std::vector<JunctionController>* GetJunctionControllerVector();
-
-	/**
-	 * Return the number of junction controller records
-	 * @return An unsigned int that stores the number of junction controller records
-	 */
-	unsigned int  GetJunctionControllerCount();
-
-	/**
-	 * Return the pointer to a junction controller record at provided index
-	 * @param i Index to the junction controller record that is returned
-	 * @return A pointer to JunctionController object
-	 */
-	JunctionController* GetJunctionController(unsigned int i);
-
-	/**
-	 * Return the pointer to the last junction controller record
-	 * @return A pointer to JunctionController object
-	 */
-    JunctionController* GetLastJunctionController();
-
-	/**
-	 * Return the pointer to the last added junction controller record (which might not be the one from the end of the vector)
-	 * @return A pointer to JunctionController object
-	 */
-    JunctionController* GetLastAddedJunctionController();
-
-};
-
-
-/**
- * Junction connection class. Holds all the information for a connection record
- *
- *
- *
- *
- */
-class JunctionConnection
-{
-private:
-	/**
-	 * Connection parameters
-	 */
-	string mId;
-	string mIncomingRoad;
-	string mConnectingRoad;
-	string mContactPoint;	//Possible values: start / end
-
-	/**
-	 * Lane linkage parameters vector
-	 */
-	std::vector<JunctionLaneLink> mJunctionLaneLinkVector;
-public:
-	
-	unsigned int mLastAddedJunctionLaneLink;
-
-	/**
-	 * Constructor. Sets basic junction connection parameters
-	 * @param id ID within the junction
-	 * @param incomingRoad ID of the incoming road
-	 * @param connectingRoad ID of the connecting path
-	 * @param contactPoint Contact point on the connecting road (start / end)
-	 */
-	JunctionConnection(	string id, string incomingRoad, string connectingRoad, string contactPoint);
-
-	/**
-	 * Set the ID parameter
-	 */
-	void SetId(string id);
-
-	/**
-	 * Set the ID of the incoming road 
-	 */
-	void SetIncomingRoad(string incomingRoad);
-
-	/**
-	 * Set the ID of the connecting path
-	 */
-	void SetConnectingRoad(string connectingRoad);
-
-	/**
-	 * Set the contact point parameter
-	 * @param contactPoint Contact point of the connecting road. Can be either start or end
-	 */
-	void SetContactPoint(string contactPoint);
-
-	/**
-	 * Add a lane link record
-	 * @param from ID of the incoming lane
-	 * @param to ID of the connecting lane
-	 */
-	unsigned int AddJunctionLaneLink(int from, int to);
-
-	//clone elements
-	unsigned int CloneJunctionLaneLink(unsigned int index);
-
-	/**
-	 * Delete the lane link parameter at the provided index
-	 */
-	void DeleteJunctionLaneLink(unsigned int index);
-
-	/**
-	 * Get the ID parameter
-	 */
-	string GetId();
-
-	/**
-	 * Get the ID fo the incoming road
-	 */
-	string GetIncomingRoad();
-	
-	/**
-	 * Get the ID of the connecting road
-	 */
-	string GetConnectingRoad();
-	
-	/**
-	 * Get the contact point parameter
-	 */
-	string GetContactPoint();
-
-	/**
-	 * Return the vector that stores junction lane link records
-	 * @return A pointer to std::vector of JunctionLaneLink type that stores junction lane link records
-	 */
-	std::vector<JunctionLaneLink>* GetJunctionLaneLinkVector();
-	
-	/**
-	 * Return the number of junction lane link records
-	 * @return An unsigned int that stores the number of junction lane link records
-	 */
-	unsigned int GetJunctionLaneLinkCount();
-
-	/**
-	 * Return the pointer to a junction lane link record at provided index
-	 * @param i Index to the junction lane link record that is returned
-	 * @return A pointer to JunctionLaneLink object
-	 */
-	JunctionLaneLink* GetJunctionLaneLink(unsigned int);
-
-	/**
-	 * Return the pointer to the last junction lane link record
-	 * @return A pointer to JunctionLaneLink object
-	 */
-	JunctionLaneLink* GetLastJunctionLaneLink();
-
-	/**
-	 * Return the pointer to the last added junction lane link record (which might not be the one from the end of the vector)
-	 * @return A pointer to JunctionLaneLink object
-	 */
-	JunctionLaneLink* GetLastAddedJunctionLaneLink();
-
-
-};
-
-/**
- * Junction lane link class. Holds all the information for a lane link record
- *
- *
- *
- *
- */
-class JunctionLaneLink
-{
-private:
-	/**
-	 * Record parameters
-	 */
-	int mFrom;
-	int mTo;
-
-public:
-	/**
-	 * Constructor. Initializes the parameters
-	 * @param from ID of the incoming lane
-	 * @param to ID of the connecting lane
-	 */
-	JunctionLaneLink(int from, int to);
-
-	/**
-	 * Set the ID of the incoming lane
-	 */
-	void SetFrom (int from);
-
-	/**
-	 * Set the ID of the connecting lane
-	 */
-	void SetTo (int to);
-
-	/**
-	 * Get the ID of the incoming lane
-	 */
-	int GetFrom();
-
-	/**
-	 * Get the ID of the connecting lane
-	 */
-	int GetTo();
-};
-
-
-/**
- * Junction priority class. Holds all the information for a priority record
- *
- *
- *
- *
- */
-class JunctionPriorityRoad
-{
-private:
-	/**
-	 * Record parameters
-	 */
-	string mHigh;
-	string mLow;
-public:
-
-	/**
-	 * Constructor. Initializes the parameters
-	 * @param high ID of the connecting road with higher priority
-	 * @param low ID of the connecting road with lower priority
-	 */
-	JunctionPriorityRoad(string high, string low);
-
-	/**
-	 * Set the ID of the connecting road with higher priority
-	 */
-	void SetHigh (string high);
-
-	/**
-	 * Set the ID of the connecting road with lower priority
-	 */
-	void SetLow (string low);
-
-	/**
-	 * Get the ID of the connecting road with higher priority
-	 */
-	string GetHigh();
-
-	/**
-	 * Get the ID of the connecting road with lower priority
-	 */
-	string GetLow();
-
-};
-
-
-
-/**
- * Junction controller class. Holds all the information for a priority record
- *
- *
- *
- *
- */
-class JunctionController
-{
-private:
-	/**
-	 * Record parameters
-	 */
-	string mId;
-	string mType;
-public:
-	/**
-	 * Constructor. Initializes the parameters
-	 * @param id ID of the controller to add
-	 * @param type Type of control
-	 */
-	JunctionController(string id, string type);
-
-	/**
-	 * Set the ID of the controller to add
-	 */
-	void SetId (string id);
-
-	/**
-	 * Set the type of control
-	 */
-	void SetType (string type);
-
-	/**
-	 * Get the ID of the controller to add
-	 */
-	string GetId();
-
-	/**
-	 * Get the type of control
-	 */
-	string GetType();
-
-};
-
-#endif

+ 0 - 1509
src/tool/tool_xodrobj/OpenDrive/Lane.cpp

@@ -1,1509 +0,0 @@
-#include "Lane.h"
-
-
-
-
-/**
-* Lane section class. Holds all the lane section information
-*
-*
-*
-*
-*/
-
-/**
-* Constructor. Sets basic lane section parameters
-* @param s s-offset of the lane section
-*/
-LaneSection::LaneSection (double s)
-{	mS=s;	}
-
-/**
-* Add a lane to the lane section
-* @param side the side of the road to which the lane will be added
-* @param id ID of the lane
-* @param type Type of the lane (Section 6.5 of the OpenDRIVE specification) 
-* @param level Level parameter of the road
-* @param sort Defines if the lanes should be sorted when added. True by default
-*/
-unsigned int LaneSection::AddLane(short int side, int id, string type, bool level, bool sort)
-{	
-	unsigned int index=0;
-	//if lanes are sorted, add the lane to the correct side
-	if(sort)
-	{
-		if(side<0)
-		{
-			index=GetLaneCount();
-			mLaneVector.push_back(Lane(side,id,type,level));	
-			mLastAddedLane=index;
-		}
-		else if(side==0)
-		{
-			int sz=GetLaneCount();
-			if(sz>0)
-			{
-				for(int i=0; i<sz; i++)
-				{
-					if(mLaneVector[i].GetId()<0)
-					{
-						index=i;
-						mLaneVector.insert(mLaneVector.begin()+index, Lane(side,id,type,level));
-						mLastAddedLane=index;
-						break;
-					}
-				}
-			}
-			else
-			{
-				index=0;
-				mLaneVector.push_back(Lane(side,id,type,level));
-				mLastAddedLane=index;
-			}
-		}
-		else
-		{
-			index=0;
-			mLaneVector.insert(mLaneVector.begin(), Lane(side,id,type,level));
-			mLastAddedLane=index;
-		}
-
-		return index;
-	}
-	else
-	{
-		index=GetLaneCount();
-		mLaneVector.push_back(Lane(side,id,type,level));	
-		mLastAddedLane=index;
-		return index;
-	}	
-}
-
-/**
-* Delete the lane at the provided index
-*/
-void LaneSection::DeleteLane(unsigned int index)
-{
-	mLaneVector.erase(mLaneVector.begin()+index);
-}
-
-/**
-* Delete the outside left or right lane 
-*/
-void LaneSection::DeleteLeftLane()
-{
-	mLaneVector.erase(mLaneVector.begin());
-}
-void LaneSection::DeleteRigthLane()
-{
-	mLaneVector.pop_back();
-}
-
-/**
-* Get the last lane
-* @return A pointer to Lane object
-*/
-Lane* LaneSection::GetLastLane()
-{
-	if (mLaneVector.size()>0)
-		return &mLaneVector.at(mLaneVector.size()-1);
-	else
-		return NULL;
-}
-
-/**
-* Get the last added lane (which might not be the one from the end of the vector)
-* @return A pointer to Lane object
-*/
-Lane* LaneSection::GetLastAddedLane()
-{
-	if(mLastAddedLane<mLaneVector.size())
-		return &mLaneVector.at(mLastAddedLane);
-	else
-		return NULL;
-}
-
-/**
-* Get the last left lane
-* @return A pointer to Lane object
-*/
-Lane* LaneSection::GetLastLeftLane()
-{
-	if(mLaneVector.size()>0)
-	{
-		if(mLaneVector.at(0).GetSide()>0)
-			return &mLaneVector.at(0);
-		else
-			return NULL;
-	}
-	else
-		return NULL;
-}
-
-/**
-* Get the last center lane
-* @return A pointer to Lane object
-*/
-Lane* LaneSection::GetLastCenterLane()
-{
-	int sz=GetLaneCount();
-	for(int i=0; i<sz; i++)
-	{
-		if(mLaneVector[i].GetSide()==0)
-		{
-			return &mLaneVector.at(i);
-		}
-	}
-	return NULL;
-}
-
-/**
-* Get the last right lane
-* @return A pointer to Lane object
-*/
-Lane* LaneSection::GetLastRightLane()
-{
-	if(mLaneVector.size()>0)
-	{
-		int indexLast=mLaneVector.size()-1;
-		if(mLaneVector.at(indexLast).GetSide()<0)
-			return &mLaneVector.at(indexLast);
-		else
-			return NULL;
-	}
-	else return NULL;
-}
-/**
-* Get the lane vector
-* @return A pointer to a vector of type Lane
-*/
-vector<Lane>* LaneSection::GetLaneVector()
-{
-	return &mLaneVector;
-}
-
-/**
-* Get the lane by providing its index
-* @param i Index of the lane to be returned
-* @return A pointer to Lane object
-*/
-Lane* LaneSection::GetLane(unsigned int i)
-{
-	if ((mLaneVector.size()>0)&&(i<mLaneVector.size()))
-		return &mLaneVector.at(i);
-	else
-		return NULL;
-}
-
-/**
-* Get the lane number
-* @return Unsigned int with that stores the number of lanes
-*/
-unsigned int LaneSection::GetLaneCount()
-{
-	return mLaneVector.size();
-}
-
-/**
-* Get the lane section s-offset
-*/
-double LaneSection::GetS()
-{
-	return mS;
-}
-
-/**
-* Get the lane section final s-offset which is the s-offset of the last record of the lane section
-*/
-double LaneSection::GetS2()
-{
-	double lHighestS=0;
-
-	int sz=GetLaneCount();
-	for(int i=0; i<sz; i++)
-	{
-		Lane *lLane = GetLane(i);
-
-		//width
-		LaneWidth *lWidth = lLane->GetLaneWidth(lLane->GetLaneWidthCount()-1);
-		if(lWidth!=NULL) 
-		{
-			if(lWidth->GetS()>lHighestS) lHighestS=lWidth->GetS();
-		}
-
-		//road mark
-		LaneRoadMark *lRoadMark = lLane->GetLaneRoadMark(lLane->GetLaneRoadMarkCount()-1);
-		if(lRoadMark!=NULL) 
-		{
-			if(lRoadMark->GetS()>lHighestS) lHighestS=lRoadMark->GetS();
-		}
-
-		//material
-		LaneMaterial *lMaterial = lLane->GetLaneMaterial(lLane->GetLaneMaterialCount()-1);
-		if(lMaterial!=NULL) 
-		{
-			if(lMaterial->GetS()>lHighestS) lHighestS=lMaterial->GetS();
-		}
-
-		//visibility
-		LaneVisibility *lVisibility = lLane->GetLaneVisibility(lLane->GetLaneVisibilityCount()-1);
-		if(lVisibility!=NULL) 
-		{
-			if(lVisibility->GetS()>lHighestS) lHighestS=lVisibility->GetS();
-		}
-
-		//speed
-		LaneSpeed *lSpeed = lLane->GetLaneSpeed(lLane->GetLaneSpeedCount()-1);
-		if(lSpeed!=NULL) 
-		{
-			if(lSpeed->GetS()>lHighestS) lHighestS=lSpeed->GetS();
-		}
-
-		//access
-		LaneAccess *lAccess = lLane->GetLaneAccess(lLane->GetLaneAccessCount()-1);
-		if(lAccess!=NULL) 
-		{
-			if(lAccess->GetS()>lHighestS) lHighestS=lAccess->GetS();
-		}
-
-		//height
-		LaneHeight *lHeight = lLane->GetLaneHeight(lLane->GetLaneHeightCount()-1);
-		if(lHeight!=NULL) 
-		{
-			if(lHeight->GetS()>lHighestS) lHighestS=lHeight->GetS();
-		}
-	}
-
-	return mS+lHighestS;
-
-}
-
-/**
-* Set the lane section s-offset
-*/
-void LaneSection::SetS(double value)
-{
-	mS=value;
-}
-
-
-/**
-* Check if the tested s-offset is inside the lane section interval
-* @param A double s-offset value that has to be checked
-* @return Return true if the s-offset value belongs to current lane section, false otherwise
-*/
-bool LaneSection::CheckInterval(double s_check)
-{
-	if (s_check>=mS)
-		return true;
-	else 
-		return false;
-}
-
-/**
-* Return the lane-0 index in the lanes vector
-* @return An unsigned int value with the index
-*/
-unsigned int LaneSection::GetZeroLaneIndex()
-{
-	for (unsigned int i=0; i<GetLaneCount(); i++)
-	{
-		if(mLaneVector.at(i).GetId()==0)
-			return i;
-	}
-	return 0;
-}
-
-/**
-* Return the number of left lanes
-* @return An unsigned int value with the number of left lanes
-*/
-unsigned int LaneSection::GetLeftLaneCount()
-{
-	unsigned int count=0;
-	for (unsigned int i=0;i<GetLaneCount();i++)
-	{
-		if(mLaneVector.at(i).GetSide()==1)
-			count++;
-	}
-	return count;
-}
-
-/**
-* Return the number of central lanes
-* @return An unsigned int value with the number of central lanes
-*/
-unsigned int LaneSection::GetCenterLaneCount()
-{
-	unsigned int count=0;
-	for(unsigned int i=0; i<GetLaneCount(); i++)
-	{
-		if(mLaneVector[i].GetSide()==0)
-		{
-			count++;
-		}
-	}
-	return count;
-}
-
-/**
-* Return the number of right lanes
-* @return An unsigned int value with the number of right lanes
-*/
-unsigned int LaneSection::GetRightLaneCount()
-{
-	unsigned int count=0;
-	for (unsigned int i=0;i<GetLaneCount();i++)
-	{
-		if(mLaneVector.at(i).GetSide()==-1)
-			count++;
-	}
-	return count;
-}
-
-/**
-* Fill a special structure with all the lane / lane section data that is sampled at a provided s-offset position along the road
-* This data is used later to fill the geometry arrays
-* @param s_chek s-offset along the road at which to sample the lane section
-* @param laneSectionSample The structure that has to be filled with the sampled data
-* @return Returns true if the operation was successful. 
-*/
-bool LaneSection::FillLaneSectionSample(double s_check, LaneSectionSample& laneSectionSample)
-{
-	//clear and initialize variables
-	laneSectionSample.ClearVectors();
-	double width=0;
-	int leftMax=0;
-	int rightMax=GetLaneCount()-1;
-
-	s_check-=GetS();
-
-	bool level;
-	string type;
-	LaneHeight height; 
-	LaneRoadMark roadMark;
-	//Fill in left width vector
-	//if there are left lanes
-	if (GetLeftLaneCount()>0)
-	{	
-		//go through all of them
-		for (int i=GetZeroLaneIndex(); i>=leftMax;i--)
-		{	
-			type=GetLane(i)->GetType();
-			level=GetLane(i)->GetLevel();
-			height=GetLane(i)->GetHeightValue(s_check);
-			roadMark=GetLane(i)->GetRoadMarkValue(s_check);
-			//and accumulate the width
-			width=GetLane(i)->GetWidthValue(s_check);
-
-			laneSectionSample.AddLeftRecord(type, width, height, roadMark, level);
-		}
-	}
-
-	//same for the right side of the road
-	if (GetRightLaneCount()>0)
-	{	
-		//go through all of them
-		for (int i=GetZeroLaneIndex(); i<=rightMax;i++)
-		{	
-			type=GetLane(i)->GetType();
-			level=GetLane(i)->GetLevel();
-			height=GetLane(i)->GetHeightValue(s_check);
-			roadMark=GetLane(i)->GetRoadMarkValue(s_check);
-			//and accumulate the width
-			width=GetLane(i)->GetWidthValue(s_check);
-
-			laneSectionSample.AddRightRecord(type, width, height, roadMark, level);	
-		}
-	}
-	return true;
-}
-
-/**
-* Destructor. Delete all the members of the vectors: mLeft, mCenter, mRight
-*/
-LaneSection::~LaneSection()
-{
-	// DELETING LANES
-	mLaneVector.clear();
-}
-
-
-/**
-* Lane Section Sample. Holds all the lane information at a certain S value including lane widths, levels, 
-* heights, etc
-*
-*
-*
-*
-*/ 
-
-LaneSectionSample::LaneSectionSample()
-{}
-
-/*
-* Add various elements to the structure. Depending on the the value to be added, various input parameters are used.
-* The methods are divided into left and right for left and right sides of the road.
-*/
-void LaneSectionSample::AddLeftType(string type)
-{	mLeftTypeVector.push_back(type);	}
-void LaneSectionSample::AddLeftWidth(double width)
-{	mLeftWidthVector.push_back(width);	}
-void LaneSectionSample::AddLeftHeight(LaneHeight height)
-{	mLeftHeightVector.push_back(height);	}
-void LaneSectionSample::AddLeftRoadMark(LaneRoadMark roadMark)
-{	mLeftRoadMarkVector.push_back(roadMark);	}
-void LaneSectionSample::AddLeftLevel(bool level)
-{	mLeftLevelVector.push_back(level);	}
-
-void LaneSectionSample::AddRightType(string type)
-{	mRightTypeVector.push_back(type);	}
-void LaneSectionSample::AddRightWidth(double width)
-{	mRightWidthVector.push_back(width);	}
-void LaneSectionSample::AddRightHeight(LaneHeight height)
-{	mRightHeightVector.push_back(height);	}
-void LaneSectionSample::AddRightRoadMark(LaneRoadMark roadMark)
-{	mRightRoadMarkVector.push_back(roadMark);	}
-void LaneSectionSample::AddRightLevel(bool level)
-{	mRightLevelVector.push_back(level);	}
-
-void LaneSectionSample::AddLeftRecord(string type, double width, LaneHeight height, LaneRoadMark roadMark, bool level)
-{
-	AddLeftType(type);
-	AddLeftWidth(width);
-	AddLeftHeight(height);
-	AddLeftRoadMark(roadMark);
-	AddLeftLevel(level);
-}
-void LaneSectionSample::AddRightRecord(string type, double width, LaneHeight height, LaneRoadMark roadMark, bool level)
-{
-	AddRightType(type);
-	AddRightWidth(width);
-	AddRightHeight(height);
-	AddRightRoadMark(roadMark);
-	AddRightLevel(level);
-}
-
-/*
-* Get various elements of the structure. The methods return type depends on the elements that are returned.
-* The methods are divided into left and right for left and right sides of the road.
-*/
-string LaneSectionSample::GetLeftType(unsigned int i)
-{	return mLeftTypeVector.at(i);	}
-double LaneSectionSample::GetLeftWidth(unsigned int i)
-{	return mLeftWidthVector.at(i);	}
-LaneHeight LaneSectionSample::GetLeftHeight(unsigned int i)
-{	return mLeftHeightVector.at(i);	}
-LaneRoadMark LaneSectionSample::GetLeftRoadMark(unsigned int i)
-{	return mLeftRoadMarkVector.at(i);	}
-bool LaneSectionSample::GetLeftLevel(unsigned int i)
-{	return mLeftLevelVector.at(i);	}
-
-string LaneSectionSample::GetRightType(unsigned int i)
-{	return mRightTypeVector.at(i);	}
-double LaneSectionSample::GetRightWidth(unsigned int i)
-{	return mRightWidthVector.at(i);	}
-LaneHeight LaneSectionSample::GetRightHeight(unsigned int i)
-{	return mRightHeightVector.at(i);	}
-LaneRoadMark LaneSectionSample::GetRightRoadMark(unsigned int i)
-{	return mRightRoadMarkVector.at(i);	}
-bool LaneSectionSample::GetRightLevel(unsigned int i)
-{	return mRightLevelVector.at(i);	}
-
-
-/*
-* Get the number of elements in the vectors
-*/
-unsigned int LaneSectionSample::GetLeftVectorsSize()
-{	return mLeftWidthVector.size();	}
-unsigned int LaneSectionSample::GetRightVectorsSize()
-{	return mRightWidthVector.size();	}
-
-
-/*
-* Get the various record vectors. The vector type depends on the record
-* The methods are divided into left and right for left and right sides of the road.
-*/
-vector<string>* LaneSectionSample::GetLeftTypeVector()
-{	return &mLeftTypeVector;	}
-vector<double>* LaneSectionSample::GetLeftWidthVector()
-{	return &mLeftWidthVector;	}
-vector<LaneHeight>* LaneSectionSample::GetLeftHeigthVector()
-{	return &mLeftHeightVector;	}
-vector<LaneRoadMark>* LaneSectionSample::GetLeftRoadMarkVector()
-{	return &mLeftRoadMarkVector;	}
-vector<bool>* LaneSectionSample::GetLeftLevelVector()
-{	return &mLeftLevelVector;	}
-
-vector<string>* LaneSectionSample::GetRightTypeVector()
-{	return &mRightTypeVector;	}
-vector<double>* LaneSectionSample::GetRightWidthVector()
-{	return &mRightWidthVector;	}
-vector<LaneHeight>* LaneSectionSample::GetRightHeigthVector()
-{	return &mRightHeightVector;	}
-vector<LaneRoadMark>* LaneSectionSample::GetRightRoadMarkVector()
-{	return &mRightRoadMarkVector;	}
-vector<bool>* LaneSectionSample::GetRightLevelVector()
-{	return &mRightLevelVector;	}
-
-/*
-* Clear the vectors
-*/
-void LaneSectionSample::ClearVectors()
-{
-	mLeftTypeVector.clear();
-	mLeftWidthVector.clear();
-	mLeftHeightVector.clear();
-	mLeftRoadMarkVector.clear();
-	mLeftLevelVector.clear();
-
-	mRightTypeVector.clear();
-	mRightWidthVector.clear();
-	mRightHeightVector.clear();
-	mRightRoadMarkVector.clear();
-	mRightLevelVector.clear();
-}
-
-/**
-* Lane class. Holds all the record data that describes a lane
-*
-*
-*
-*
-*
-*/
-
-/**
-*	Constructor
-*/
-Lane::Lane(short int side, int id, string type, bool level)
-{	mSide=side; mId=id; mType=type; mLevel=level;	mPredecessorExists=false; mSuccessorExists=false;	}
-
-/**
-*	Various set methods.
-*/
-void Lane::SetSide(short int side)
-{
-	mSide=side;
-}
-void Lane::SetId(int id)
-{
-	mId=id;
-}
-void Lane::SetType(string type)
-{
-	mType=type;
-}
-void Lane::SetLevel(bool level)
-{
-	mLevel=level;
-}
-//-------------
-void Lane::SetPredecessor(int predecessor)
-{	mPredecessor=predecessor; mPredecessorExists=true;	}
-//-------------
-void Lane::SetSuccessor(int successor)
-{	mSuccessor=successor;	mSuccessorExists=true;	}
-
-/**
-*	Remove lane linkage
-*/
-void Lane::RemovePredecessor()
-{	mPredecessor=0;	mPredecessorExists=false;	}
-
-void Lane::RemoveSuccessor()
-{	mSuccessor=0;	mSuccessorExists=false;		}
-
-
-/**
- * Methods used to add child records to the respective vectors
- */
-unsigned int Lane::AddWidthRecord(double s, double a, double b, double c, double d)
-{	
-	// Gets the index where the record should be inserted in the vector
-	unsigned int index = CheckWidthInterval(s)+1;
-	// If larger than the record count - push to the back
-	if(index>=GetLaneWidthCount()) mLaneWidth.push_back(LaneWidth(s,a,b,c,d));	
-	// else insert in the middle
-	else mLaneWidth.insert(mLaneWidth.begin()+index, LaneWidth(s,a,b,c,d));
-	// Save the last added record index
-	mLastAddedLaneWidth=index;
-	return index;
-}
-//-------------
-unsigned int Lane::AddRoadMarkRecord(double sOffset, string type, string weight, string color, double width, string laneChange)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckRoadMarkInterval(sOffset)+1;
-	if(index>=GetLaneRoadMarkCount()) mLaneRoadMark.push_back(LaneRoadMark(sOffset, type, weight, color, width, laneChange));	
-	else mLaneRoadMark.insert(mLaneRoadMark.begin()+index, LaneRoadMark(sOffset, type, weight, color, width, laneChange));
-	mLastAddedLaneRoadMark=index;
-	return index;
-}
-//-------------
-unsigned int Lane::AddMaterialRecord(double sOffset, string surface, double friction, double roughness)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckMaterialInterval(sOffset)+1;
-	if(index>=GetLaneMaterialCount()) mLaneMaterial.push_back(LaneMaterial(sOffset,surface,friction,roughness));	
-	else mLaneMaterial.insert(mLaneMaterial.begin()+index, LaneMaterial(sOffset,surface,friction,roughness));
-	mLastAddedLaneMaterial=index;
-	return index;
-}
-//-------------
-unsigned int Lane::AddVisibilityRecord(double sOffset, double forward, double back, double left, double right)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckVisibilityInterval(sOffset)+1;
-	if(index>=GetLaneVisibilityCount()) mLaneVisibility.push_back(LaneVisibility(sOffset,forward,back,left,right));	
-	else mLaneVisibility.insert(mLaneVisibility.begin()+index, LaneVisibility(sOffset,forward,back,left,right));
-	mLastAddedLaneVisibility=index;
-	return index;
-}
-//-------------
-unsigned int Lane::AddSpeedRecord(double sOffset, double max)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckSpeedInterval(sOffset)+1;
-	if(index>=GetLaneSpeedCount()) mLaneSpeed.push_back(LaneSpeed(sOffset,max));	
-	else mLaneSpeed.insert(mLaneSpeed.begin()+index, LaneSpeed(sOffset,max));
-	mLastAddedLaneSpeed=index;
-	return index;
-}
-//-------------
-unsigned int Lane::AddAccessRecord(double sOffset, string restriction)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckAccessInterval(sOffset)+1;
-	if(index>=GetLaneAccessCount()) mLaneAccess.push_back(LaneAccess(sOffset,restriction));	
-	else mLaneAccess.insert(mLaneAccess.begin()+index, LaneAccess(sOffset,restriction));
-	mLastAddedLaneAccess=index;
-	return index;
-}
-//-------------
-unsigned int Lane::AddHeightRecord(double sOffset, double inner, double outer)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckHeightInterval(sOffset)+1;
-	if(index>=GetLaneHeightCount()) mLaneHeight.push_back(LaneHeight(sOffset,inner,outer));	
-	else mLaneHeight.insert(mLaneHeight.begin()+index, LaneHeight(sOffset,inner,outer));
-	mLastAddedLaneHeight=index;
-	return index;
-}
-
-/**
- * Methods used to clone child records in the respective vectors
- */
-unsigned int Lane::CloneLaneWidth(unsigned int index)
-{
-	// Clone the object and insert it in the middle of the vector
-	if(index<mLaneWidth.size()-1)
-		mLaneWidth.insert(mLaneWidth.begin()+index+1, mLaneWidth[index]);
-	// or just push it to the back
-	else if(index==mLaneWidth.size()-1)
-		mLaneWidth.push_back(mLaneWidth[index]);
-	// Save the last added record index
-	mLastAddedLaneWidth=index+1;
-	return mLastAddedLaneWidth;
-}
-unsigned int Lane::CloneLaneRoadMark(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mLaneRoadMark.size()-1)
-		mLaneRoadMark.insert(mLaneRoadMark.begin()+index+1, mLaneRoadMark[index]);
-	else if(index==mLaneRoadMark.size()-1)
-		mLaneRoadMark.push_back(mLaneRoadMark[index]);
-	mLastAddedLaneRoadMark=index+1;
-	return mLastAddedLaneRoadMark;
-}
-unsigned int Lane::CloneLaneMaterial(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mLaneMaterial.size()-1)
-		mLaneMaterial.insert(mLaneMaterial.begin()+index+1, mLaneMaterial[index]);
-	else if(index==mLaneMaterial.size()-1)
-		mLaneMaterial.push_back(mLaneMaterial[index]);
-	mLastAddedLaneMaterial=index+1;
-	return mLastAddedLaneMaterial;
-}
-unsigned int Lane::CloneLaneVisibility(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mLaneVisibility.size()-1)
-		mLaneVisibility.insert(mLaneVisibility.begin()+index+1, mLaneVisibility[index]);
-	else if(index==mLaneVisibility.size()-1)
-		mLaneVisibility.push_back(mLaneVisibility[index]);
-	mLastAddedLaneVisibility=index+1;
-	return mLastAddedLaneVisibility;
-}
-unsigned int Lane::CloneLaneSpeed(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mLaneSpeed.size()-1)
-		mLaneSpeed.insert(mLaneSpeed.begin()+index+1, mLaneSpeed[index]);
-	else if(index==mLaneSpeed.size()-1)
-		mLaneSpeed.push_back(mLaneSpeed[index]);
-	mLastAddedLaneSpeed=index+1;
-	return mLastAddedLaneSpeed;
-}
-unsigned int Lane::CloneLaneAccess(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mLaneAccess.size()-1)
-		mLaneAccess.insert(mLaneAccess.begin()+index+1, mLaneAccess[index]);
-	else if(index==mLaneAccess.size()-1)
-		mLaneAccess.push_back(mLaneAccess[index]);
-	mLastAddedLaneAccess=index+1;
-	return mLastAddedLaneAccess;
-}
-unsigned int Lane::CloneLaneHeight(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mLaneHeight.size()-1)
-		mLaneHeight.insert(mLaneHeight.begin()+index+1, mLaneHeight[index]);
-	else if(index==mLaneHeight.size()-1)
-		mLaneHeight.push_back(mLaneHeight[index]);
-	mLastAddedLaneHeight=index+1;
-	return mLastAddedLaneHeight;
-}
-
-/**
- * Methods used to delete child records from the respective vectors
- */
-void Lane::DeleteLaneWidth(unsigned int index)
-{
-	mLaneWidth.erase(mLaneWidth.begin()+index);
-}
-void Lane::DeleteLaneRoadMark(unsigned int index)
-{
-	mLaneRoadMark.erase(mLaneRoadMark.begin()+index);
-}
-void Lane::DeleteLaneMaterial(unsigned int index)
-{
-	mLaneMaterial.erase(mLaneMaterial.begin()+index);
-}
-void Lane::DeleteLaneVisibility(unsigned int index)
-{
-	mLaneVisibility.erase(mLaneVisibility.begin()+index);
-}
-void Lane::DeleteLaneSpeed(unsigned int index)
-{
-	mLaneSpeed.erase(mLaneSpeed.begin()+index);
-}
-void Lane::DeleteLaneAccess(unsigned int index)
-{
-	mLaneAccess.erase(mLaneAccess.begin()+index);
-}
-void Lane::DeleteLaneHeight(unsigned int index)
-{
-	mLaneHeight.erase(mLaneHeight.begin()+index);
-}
-
-
-/**
-*	Getters of the lane parameters
-*/
-int Lane::GetSide()
-{
-	return mSide;
-}
-int Lane::GetId()
-{
-	return mId;
-}
-string Lane::GetType()
-{
-	return mType;
-}
-bool Lane::GetLevel()
-{
-	return mLevel;
-}
-
-/**
-*	Check if linkage information is provided
-*/
-bool Lane::IsPredecessorSet()
-{
-	return mPredecessorExists;
-}
-int Lane::GetPredecessor()
-{
-	return mPredecessor;
-}
-bool Lane::IsSuccessorSet()
-{
-	return mSuccessorExists;
-}
-int Lane::GetSuccessor()
-{
-	return mSuccessor;
-}
-
-
-/**
-*	Get pointers to the records vectors
-*/
-vector <LaneWidth> *Lane::GetLaneWidthVector()
-{	return &mLaneWidth;	}
-
-vector <LaneRoadMark> *Lane::GetLaneRoadMarkVector()
-{	return &mLaneRoadMark;	}
-
-vector <LaneMaterial> *Lane::GetLaneMaterialVector()
-{	return &mLaneMaterial;	}
-
-vector <LaneVisibility> *Lane::GetLaneVisibilityVector()
-{	return &mLaneVisibility;	}
-
-vector <LaneSpeed> *Lane::GetLaneSpeedVector()
-{	return &mLaneSpeed;	}
-
-vector <LaneAccess> *Lane::GetLaneAccessVector()
-{	return &mLaneAccess;	}
-
-vector <LaneHeight> *Lane::GetLaneHeightVector()
-{	return &mLaneHeight;	}
-
-
-/**
-*	Get the number of elements in a certain vector
-*/
-unsigned int Lane::GetLaneWidthCount()
-{	return mLaneWidth.size();	}
-
-unsigned int Lane::GetLaneRoadMarkCount()
-{	return mLaneRoadMark.size();	}
-
-unsigned int Lane::GetLaneMaterialCount()
-{	return mLaneMaterial.size();	}
-
-unsigned int Lane::GetLaneVisibilityCount()
-{	return mLaneVisibility.size();	}
-
-unsigned int Lane::GetLaneSpeedCount()
-{	return mLaneSpeed.size();	}
-
-unsigned int Lane::GetLaneAccessCount()
-{	return mLaneAccess.size();	}
-
-unsigned int Lane::GetLaneHeightCount()
-{	return mLaneHeight.size();	}
-
-/**
-*	Get the elements of a certain vectors at position i
-*/
-LaneWidth* Lane::GetLaneWidth(unsigned int i)
-{
-	if ((mLaneWidth.size()>0)&&(i<mLaneWidth.size()))
-		return &mLaneWidth.at(i);
-	else
-		return NULL;
-}
-
-LaneRoadMark* Lane::GetLaneRoadMark(unsigned int i)
-{
-	if ((mLaneRoadMark.size()>0)&&(i<mLaneRoadMark.size()))
-		return &mLaneRoadMark.at(i);
-	else
-		return NULL;
-}
-
-LaneMaterial* Lane::GetLaneMaterial(unsigned int i)
-{
-	if ((mLaneMaterial.size()>0)&&(i<mLaneMaterial.size()))
-		return &mLaneMaterial.at(i);
-	else
-		return NULL;
-}
-
-LaneVisibility* Lane::GetLaneVisibility(unsigned int i)
-{
-	if ((mLaneVisibility.size()>0)&&(i<mLaneVisibility.size()))
-		return &mLaneVisibility.at(i);
-	else
-		return NULL;
-}
-
-LaneSpeed* Lane::GetLaneSpeed(unsigned int i)
-{
-	if ((mLaneSpeed.size()>0)&&(i<mLaneSpeed.size()))
-		return &mLaneSpeed.at(i);
-	else
-		return NULL;
-}
-
-LaneAccess* Lane::GetLaneAccess(unsigned int i)
-{
-	if ((mLaneAccess.size()>0)&&(i<mLaneAccess.size()))
-		return &mLaneAccess.at(i);
-	else
-		return NULL;
-}
-
-LaneHeight* Lane::GetLaneHeight(unsigned int i)
-{
-	if ((mLaneHeight.size()>0)&&(i<mLaneHeight.size()))
-		return &mLaneHeight.at(i);
-	else
-		return NULL;
-}
-
-
-/**
-*	Get the last elements of a certain vectors
-*/
-LaneWidth* Lane::GetLastLaneWidth()
-{
-	if (mLaneWidth.size()>0)
-		return &mLaneWidth.at(mLaneWidth.size()-1);
-	else
-		return NULL;
-}
-LaneRoadMark* Lane::GetLastLaneRoadMark()
-{
-	if (mLaneRoadMark.size()>0)
-		return &mLaneRoadMark.at(mLaneRoadMark.size()-1);
-	else
-		return NULL;
-}
-LaneMaterial* Lane::GetLastLaneMaterial()
-{
-	if (mLaneMaterial.size()>0)
-		return &mLaneMaterial.at(mLaneMaterial.size()-1);
-	else
-		return NULL;
-}
-LaneVisibility* Lane::GetLastLaneVisibility()
-{
-	if (mLaneVisibility.size()>0)
-		return &mLaneVisibility.at(mLaneVisibility.size()-1);
-	else
-		return NULL;
-}
-LaneSpeed* Lane::GetLastLaneSpeed()
-{
-	if (mLaneSpeed.size()>0)
-		return &mLaneSpeed.at(mLaneSpeed.size()-1);
-	else
-		return NULL;
-}
-LaneAccess* Lane::GetLastLaneAccess()
-{
-	if (mLaneAccess.size()>0)
-		return &mLaneAccess.at(mLaneAccess.size()-1);
-	else
-		return NULL;
-}
-LaneHeight* Lane::GetLastLaneHeight()
-{
-	if (mLaneHeight.size()>0)
-		return &mLaneHeight.at(mLaneHeight.size()-1);
-	else
-		return NULL;
-}
-
-/**
-*	Get the last added elements of a certain vectors (their position might not be at the end of the vector)
-*/
-LaneWidth* Lane::GetLastAddedLaneWidth()
-{
-	if(mLastAddedLaneWidth<mLaneWidth.size())
-		return &mLaneWidth.at(mLastAddedLaneWidth);
-	else
-		return NULL;
-}
-LaneRoadMark* Lane::GetLastAddedLaneRoadMark()
-{
-	if(mLastAddedLaneRoadMark<mLaneRoadMark.size())
-		return &mLaneRoadMark.at(mLastAddedLaneRoadMark);
-	else
-		return NULL;
-}
-LaneMaterial* Lane::GetLastAddedLaneMaterial()
-{
-	if(mLastAddedLaneMaterial<mLaneMaterial.size())
-		return &mLaneMaterial.at(mLastAddedLaneMaterial);
-	else
-		return NULL;
-}
-LaneVisibility* Lane::GetLastAddedLaneVisibility()
-{
-	if(mLastAddedLaneVisibility<mLaneVisibility.size())
-		return &mLaneVisibility.at(mLastAddedLaneVisibility);
-	else
-		return NULL;
-}
-LaneSpeed* Lane::GetLastAddedLaneSpeed()
-{
-	if(mLastAddedLaneSpeed<mLaneSpeed.size())
-		return &mLaneSpeed.at(mLastAddedLaneSpeed);
-	else
-		return NULL;
-}
-LaneAccess* Lane::GetLastAddedLaneAccess()
-{
-	if(mLastAddedLaneAccess<mLaneAccess.size())
-		return &mLaneAccess.at(mLastAddedLaneAccess);
-	else
-		return NULL;
-}
-LaneHeight* Lane::GetLastAddedLaneHeight()
-{
-	if(mLastAddedLaneHeight<mLaneHeight.size())
-		return &mLaneHeight.at(mLastAddedLaneHeight);
-	else
-		return NULL;
-}
-
-/**
-*	Check the intervals and return the index of the records that applies to the provided s-offset
-*/
-int  Lane::CheckWidthInterval(double s_check)
-{
-
-	int res=-1;
-	//Go through all the width records
-	for (unsigned int i=0;i<mLaneWidth.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (s_check >= mLaneWidth.at(i).GetS())
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-int Lane::CheckRoadMarkInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the road mark records
-	for (unsigned int i=0;i<mLaneRoadMark.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (s_check >= mLaneRoadMark.at(i).GetS())
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-int Lane::CheckMaterialInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the material records
-	for (unsigned int i=0;i<mLaneMaterial.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (s_check >= mLaneMaterial.at(i).GetS())
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-int Lane::CheckVisibilityInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the visibility records
-	for (unsigned int i=0;i<mLaneVisibility.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (s_check >= mLaneVisibility.at(i).GetS())
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-int Lane::CheckSpeedInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the speed records
-	for (unsigned int i=0;i<mLaneSpeed.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (s_check >= mLaneSpeed.at(i).GetS())
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-int Lane::CheckAccessInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the access records
-	for (unsigned int i=0;i<mLaneAccess.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (s_check >= mLaneAccess.at(i).GetS())
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-int Lane::CheckHeightInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the height records
-	for (unsigned int i=0;i<mLaneHeight.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (s_check >= mLaneHeight.at(i).GetS())
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-
-/**
-*	Evaluate the record and return the width value
-*/
-double  Lane::GetWidthValue(double s_check)
-{
-	double retVal=0;
-	//find the record where s_check belongs
-	int index=CheckWidthInterval(s_check);
-	//If found, return the type
-	if (index>=0)
-		retVal= mLaneWidth.at(index).GetValue(s_check);
-	return retVal;
-}
-
-/**
-*	Evaluate the record and return the height object
-*/
-LaneHeight  Lane::GetHeightValue(double s_check)
-{
-	LaneHeight  retVal(0,0,0);
-	//find the record where s_check belongs
-	int index=CheckHeightInterval(s_check);
-	//If found, return the type
-	if (index>=0)
-	{
-		retVal.SetInner(mLaneHeight.at(index).GetInner());
-		retVal.SetOuter(mLaneHeight.at(index).GetOuter());
-	}
-	return retVal;
-}
-
-
-/**
-*	Evaluate the road marks records and return the road mark object corresponding to the provided s-offset
-*/
-LaneRoadMark Lane::GetRoadMarkValue(double s_check)
-{
-	LaneRoadMark returnRoadMark;
-	//find the record where s_check belongs
-	int index=CheckRoadMarkInterval(s_check);
-	//If found, return the params 
-	if (index>=0)
-	{
-		returnRoadMark.SetColor(mLaneRoadMark.at(index).GetColor());
-		returnRoadMark.SetLaneChange(mLaneRoadMark.at(index).GetLaneChange());
-		returnRoadMark.SetType(mLaneRoadMark.at(index).GetType());
-		returnRoadMark.SetWeight(mLaneRoadMark.at(index).GetWeight());
-		returnRoadMark.SetWidth(mLaneRoadMark.at(index).GetWidth());
-	}
-
-	return returnRoadMark;
-
-}
-
-/**
-* Destructor
-* Delete all the members of the vectors:
-* mLaneWidth, mRoadMark, mLaneMaterial, mLaneVisibility, mLaneSpeed, mLaneAccess, mLaneHeight
-*/
-Lane::~Lane()
-{
-	// DELETING LANE WIDTHS
-	mLaneWidth.clear();
-
-	// DELETING LANE ROAD MARKS
-	mLaneRoadMark.clear();
-
-	// DELETING LANE MATERIAL
-	mLaneMaterial.clear();
-
-	// DELETING LANE VISIBILITY
-	mLaneVisibility.clear();
-
-	// DELETING LANE SPEED
-	mLaneSpeed.clear();
-
-	// DELETING LANE ACCESS
-	mLaneAccess.clear();
-
-	// DELETING LANE HEIGHTS
-	mLaneHeight.clear();
-}
-
-/**
-* Lane width class. Holds all the data that describes a lane width
-*
-*
-*
-*
-*
-*/
-
-/**
-* Constructor
-* @param s s-offset of the record starting from the lane section s-offset
-* @ param a,b,c,d The 4 parameters of the polynomial
-*/
-LaneWidth::LaneWidth(double s, double a, double b, double c, double d):ThirdOrderPolynom (s,a,b,c,d)
-{}
-
-/**
-* Road mark class. Holds all the data that describes a road mark
-*
-*
-*
-*
-*
-*/
-
-/*
-* Constructors
-*/
-LaneRoadMark::LaneRoadMark()
-{	mSOffset=0, mType="none"; mWeight="standard"; mColor="standard"; mWidth=0.75; mLaneChange="both"; 	}
-//-------------
-LaneRoadMark::LaneRoadMark(double sOffset, string type, string weight, string color, double width, string laneChange)
-{	mSOffset=sOffset; mType=type; mWeight=weight; mColor=color; mWidth=width; mLaneChange=laneChange;	
-}
-//-------------
-LaneRoadMark::LaneRoadMark(double sOffset, string type, string weight, string color, double width)
-{	mSOffset=sOffset; mType=type; mWeight=weight; mColor=color; mWidth=width; mLaneChange="both"; }
-
-/*
-* Methods that set the parameters of the road mark
-*/
-void LaneRoadMark::SetS(double value)
-{	mSOffset = value;	}
-void LaneRoadMark::SetType(string type)
-{	mType=type;	}
-void LaneRoadMark::SetWeight(string weight)
-{	mWeight=weight;	}
-void LaneRoadMark::SetColor(string color)
-{	mColor=color;	}
-void LaneRoadMark::SetWidth(double value)
-{	mWidth=value;	}
-void LaneRoadMark::SetLaneChange(string laneChange)
-{	mLaneChange=laneChange;	}
-
-
-/*
-* Methods that return the parameters of the road mark
-*/
-double LaneRoadMark::GetS()
-{	return mSOffset;	}
-string LaneRoadMark::GetType()
-{	return mType;	}
-string LaneRoadMark::GetWeight()
-{	return mWeight;	}
-string LaneRoadMark::GetColor()
-{	return mColor;	}
-double LaneRoadMark::GetWidth()
-{	return mWidth;	}
-string LaneRoadMark::GetLaneChange()
-{	return mLaneChange;	}
-
-/**
-* Lane material class. Contains all the data that describes a lane material
-*
-*
-*
-*
-*
-*/
-
-/*
-* Constructor
-*/
-LaneMaterial::LaneMaterial (double sOffset, string surface, double friction, double roughness)
-{	mSOffset=sOffset; mSurface=surface; mFriction=friction; mRoughness=roughness;	}
-
-/*
-* Methods that return the parameters of the lane material
-*/
-double LaneMaterial::GetS()
-{	return mSOffset;	}
-string LaneMaterial::GetSurface()
-{	return mSurface;	}
-double LaneMaterial::GetFriction()
-{	return mFriction;	}
-double LaneMaterial::GetRoughness()
-{	return mRoughness;	}
-
-/*
-* Methods that set the parameters of the lane material
-*/
-void LaneMaterial::SetS(double value)
-{	mSOffset=value;	}
-void LaneMaterial::SetSurface(string surface)
-{	mSurface=surface;	}
-void LaneMaterial::SetFriction(double value)
-{	mFriction=value;	}
-void LaneMaterial::SetRoughness(double value)
-{	mRoughness=value;	}
-
-
-/**
-* Lane visibility class. Contains all the data that describes lane visibility record
-*
-*
-*
-*
-*
-*/
-
-/*
-* Constructor
-*/
-LaneVisibility::LaneVisibility(double sOffset, double forward, double back, double left, double right)
-{	mSOffset=sOffset; mForward=forward; mBack=back; mLeft=left; mRight=right;	}
-
-/*
-* Methods that return the parameters of the lane visibility
-*/
-double LaneVisibility::GetS()
-{	return mSOffset;	}
-double LaneVisibility::GetForward()
-{	return mForward;	}
-double LaneVisibility::GetBack()
-{	return mBack;	}
-double LaneVisibility::GetLeft()
-{	return mLeft;	}
-double LaneVisibility::GetRight()
-{	return mRight;	}
-
-/*
-* Methods that set the parameters of the lane visibility
-*/
-void LaneVisibility::SetS(double value)
-{	mSOffset=value;	}
-void LaneVisibility::SetForward(double value)
-{	mForward=value;	}
-void LaneVisibility::SetBack(double value)
-{	mBack=value;	}
-void LaneVisibility::SetLeft(double value)
-{	mLeft=value;	}
-void LaneVisibility::SetRight(double value)
-{	mRight=value;	}
-
-
-/**
-* Lane speed class. Contains all the data that describes lane speed record
-*
-*
-*
-*
-*
-*/
-
-/*
-* Constructor
-*/
-LaneSpeed::LaneSpeed (double sOffset, double max)
-{	mSOffset=sOffset; mMax=max;}
-
-/*
-* Methods that return the parameters of the lane speed
-*/
-double LaneSpeed::GetS()
-{	return mSOffset;	}
-double LaneSpeed::GetMax()
-{	return mMax;	}
-
-/*
-* Methods that set the parameters of the lane speed
-*/
-void LaneSpeed::SetS(double value)
-{	mSOffset=value;	}
-void LaneSpeed::SetMax(double value)
-{	mMax=value;	}
-
-
-/**
-* Lane access class. Contains all the data that describes lane access record
-*
-*
-*
-*
-*
-*/
-/*
-* Constructor
-*/
-LaneAccess::LaneAccess (double sOffset, string restriction)
-{	mSOffset=sOffset; mRestriction = restriction;	}
-
-/*
-* Methods that return the parameters of the lane access
-*/
-double LaneAccess::GetS()
-{	return mSOffset;	}
-string LaneAccess::GetRestriction()
-{	return mRestriction;	}
-
-/*
-* Methods that set the parameters of the lane access
-*/
-void LaneAccess::SetS(double value)
-{	mSOffset=value;	}
-void LaneAccess::SetRestriction(string restriction)
-{	mRestriction=restriction;	}
-
-/**
-* Lane height class. Contains all the data that describes lane access record
-*
-*
-*
-*
-*
-*/
-/*
-* Constructors
-*/
-LaneHeight::LaneHeight()
-{mSOffset=0; mInner=0; mOuter=0;}
-LaneHeight::LaneHeight (double sOffset, double inner, double outer)
-{	mSOffset=sOffset; mInner=inner; mOuter=outer;	}
-
-/*
-* Methods that return the parameters of the lane height
-*/
-double LaneHeight::GetS()
-{	return mSOffset;	}
-double LaneHeight::GetInner()
-{	return mInner;	}
-double LaneHeight::GetOuter()
-{	return mOuter;	}
-
-/*
-* Methods that set the parameters of the lane height
-*/
-void LaneHeight::SetS(double value)
-{	mSOffset=value;	}
-void LaneHeight::SetInner(double value)
-{	mInner=value;	}
-void LaneHeight::SetOuter(double value)
-{	mOuter=value;	}

+ 0 - 773
src/tool/tool_xodrobj/OpenDrive/Lane.h

@@ -1,773 +0,0 @@
-#ifndef LANE_H
-#define LANE_H
-
-#include "Road.h"
-#include "OtherStructures.h"
-#include <vector>
-#include <string>
-
-
-//Prototypes
-class LaneSection;
-class LaneSectionSample;
-class Lane;
-class LaneWidth;
-class LaneRoadMark;
-class LaneMaterial;
-class LaneVisibility;
-class LaneSpeed;
-class LaneAccess;
-class LaneHeight;
-
-using std::vector;
-using std::string;
-
-/**
-* Lane section class. Holds all the lane section information
-*
-*
-*
-*
-*/
-class LaneSection
-{
-private:
-	/**
-	* Record parameters
-	*/
-	double mS;
-	vector<Lane> mLaneVector;
-
-	unsigned int mLastAddedLane;
-
-public:
-	/**
-	* Constructor. Sets basic lane section parameters
-	* @param s s-offset of the lane section
-	*/
-	LaneSection (double s);
-
-	/**
-	* Add a lane to the lane section
-	* @param side the side of the road to which the lane will be added
-	* @param id ID of the lane
-	* @param type Type of the lane (Section 6.5 of the OpenDRIVE specification) 
-	* @param level Level parameter of the road
-	* @param sort Defines if the lanes should be sorted when added. True by default
-	*/
-	unsigned int AddLane(short int side, int id, string type, bool level, bool sort=true);
-
-
-	/**
-	* Delete the lane at the provided index
-	*/
-	void DeleteLane(unsigned int index);
-
-	/**
-	* Delete the outside left or right lane 
-	*/
-	void DeleteLeftLane();
-	void DeleteRigthLane();
-
-	/**
-	* Get the last lane
-	* @return A pointer to Lane object
-	*/
-	Lane* GetLastLane();
-
-	/**
-	* Get the last added lane (which might not be the one from the end of the vector)
-	* @return A pointer to Lane object
-	*/
-	Lane* GetLastAddedLane();
-
-	/**
-	* Get the last left lane
-	* @return A pointer to Lane object
-	*/
-	Lane* GetLastLeftLane();
-
-	/**
-	* Get the last right lane
-	* @return A pointer to Lane object
-	*/
-	Lane* GetLastRightLane();
-
-	/**
-	* Get the last center lane
-	* @return A pointer to Lane object
-	*/
-	Lane* GetLastCenterLane();
-
-	/**
-	* Get the lane by providing its index
-	* @param i Index of the lane to be returned
-	* @return A pointer to Lane object
-	*/
-	Lane* GetLane(unsigned int i);
-
-	/**
-	* Get the lane number
-	* @return Unsigned int with that stores the number of lanes
-	*/
-	unsigned int GetLaneCount();
-
-	/**
-	* Get the lane vector
-	* @return A pointer to a vector of type Lane
-	*/
-	vector<Lane>* GetLaneVector();
-
-	/**
-	* Get the lane section s-offset
-	*/
-	double GetS();
-
-	/**
-	* Get the lane section final s-offset which is the s-offset of the last record of the lane section
-	*/
-	double GetS2();
-
-	/**
-	* Set the lane section s-offset
-	*/
-	void SetS(double value);
-
-
-	/**
-	* Check if the tested s-offset is inside the lane section interval
-	* @param A double s-offset value that has to be checked
-	* @return Return true if the s-offset value belongs to current lane section, false otherwise
-	*/
-	bool CheckInterval(double s_check);
-
-	/**
-	* Return the lane-0 index in the lanes vector
-	* @return An unsigned int value with the index
-	*/
-	unsigned int GetZeroLaneIndex();
-
-	/**
-	* Return the number of left lanes
-	* @return An unsigned int value with the number of left lanes
-	*/
-	unsigned int GetLeftLaneCount();
-
-	/**
-	* Return the number of central lanes
-	* @return An unsigned int value with the number of central lanes
-	*/
-	unsigned int GetCenterLaneCount();
-
-	/**
-	* Return the number of right lanes
-	* @return An unsigned int value with the number of right lanes
-	*/
-	unsigned int GetRightLaneCount();
-
-	/**
-	* Fill a special structure with all the lane / lane section data that is sampled at a provided s-offset position along the road
-	* @param s_chek s-offset along the road at which to sample the lane section
-	* @param laneSectionSample The structure that has to be filled with the sampled data
-	* @return Returns true if the operation was successful. 
-	*/
-	bool FillLaneSectionSample(double s_check, LaneSectionSample& laneSectionSample);
-
-	/**
-	* Destructor. Delete all the members of the vectors: mLeft, mCenter, mRight
-	*/
-	~LaneSection();
-};
-
-
-/**
-* Lane Section Sample. Holds all the lane information at a certain S value including lane widths, levels, 
-* heights, etc
-*
-*
-*
-*
-*/ 
-class LaneSectionSample
-{
-private:
-	/*
-	*	All the vectors for the data that is sampled. For ease of use the structure is divided into left and right lane groups.
-	*
-	*/
-	vector<string> mLeftTypeVector;
-	vector<double> mLeftWidthVector;
-	vector<LaneHeight> mLeftHeightVector;
-	vector<LaneRoadMark> mLeftRoadMarkVector;
-	vector<bool> mLeftLevelVector;
-
-	vector<string> mRightTypeVector;
-	vector<double> mRightWidthVector;
-	vector<LaneHeight> mRightHeightVector;
-	vector<LaneRoadMark> mRightRoadMarkVector;
-	vector<bool> mRightLevelVector;
-public:
-	LaneSectionSample();
-
-	/*
-	* Add various elements to the structure. Depending on the the value to be added, various input parameters are used.
-	* The methods are divided into left and right for left and right sides of the road.
-	*/
-	void AddLeftType(string type);
-	void AddLeftWidth(double width);
-	void AddLeftHeight(LaneHeight height);
-	void AddLeftRoadMark(LaneRoadMark roadMark);
-	void AddLeftLevel(bool level);
-
-	void AddRightType(string type);
-	void AddRightWidth(double width);
-	void AddRightHeight(LaneHeight height);
-	void AddRightRoadMark(LaneRoadMark roadMark);
-	void AddRightLevel(bool level);
-
-	void AddLeftRecord(string type, double width, LaneHeight height, LaneRoadMark roadMark, bool level);
-	void AddRightRecord(string type, double width, LaneHeight height, LaneRoadMark roadMark, bool level);
-
-	/*
-	* Get various elements of the structure. The methods return type depends on the elements that are returned.
-	* The methods are divided into left and right for left and right sides of the road.
-	*/
-	string GetLeftType(unsigned int i);
-	double GetLeftWidth(unsigned int i);
-	LaneHeight GetLeftHeight(unsigned int i);
-	LaneRoadMark GetLeftRoadMark(unsigned int i);
-	bool GetLeftLevel(unsigned int i);
-
-	string GetRightType(unsigned int i);
-	double GetRightWidth(unsigned int i);
-	LaneHeight GetRightHeight(unsigned int i);
-	LaneRoadMark GetRightRoadMark(unsigned int i);
-	bool GetRightLevel(unsigned int i);
-
-	/*
-	* Get the number of elements in the vectors
-	*/
-	unsigned int GetLeftVectorsSize();
-	unsigned int GetRightVectorsSize();
-
-	/*
-	* Get the various record vectors. The vector type depends on the record
-	* The methods are divided into left and right for left and right sides of the road.
-	*/
-	vector<string>* GetLeftTypeVector();
-	vector<double>* GetLeftWidthVector();
-	vector<LaneHeight>* GetLeftHeigthVector();
-	vector<LaneRoadMark>* GetLeftRoadMarkVector();
-	vector<bool>* GetLeftLevelVector();
-
-	vector<string>* GetRightTypeVector();
-	vector<double>* GetRightWidthVector();
-	vector<LaneHeight>* GetRightHeigthVector();
-	vector<LaneRoadMark>* GetRightRoadMarkVector();
-	vector<bool>* GetRightLevelVector();
-
-
-	/*
-	* Clear the vectors
-	*/
-	void ClearVectors();
-
-};
-
-
-
-/**
-* Lane class. Holds all the record data that describes a lane
-*
-*
-*
-*
-*
-*/
-class Lane
-{
-private:
-	/**
-	*	Record parameters
-	*/
-	short int mSide; //0 = center, -1 = right, 1=left
-	int mId;
-	string mType; 
-	bool mLevel; //true or false(default)
-
-	//links
-	bool mPredecessorExists;
-	int mPredecessor;
-	bool mSuccessorExists;
-	int mSuccessor;
-
-	//Width
-	vector <LaneWidth> mLaneWidth;
-	//Road Mark
-	vector <LaneRoadMark> mLaneRoadMark;
-	//Lane Material
-	vector <LaneMaterial> mLaneMaterial;
-	//Lane Visibility
-	vector <LaneVisibility> mLaneVisibility;
-	//Lane Speed
-	vector <LaneSpeed> mLaneSpeed;
-	//Lane Access
-	vector<LaneAccess> mLaneAccess;
-	//Lane Height
-	vector<LaneHeight> mLaneHeight;
-
-
-	unsigned int mLastAddedLaneWidth;
-	unsigned int mLastAddedLaneRoadMark;
-	unsigned int mLastAddedLaneMaterial;
-	unsigned int mLastAddedLaneVisibility;
-	unsigned int mLastAddedLaneSpeed;
-	unsigned int mLastAddedLaneAccess;
-	unsigned int mLastAddedLaneHeight;
-
-public:
-	/**
-	*	Constructor
-	*/
-	Lane(short int side, int id, string type, bool level);
-	/**
-	*	Operator less, Used to sort the lanes
-	*/
-	bool operator<(Lane rhs)const { return (mId < rhs.mId); }
-
-
-	/**
-	*	Various set methods.
-	*/
-	void SetSide(short int side);
-	void SetId(int id);
-	void SetType(string type);
-	void SetLevel(bool level);
-	void SetPredecessor(int predecessor);
-	void SetSuccessor(int successor);
-
-	/**
-	*	Remove lane linkage methods.
-	*/
-	void RemovePredecessor();
-	void RemoveSuccessor();
-
-	/**
-	 * Methods used to add child records to the respective vectors
-	 */
-	unsigned int AddWidthRecord(double s, double a, double b, double c, double d);
-	unsigned int AddRoadMarkRecord(double sOffset, string type, string weight, string color, double width, string laneChange);
-	unsigned int AddMaterialRecord(double sOffset, string surface, double friction, double roughness);
-	unsigned int AddVisibilityRecord(double sOffset, double forward, double back, double left, double right);
-	unsigned int AddSpeedRecord(double sOffset, double max);
-	unsigned int AddAccessRecord(double sOffset, string restriction);
-	unsigned int AddHeightRecord(double sOffset, double inner, double outer);
-
-	/**
-	 * Methods used to clone child records in the respective vectors
-	 */
-	unsigned int CloneLaneWidth(unsigned int index);
-	unsigned int CloneLaneRoadMark(unsigned int index);
-	unsigned int CloneLaneMaterial(unsigned int index);
-	unsigned int CloneLaneVisibility(unsigned int index);
-	unsigned int CloneLaneSpeed(unsigned int index);
-	unsigned int CloneLaneAccess(unsigned int index);
-	unsigned int CloneLaneHeight(unsigned int index);
-
-	/**
-	 * Methods used to delete child records from the respective vectors
-	 */
-	void DeleteLaneWidth(unsigned int index);
-	void DeleteLaneRoadMark(unsigned int index);
-	void DeleteLaneMaterial(unsigned int index);
-	void DeleteLaneVisibility(unsigned int index);
-	void DeleteLaneSpeed(unsigned int index);
-	void DeleteLaneAccess(unsigned int index);
-	void DeleteLaneHeight(unsigned int index);
-
-
-	/**
-	*	Getters of the lane parameters
-	*/
-	int GetSide();
-	int GetId();
-	string GetType();
-	bool GetLevel();
-
-	/**
-	*	Check if linkage information is provided
-	*/
-	bool IsPredecessorSet();
-	int GetPredecessor();
-	bool IsSuccessorSet();
-	int GetSuccessor();
-
-	/**
-	*	Get pointers to the records vectors
-	*/
-	vector <LaneWidth> *GetLaneWidthVector();
-	vector <LaneRoadMark> *GetLaneRoadMarkVector();
-	vector <LaneMaterial> *GetLaneMaterialVector();
-	vector <LaneVisibility> *GetLaneVisibilityVector();
-	vector <LaneSpeed> *GetLaneSpeedVector();
-	vector <LaneAccess> *GetLaneAccessVector();
-	vector <LaneHeight> *GetLaneHeightVector();
-
-
-	/**
-	*	Get the number of elements in a certain vector
-	*/
-	unsigned int GetLaneWidthCount();
-	unsigned int GetLaneRoadMarkCount();
-	unsigned int GetLaneMaterialCount();
-	unsigned int GetLaneVisibilityCount();
-	unsigned int GetLaneSpeedCount();
-	unsigned int GetLaneAccessCount();
-	unsigned int GetLaneHeightCount();
-
-
-	/**
-	*	Get the elements of a certain vectors at position i
-	*/
-	LaneWidth* GetLaneWidth(unsigned int i); 
-	LaneRoadMark* GetLaneRoadMark(unsigned int i);
-	LaneMaterial* GetLaneMaterial(unsigned int i);
-	LaneVisibility* GetLaneVisibility(unsigned int i);
-	LaneSpeed* GetLaneSpeed(unsigned int i);
-	LaneAccess* GetLaneAccess(unsigned int i);
-	LaneHeight* GetLaneHeight(unsigned int i);
-
-
-	/**
-	*	Get the last elements of a certain vectors
-	*/
-	LaneWidth* GetLastLaneWidth(); 
-	LaneRoadMark* GetLastLaneRoadMark();
-	LaneMaterial* GetLastLaneMaterial();
-	LaneVisibility* GetLastLaneVisibility();
-	LaneSpeed* GetLastLaneSpeed();
-	LaneAccess* GetLastLaneAccess();
-	LaneHeight* GetLastLaneHeight();
-
-	/**
-	*	Get the last added elements of a certain vectors (their position might not be at the end of the vector)
-	*/
-	LaneWidth* GetLastAddedLaneWidth(); 
-	LaneRoadMark* GetLastAddedLaneRoadMark();
-	LaneMaterial* GetLastAddedLaneMaterial();
-	LaneVisibility* GetLastAddedLaneVisibility();
-	LaneSpeed* GetLastAddedLaneSpeed();
-	LaneAccess* GetLastAddedLaneAccess();
-	LaneHeight* GetLastAddedLaneHeight();
-
-	/**
-	*	Check the intervals and return the index of the records that applies to the provided s-offset
-	*/
-	int CheckWidthInterval(double s_check);
-	int CheckRoadMarkInterval(double s_check);
-	int CheckMaterialInterval(double s_check);
-	int CheckVisibilityInterval(double s_check);
-	int CheckSpeedInterval(double s_check);
-	int CheckAccessInterval(double s_check);
-	int CheckHeightInterval(double s_check);
-
-
-	/**
-	*	Evaluate the record and return the width value
-	*/
-	double GetWidthValue(double s_check);
-
-	/**
-	*	Evaluate the record and return the height object
-	*/
-	LaneHeight GetHeightValue(double s_check);
-
-	/**
-	*	Evaluate the road marks records and return the road mark object corresponding to the provided s-offset
-	*/
-	LaneRoadMark GetRoadMarkValue(double s_check);
-
-
-	/**
-	* Destructor
-	* Delete all the members of the vectors:
-	* mLaneWidth, mRoadMark, mLaneMaterial, mLaneVisibility, mLaneSpeed, mLaneAccess, mLaneHeight
-	*/
-	~Lane();
-	//--------------
-
-};
-
-/**
-* Lane width class. Holds all the data that describes a lane width
-*
-*
-*
-*
-*
-*/
-class LaneWidth : public ThirdOrderPolynom
-{
-public:
-
-	/**
-	* Constructor
-	* @param s s-offset of the record starting from the lane section s-offset
-	* @ param a,b,c,d The 4 parameters of the polynomial
-	*/
-	LaneWidth(double s, double a, double b, double c, double d);
-
-};
-
-/**
-* Road mark class. Holds all the data that describes a road mark
-*
-*
-*
-*
-*
-*/
-class LaneRoadMark
-{
-private:
-
-	/*
-	* Parameters of the road mark
-	*/
-	double mSOffset;
-	string mType;
-	string mWeight;
-	string mColor; 
-	double mWidth;
-	string mLaneChange;
-public:
-	/*
-	* Constructors
-	*/
-	LaneRoadMark();
-	LaneRoadMark(double sOffset, string type, string weight, string color, double width, string laneChange);
-	LaneRoadMark(double sOffset, string type, string weight, string color, double width);
-
-	/*
-	* Methods that set the parameters of the road mark
-	*/
-	void SetS(double value);
-	void SetType(string type);
-	void SetWeight(string weight);
-	void SetColor(string color);
-	void SetWidth(double value);
-	void SetLaneChange(string laneChange);
-
-	/*
-	* Methods that return the parameters of the road mark
-	*/
-	double GetS();
-	string GetType();
-	string GetWeight();
-	string GetColor();
-	double GetWidth();
-	string GetLaneChange();
-
-};
-
-/**
-* Lane material class. Contains all the data that describes a lane material
-*
-*
-*
-*
-*
-*/
-class LaneMaterial
-{
-private:
-	/*
-	* Parameters that describe the lane material
-	*/
-	double mSOffset;
-	string mSurface;
-	double mFriction;
-	double mRoughness;
-public:
-
-	/*
-	* Constructor
-	*/
-	LaneMaterial (double sOffset, string surface, double friction, double roughness);
-
-	/*
-	* Methods that return the parameters of the lane material
-	*/
-	double GetS();
-	string GetSurface();
-	double GetFriction();
-	double GetRoughness();
-
-	/*
-	* Methods that set the parameters of the lane material
-	*/
-	void SetS(double value);
-	void SetSurface(string surface);
-	void SetFriction(double value);
-	void SetRoughness(double value);
-
-};
-
-/**
-* Lane visibility class. Contains all the data that describes lane visibility record
-*
-*
-*
-*
-*
-*/
-class LaneVisibility
-{
-private:
-	/*
-	* Parameters that describe the lane visibility
-	*/
-	double mSOffset;
-	double mForward;
-	double mBack;
-	double mLeft;
-	double mRight;
-public:
-	/*
-	* Constructor
-	*/
-	LaneVisibility(double sOffset, double forward, double back, double left, double right);
-
-	/*
-	* Methods that return the parameters of the lane visibility
-	*/
-	double GetS();
-	double GetForward();
-	double GetBack();
-	double GetLeft();
-	double GetRight();
-
-	/*
-	* Methods that set the parameters of the lane visibility
-	*/
-	void SetS(double value);
-	void SetForward(double value);
-	void SetBack(double value);
-	void SetLeft(double value);
-	void SetRight(double value);
-
-};
-
-/**
-* Lane speed class. Contains all the data that describes lane speed record
-*
-*
-*
-*
-*
-*/
-class LaneSpeed
-{
-private:
-	/*
-	* Parameters that describe the lane speed
-	*/
-	double mSOffset;
-	double mMax;
-public:
-	/*
-	* Constructor
-	*/
-	LaneSpeed (double sOffset, double max);
-
-	/*
-	* Methods that return the parameters of the lane speed
-	*/
-	double GetS();
-	double GetMax();
-
-	/*
-	* Methods that set the parameters of the lane speed
-	*/
-	void SetS(double value);
-	void SetMax(double value);
-};
-
-/**
-* Lane access class. Contains all the data that describes lane access record
-*
-*
-*
-*
-*
-*/
-class LaneAccess
-{
-private:
-	/*
-	* Parameters that describe the lane access
-	*/
-	double mSOffset;
-	string mRestriction;
-public:
-	/*
-	* Constructor
-	*/
-	LaneAccess (double sOffset, string restriction);
-
-	/*
-	* Methods that return the parameters of the lane access
-	*/
-	double GetS();
-	string GetRestriction();
-
-	/*
-	* Methods that set the parameters of the lane access
-	*/
-	void SetS(double value);
-	void SetRestriction(string restriction);
-};
-
-/**
-* Lane height class. Contains all the data that describes lane access record
-*
-*
-*
-*
-*
-*/
-class LaneHeight
-{
-private:
-	/*
-	* Parameters that describe the lane height
-	*/
-	double mSOffset;
-	double mInner;
-	double mOuter;
-public:
-	/*
-	* Constructors
-	*/
-	LaneHeight();
-	LaneHeight (double sOffset, double inner, double outer);
-
-	/*
-	* Methods that return the parameters of the lane height
-	*/
-	double GetS();
-	double GetInner();
-	double GetOuter();
-
-	/*
-	* Methods that set the parameters of the lane height
-	*/
-	void SetS(double value);
-	void SetInner(double value);
-	void SetOuter(double value);
-};
-
-//----------------------------------------------------------------------------------
-
-
-#endif

+ 0 - 0
src/tool/tool_xodrobj/OpenDrive/ObjectSignal.cpp


+ 0 - 28
src/tool/tool_xodrobj/OpenDrive/ObjectSignal.h

@@ -1,28 +0,0 @@
-#ifndef OBJECTSIGNAL_H
-#define OBJECTSIGNAL_H
-
-
-
-//***********************************************************************************
-//Object
-//***********************************************************************************
-class Object
-{
-public:
-	Object(){}
-};
-//----------------------------------------------------------------------------------
-
-
-//***********************************************************************************
-//Signal
-//***********************************************************************************
-class Signal
-{
-public:
-	Signal(){}
-};
-//----------------------------------------------------------------------------------
-
-
-#endif

+ 0 - 301
src/tool/tool_xodrobj/OpenDrive/OpenDrive.cpp

@@ -1,301 +0,0 @@
-#include "OpenDrive.h"
-
-
-//***********************************************************************************
-//OpenDRIVE Structure
-//***********************************************************************************
-/**
- * Constructor
- */
-OpenDrive::OpenDrive()
-{
-	mHeader=NULL;
-}
-
-
-/**
- * Sets the header of the OpenDrive file
- */
-void OpenDrive::SetHeader(unsigned short int revMajor, unsigned short int revMinor, string name, float version, string date, 
-						  double north, double south, double east,double west)
-{	
-	if (mHeader==NULL)
-		mHeader=new Header(revMajor, revMinor, name, version, date, north, south, east, west);
-	else
-	{
-		mHeader->SetAllParams(revMajor, revMinor, name, version, date, north, south, east, west);
-	}
-
-}
-
-void OpenDrive::SetHeader(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)
-{
-    if (mHeader==NULL)
-        mHeader=new Header(revMajor, revMinor, name, version, date, north, south, east, west,lat0,lon0,hdg0);
-    else
-    {
-        mHeader->SetAllParams(revMajor, revMinor, name, version, date, north, south, east, west,lat0,lon0,hdg0);
-    }
-
-}
-
-/**
- * Methods used to add records to the respective vectors
- */
-unsigned int OpenDrive::AddRoad(string name, double length, string id, string junction)
-{
-	unsigned int index=GetRoadCount();
-	// Adds the new road to the end of the vector
-	mRoadVector.push_back(Road(name, length, id, junction));
-	// Saves the index of the newly added road
-	mLastAddedRoad=index;
-	return index;
-}
-unsigned int OpenDrive::AddJunction(string name, string id)
-{
-	unsigned int index=GetJunctionCount();
-	// Adds the new junction to the end of the vector
-	mJunctionVector.push_back(Junction(name,id));
-	// Saves the index of the newly added junction
-	mLastAddedJunction=index;
-	return index;
-}
-
-/**
- * Methods used to delete records from the respective vectors
- */
-void OpenDrive::DeleteRoad(unsigned int index)
-{
-	mRoadVector.erase(mRoadVector.begin()+index);
-}
-void OpenDrive::DeleteJunction(unsigned int index)
-{
-	mJunctionVector.erase(mJunctionVector.begin()+index);
-}
-
-//-------------------------------------------------
-
-/**
- * Getters for the last child records in their respective vectors
- */
-Road* OpenDrive::GetLastRoad()
-{	
-	if (mRoadVector.size()>0)
-		return &(mRoadVector.at(mRoadVector.size()-1));
-	else
-		return NULL;
-}
-Junction* OpenDrive::GetLastJunction()
-{
-	if (mJunctionVector.size()>0)
-		return &(mJunctionVector.at(mJunctionVector.size()-1));
-	else
-		return NULL;
-}
-
-/**
- * Getters for the last added records in their respective vectors
- */
-Road* OpenDrive::GetLastAddedRoad()
-{	
-	if(mLastAddedRoad<mRoadVector.size())
-		return &mRoadVector.at(mLastAddedRoad);
-	else
-		return NULL;
-}
-
-/**
- * Getter for the OpenDrive header
- */
-Header* OpenDrive::GetHeader()
-{ 
-	return mHeader;
-}
-
-/**
- * Getters for the records and their vectors
- */
-// Road records
-vector<Road> * OpenDrive::GetRoadVector()
-{
-	return &mRoadVector;
-}
-Road* OpenDrive::GetRoad(unsigned int i)
-{	
-	if ((i < mRoadVector.size())&&( mRoadVector.size()>0))
-		return &(mRoadVector.at(i));	
-	else
-		return NULL;
-}
-unsigned int OpenDrive::GetRoadCount()
-{	
-	return mRoadVector.size();	
-}
-// Junction records
-vector<Junction> * OpenDrive::GetJunctionVector()
-{
-	return &mJunctionVector;
-}
-Junction* OpenDrive::GetJunction(unsigned int i)
-{	if (i < mJunctionVector.size())
-		return &(mJunctionVector.at(i));
-	else
-		return NULL;
-}
-unsigned int OpenDrive::GetJunctionCount()
-{	
-	return mJunctionVector.size();	
-}
-//-------------------------------------------------
-
-/**
- * Clears the OpenDrive structure, could be used to start a new document
- */
-void OpenDrive::Clear()
-{
-	mRoadVector.clear();
-	mJunctionVector.clear();
-}
-
-/**
- * Destructor
- */
-OpenDrive::~OpenDrive()
-{
-	if (mHeader!=NULL)
-		delete mHeader;
-
-	// DELETING ROADS
-	mRoadVector.clear();
-
-	// DELETING JUNCTIONS
-	mJunctionVector.clear();
-}
-
-
-//***********************************************************************************
-//Header
-//***********************************************************************************
-/**
- * Constructor that initializes the base properties
- */
-Header::Header(unsigned short int revMajor, unsigned short int revMinor, string name, float version, string date, 
-			   double north, double south, double east,double west)
-{
-	mRevMajor=revMajor;
-	mRevMinor=revMinor;
-	mName=name;
-	mVersion=version;
-	mDate=date;
-	mNorth=north;
-	mSouth=south;
-	mEast=east;
-	mWest=west;
-
-}
-
-Header::Header(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)
-{
-    mRevMajor=revMajor;
-    mRevMinor=revMinor;
-    mName=name;
-    mVersion=version;
-    mDate=date;
-    mNorth=north;
-    mSouth=south;
-    mEast=east;
-    mWest=west;
-
-    mLat0=lat0;
-    mLon0=lon0;
-    mHdg0=hdg0;
-
-}
-
-/**
- * Getter for all properties
- */
-void Header::GetAllParams(unsigned short int &revMajor, unsigned short int &revMinor, string &name, float &version, string &date, 
-						  double &north, double &south, double &east,double &west)
-{
-	revMajor=mRevMajor;
-	revMinor=mRevMinor;
-	name=mName;
-	version=mVersion;
-	date=mDate;
-	north=mNorth;
-	south=mSouth;
-	east=mEast;
-	west=mWest;
-
-}
-
-void Header::GetAllParams(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)
-{
-    revMajor=mRevMajor;
-    revMinor=mRevMinor;
-    name=mName;
-    version=mVersion;
-    date=mDate;
-    north=mNorth;
-    south=mSouth;
-    east=mEast;
-    west=mWest;
-    lat0=mLat0;
-    lon0=mLon0;
-    hdg0=mHdg0;
-
-}
-
-
-void Header::GetXYValues(double &north, double &south, double &east,double &west)
-{
-	north=mNorth;
-	south=mSouth;
-	east=mEast;
-	west=mWest;
-}
-
-/**
- * Setter for all properties
- */
-void Header::SetAllParams(unsigned short int revMajor, unsigned short int revMinor, string name, float version, string date, 
-						  double north, double south, double east,double west)
-{
-	mRevMajor=revMajor;
-	mRevMinor=revMinor;
-	mName=name;
-	mVersion=version;
-	mDate=date;
-	mNorth=north;
-	mSouth=south;
-	mEast=east;
-	mWest=west;
-}
-
-void Header::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)
-{
-    mRevMajor=revMajor;
-    mRevMinor=revMinor;
-    mName=name;
-    mVersion=version;
-    mDate=date;
-    mNorth=north;
-    mSouth=south;
-    mEast=east;
-    mWest=west;
-    mLat0=lat0;
-    mLon0=lon0;
-    mHdg0=hdg0;
-}
-void Header::SetXYValues(double north, double south, double east,double west)
-{
-	mNorth=north;
-	mSouth=south;
-	mEast=east;
-	mWest=west;
-}

+ 0 - 187
src/tool/tool_xodrobj/OpenDrive/OpenDrive.h

@@ -1,187 +0,0 @@
-#ifndef OPENDRIVE_H
-#define OPENDRIVE_H
-
-#include <vector>
-#include <string>
-
-#include "Road.h"
-//--Prototypes--
-//main
-class Header;
-//--------------
-
-
-using std::vector;
-using std::string;
-
-
-/**
- * The main class in OpenDrive structure
- * Holds the two vectors of the top-level records: ROAD and JUNCTION
- * Has methods to add, get and delete those records
- * From this class - one could get access to any record in OpenDrive structure
- * going down the hierarchy
- */
-class OpenDrive
-{
-private:
-	/**
-	 * Header of the OpenDrive file
-	 */
-	Header* mHeader;
-
-	/**
-	 * Vectors used to store the top-level ROAD and JUNCTION records
-	 */
-	vector<Road> mRoadVector;
-	vector<Junction> mJunctionVector;
-	
-	/**
-	 * Indices of the last added records
-	 */
-	unsigned int mLastAddedRoad;
-	unsigned int mLastAddedJunction;
-
-	//-------------------------------------------------
-
-	/**
-	 * Copy constructor, makes the object non-copyable
-	 */
-	OpenDrive (const OpenDrive& openDrive){};
-	const OpenDrive& operator=(const OpenDrive& rhs){};
-
-public:
-	/**
-	 * Constructor
-	 */
-	OpenDrive();
-
-	//-------------------------------------------------
-
-	/**
-	 * Sets the header of the OpenDrive file
-	 */
-	void SetHeader(unsigned short int revMajor, unsigned short int revMinor, string name, float version, string date, 
-					double north, double south, double east,double west);
-
-    /**
-     * Sets the header of the OpenDrive file  Added by Yuchuli,2019.11.04
-     */
-    void SetHeader(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);
-	
-	/**
-	 * Methods used to add records to the respective vectors
-	 */
-	unsigned int AddRoad(string name, double length, string id, string junction);
-	unsigned int AddJunction(string name, string id);
-
-	/**
-	 * Methods used to delete records from the respective vectors
-	 */
-	void DeleteRoad(unsigned int index);
-	void DeleteJunction(unsigned int index);
-
-	//-------------------------------------------------
-
-	/**
-	 * Getters for the last child records in their respective vectors
-	 */
-	Road* GetLastRoad();
-	Junction* GetLastJunction();
-
-	/**
-	 * Getters for the last added records in their respective vectors
-	 */
-	Road* GetLastAddedRoad();
-
-	/**
-	 * Getter for the OpenDrive header
-	 */
-	Header* GetHeader();
-
-	/**
-	 * Getters for the records and their vectors
-	 */
-	// Road records
-	vector<Road> * GetRoadVector();
-	Road* GetRoad(unsigned int i);
-	unsigned int GetRoadCount();
-	// Junction records
-	vector<Junction> * GetJunctionVector();
-	Junction* GetJunction(unsigned int i);
-	unsigned int GetJunctionCount();
-	
-	//-------------------------------------------------
-
-
-	/**
-	 * Clears the OpenDrive structure, could be used to start a new document
-	 */
-	void Clear();
-
-
-	/**
-	 * Destructor
-	 */
-	~OpenDrive();
-};
-
-
-
-/**
- * Class used to store the heading details of the OpenDrive file
- */
-class Header
-{
-private:
-	/**
-	 * Base properties
-	 */
-	unsigned short int mRevMajor;
-	unsigned short int mRevMinor;
-	string mName;
-	float mVersion;
-	string mDate;
-	double mNorth;
-	double mSouth;
-	double mEast;
-	double mWest;
-
-    //Added by Yuchuli,2019.11.04
-    double mLat0;
-    double mLon0;
-    double mHdg0;
-
-public:
-	/**
-	 * Constructor that initializes the base properties
-	 */
-	Header(unsigned short int revMajor, unsigned short int revMinor, string name, float version, string date, 
-		double north, double south, double east,double west);
-
-    Header(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);
-	
-	/**
-	 * Getter for all properties
-	 */
-	void GetAllParams(unsigned short int &revMajor, unsigned short int &revMinor, string &name, float &version, string &date, 
-		double &north, double &south, double &east,double &west);
-    void GetAllParams(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);
-	void GetXYValues(double &north, double &south, double &east,double &west);
-	
-	/**
-	 * Setter for all properties
-	 */
-	void SetAllParams(unsigned short int revMajor, unsigned short int revMinor, string name, float version, string date, 
-		double north, double south, double east,double west);
-	void SetXYValues(double north, double south, double east,double west);
-
-    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);
-};
-
-
-#endif

+ 0 - 1112
src/tool/tool_xodrobj/OpenDrive/OpenDriveXmlParser.cpp

@@ -1,1112 +0,0 @@
-#include "OpenDriveXmlParser.h"
-#include <iostream>
-#include <algorithm>
-//#include "windows.h"
-
-using std::cout;
-using std::endl;
-
-/**
- * Constructor which saves a reference to OpenDrive structure
- */
-OpenDriveXmlParser::OpenDriveXmlParser (OpenDrive* openDriveObj)
-{	
-	mOpenDrive=openDriveObj;	
-}
-
-/**
- * The following methods are used to read the data from the XML file and fill in the the OpenDrive structure
- * Methods follow the hierarchical structure and are called automatically when ReadFile is executed
- */
-bool OpenDriveXmlParser::ReadHeader(TiXmlElement *node)
-{
-	//Read the Header
-	unsigned short int revMajor;
-	unsigned short int revMinor;
-	string name;
-	float version;
-	string date;
-	double north;
-	double south;
-	double east;
-	double west;
-
-    //Added By Yuchuli,2019.11.04
-    double lat0;
-    double lon0;
-    double hdg0;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryValueAttribute<unsigned short int>("revMajor",&revMajor);
-	checker+=node->QueryValueAttribute<unsigned short int>("revMinor",&revMinor);
-	checker+=node->QueryStringAttribute("name",&name);
-	checker+=node->QueryFloatAttribute("version",&version);
-	checker+=node->QueryStringAttribute("date",&date);
-	checker+=node->QueryDoubleAttribute("north",&north);
-	checker+=node->QueryDoubleAttribute("south",&south);
-	checker+=node->QueryDoubleAttribute("east",&east);
-	checker+=node->QueryDoubleAttribute("west",&west);
-
-
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Header attributes"<<endl;
-		return false;
-	}
-
-    checker+=node->QueryDoubleAttribute("lat0",&lat0);
-    checker+=node->QueryDoubleAttribute("lon0",&lon0);
-    checker+=node->QueryDoubleAttribute("hdg0",&hdg0);
-
-    mOpenDrive->SetHeader(revMajor, revMinor, name, version, date, north, south, east, west,lat0,lon0,hdg0);
-
-	return true;
-
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadRoad(TiXmlElement *node)
-{
-	//Read road attributes
-	string name;
-	double length;
-	string id;
-	string junction;
-
-	int checker=TIXML_SUCCESS;
-	
-	checker+=node->QueryStringAttribute("name",&name);
-	checker+=node->QueryDoubleAttribute("length",&length);
-	checker+=node->QueryStringAttribute("id",&id);
-	checker+=node->QueryStringAttribute("junction",&junction);
-
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Road attributes"<<endl;
-		return false;
-	}
-	//fill in
-	mOpenDrive->AddRoad(name, length, id, junction);
-	Road* road = mOpenDrive->GetLastAddedRoad();
-	TiXmlElement* subNode;
-
-
-	//Get links
-	subNode=node->FirstChildElement("link");
-	if (subNode)
-	{
-		ReadRoadLinks (road,subNode);
-	}	
-
-	//Proceed to road Type
-	subNode=node->FirstChildElement("type");
-	while (subNode)
-	{
-		ReadRoadType(road, subNode);
-		subNode=subNode->NextSiblingElement("type");
-	}
-
-	//Proceed to planView
-	subNode=node->FirstChildElement("planView");
-	ReadPlanView(road, subNode);
-
-	//Proceed to ElevationProfile
-	subNode=node->FirstChildElement("elevationProfile");
-	if (subNode)
-	{
-		ReadElevationProfile(road, subNode);
-	}
-
-	//Proceed to LateralProfile
-	subNode=node->FirstChildElement("lateralProfile");
-	if (subNode)
-	{
-		ReadLateralProfile(road, subNode);
-	}
-
-	//Proceed to Lanes
-	subNode=node->FirstChildElement("lanes");
-	ReadLanes(road, subNode);
-
-	//Proceed to Objects
-	subNode=node->FirstChildElement("objects");
-	if (subNode)
-	{
-		ReadObjects(road, subNode);
-	}
-
-	//Proceed to Signals
-	subNode=node->FirstChildElement("signals");
-	if (subNode)
-	{
-		ReadSignals(road, subNode);
-	}
-
-	//Proceed to Surface
-	subNode=node->FirstChildElement("surface");
-	if (subNode)
-	{
-		ReadSurface(road, subNode);
-	}
-
-	return true;
-}
-//--------------
-
-bool  OpenDriveXmlParser::ReadRoadLinks (Road* road, TiXmlElement *node)
-{
-	TiXmlElement* subNode;
-	subNode=node->FirstChildElement("predecessor");
-	if (subNode)
-	{
-		ReadRoadLink(road, subNode,0);
-	}
-
-	subNode=node->FirstChildElement("successor");
-	if (subNode)
-	{
-		ReadRoadLink(road, subNode,1);
-	}
-
-	subNode=node->FirstChildElement("neighbor");
-	if (subNode)
-	{
-		ReadRoadLink(road, subNode,2);
-	}
-
-	subNode=node->NextSiblingElement("neighbor");
-	if (subNode)
-	{
-		ReadRoadLink(road, subNode,2);
-	}
-
-	return true;
-}
-//--------------
-
-bool  OpenDriveXmlParser::ReadRoadLink (Road* road, TiXmlElement *node, short int type)
-{
-	//all three types (neighbor, successor or predecessor) have the same number and same types of members,
-	//but in case this changes in future, load it separately
-	if (type == 0)
-	{
-		string elementType; 
-		string elementId;
-		string contactPoint="NA";
-
-		int checker=TIXML_SUCCESS;
-		checker+=node->QueryStringAttribute("elementType",&elementType);
-		checker+=node->QueryStringAttribute("elementId",&elementId);
-		if (elementType.compare("road")==0)
-			checker+=node->QueryStringAttribute("contactPoint",&contactPoint);
-
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing Predecessor attributes"<<endl;
-			return false;
-		}
-		road->SetPredecessor(elementType,elementId,contactPoint);
-		return true;
-
-	}
-	else if (type == 1)
-	{
-		string elementType; 
-		string elementId;
-		string contactPoint="NA";
-
-		int checker=TIXML_SUCCESS;
-		checker+=node->QueryStringAttribute("elementType",&elementType);
-		checker+=node->QueryStringAttribute("elementId",&elementId);
-		if (elementType.compare("road")==0)
-			checker+=node->QueryStringAttribute("contactPoint",&contactPoint);
-
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing Successor attributes"<<endl;
-			return false;
-		}
-		road->SetSuccessor(elementType,elementId,contactPoint);
-		return true;
-	}
-
-	else if (type == 2)
-	{
-		string side; 
-		string elementId;
-		string direction;
-
-		int checker=TIXML_SUCCESS;
-		checker+=node->QueryStringAttribute("side",&side);
-		checker+=node->QueryStringAttribute("elementId",&elementId);
-		checker+=node->QueryStringAttribute("direction",&direction);
-
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing Neighbor attributes"<<endl;
-			return false;
-		}
-		road->SetNeighbor(side,elementId,direction);
-		return true;
-	}
-
-	return false;
-		
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadRoadType (Road* road, TiXmlElement *node)
-{
-	double s;
-	string type;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("s",&s);
-	checker+=node->QueryStringAttribute("type",&type);
-
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Road Type attributes"<<endl;
-		return false;
-	}
-
-	road->AddRoadType(s,type);
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadPlanView(Road* road, TiXmlElement *node)
-{
-	//Get geometry
-	TiXmlElement* subNode;
-	TiXmlElement* subNodeType;
-	subNode=node->FirstChildElement("geometry");
-	
-	while (subNode)
-	{
-		subNodeType=subNode->FirstChildElement();
-		if (subNodeType->ValueStr().compare("line")==0)
-		{
-			ReadGeometryBlock(road, subNode,0);		//load a straight block
-		}
-		else if (subNodeType->ValueStr().compare("spiral")==0)
-		{
-			ReadGeometryBlock(road, subNode,1);		//load a turn block
-		}
-        else if (subNodeType->ValueStr().compare("arc")==0)
-        {
-            ReadGeometryBlock(road, subNode,2);		//load a turn block
-        }
-		else if (subNodeType->ValueStr().compare("poly3")==0)
-		{
-            ReadGeometryBlock(road, subNode,3);		//load a polynom spline block
-		}       
-        else if (subNodeType->ValueStr().compare("paramPoly3")==0)
-        {
-            ReadGeometryBlock(road, subNode,4);		//load a polynom spline block
-        }
-			
-
-		subNode=subNode->NextSiblingElement("geometry");
-
-	}
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadGeometryBlock (Road* road, TiXmlElement *&node, short int blockType)
-{
-	road->AddGeometryBlock();
-	GeometryBlock* geomBlock=road->GetLastAddedGeometryBlock();
-	switch (blockType)
-	{
-	case 0:
-		ReadGeometry(geomBlock, node, 0);
-		break;
-	case 1:
-		ReadGeometry(geomBlock, node, 1);
-//		node=node->NextSiblingElement("geometry");
-//		ReadGeometry(geomBlock, node, 2);
-//		node=node->NextSiblingElement("geometry");
-//		ReadGeometry(geomBlock, node, 1);
-		break;
-	case 2:
-        ReadGeometry(geomBlock, node, 2);
-		break;
-    case 3:
-        ReadGeometry(geomBlock, node, 3);
-        break;
-    case 4:
-        ReadGeometry(geomBlock, node, 4);
-        break;
-    default:
-        break;
-	}
-
-	return true;
-	
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadGeometry(GeometryBlock* geomBlock, TiXmlElement *node, short int geometryType)
-{
-	double s, x, y, hdg, length;
-	//read the geometry node
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("s",&s);
-	checker+=node->QueryDoubleAttribute("x",&x);
-	checker+=node->QueryDoubleAttribute("y",&y);
-	checker+=node->QueryDoubleAttribute("hdg",&hdg);
-	checker+=node->QueryDoubleAttribute("length",&length);
-
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Geometry attributes"<<endl;
-		return false;
-	}
-
-	TiXmlElement *subNode=node->FirstChildElement();
-
-	//read the type nodes
-	switch ( geometryType )
-      {
-	case 0:		//line
-		geomBlock->AddGeometryLine(s,x,y,hdg,length);
-		break;
-	case 1:		//spiral
-		checker=TIXML_SUCCESS;
-		double curvatureStart, curvatureEnd; 
-		checker+=subNode->QueryDoubleAttribute("curvStart",&curvatureStart);
-		checker+=subNode->QueryDoubleAttribute("curvEnd",&curvatureEnd);
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing spiral attributes"<<endl;
-			return false;
-		}
-		geomBlock->AddGeometrySpiral(s,x,y,hdg,length,curvatureStart,curvatureEnd);
-		break;
-	case 2:		//arc
-		checker=TIXML_SUCCESS;
-		double curvature;
-		checker+=subNode->QueryDoubleAttribute("curvature",&curvature);
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing arc attributes"<<endl;
-			return false;
-		}
-		geomBlock->AddGeometryArc(s,x,y,hdg,length,curvature);
-		break;
-
-
-	case 3:		//poly3
-		checker=TIXML_SUCCESS;
-		double a,b,c,d;
-		checker+=subNode->QueryDoubleAttribute("a",&a);
-		checker+=subNode->QueryDoubleAttribute("b",&b);
-		checker+=subNode->QueryDoubleAttribute("c",&c);
-		checker+=subNode->QueryDoubleAttribute("d",&d);
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing arc attributes"<<endl;
-			return false;
-		}
-
-		geomBlock->AddGeometryPoly3(s,x,y,hdg,length,a,b,c,d);
-		break;
-
-    case 4:		//parampoly3,add by Yuchuli 2019.11.1
-        checker=TIXML_SUCCESS;
-        double ua,ub,uc,ud,va,vb,vc,vd;
-        checker+=subNode->QueryDoubleAttribute("aU",&ua);
-        checker+=subNode->QueryDoubleAttribute("bU",&ub);
-        checker+=subNode->QueryDoubleAttribute("cU",&uc);
-        checker+=subNode->QueryDoubleAttribute("dU",&ud);
-        checker+=subNode->QueryDoubleAttribute("aV",&va);
-        checker+=subNode->QueryDoubleAttribute("bV",&vb);
-        checker+=subNode->QueryDoubleAttribute("cV",&vc);
-        checker+=subNode->QueryDoubleAttribute("dV",&vd);
-        if (checker!=TIXML_SUCCESS)
-        {
-            cout<<"Error parsing arc attributes"<<endl;
-            return false;
-        }
-
-        geomBlock->AddGeometryParamPoly3(s,x,y,hdg,length,ua,ub,uc,ud,va,vb,vc,vd);
-        break;
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadElevationProfile (Road* road, TiXmlElement *node)
-{
-	TiXmlElement* subNode;
-	subNode=node->FirstChildElement("elevation");
-	double s, a, b, c, d;
-	while (subNode)
-	{
-		int checker=TIXML_SUCCESS;
-		checker+=subNode->QueryDoubleAttribute("s",&s);
-		checker+=subNode->QueryDoubleAttribute("a",&a);
-		checker+=subNode->QueryDoubleAttribute("b",&b);
-		checker+=subNode->QueryDoubleAttribute("c",&c);
-		checker+=subNode->QueryDoubleAttribute("d",&d);
-
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing Elevation attributes"<<endl;
-			return false;
-		}
-
-		road->AddElevation(s,a,b,c,d);
-
-		subNode=subNode->NextSiblingElement("elevation");
-	}
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLateralProfile (Road* road, TiXmlElement *node)
-{
-	TiXmlElement* subNode;
-	subNode=node->FirstChildElement("superelevation");
-	double s, a, b, c, d;
-	while (subNode)
-	{
-		int checker=TIXML_SUCCESS;
-		checker+=subNode->QueryDoubleAttribute("s",&s);
-		checker+=subNode->QueryDoubleAttribute("a",&a);
-		checker+=subNode->QueryDoubleAttribute("b",&b);
-		checker+=subNode->QueryDoubleAttribute("c",&c);
-		checker+=subNode->QueryDoubleAttribute("d",&d);
-
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing Superelevation attributes"<<endl;
-			return false;
-		}
-
-		road->AddSuperElevation(s,a,b,c,d);
-
-		subNode=subNode->NextSiblingElement("superelevation");
-	}
-
-	subNode=node->FirstChildElement("crossfall");
-	string side;
-	while (subNode)
-	{
-		int checker=TIXML_SUCCESS;
-		checker+=subNode->QueryStringAttribute("side",&side);
-		checker+=subNode->QueryDoubleAttribute("s",&s);
-		checker+=subNode->QueryDoubleAttribute("a",&a);
-		checker+=subNode->QueryDoubleAttribute("b",&b);
-		checker+=subNode->QueryDoubleAttribute("c",&c);
-		checker+=subNode->QueryDoubleAttribute("d",&d);
-
-		if (checker!=TIXML_SUCCESS)
-		{
-			cout<<"Error parsing Crossfall attributes"<<endl;
-			return false;
-		}
-
-		road->AddCrossfall(side,s,a,b,c,d);
-
-		subNode=subNode->NextSiblingElement("crossfall");
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLanes (Road* road, TiXmlElement *node)
-{
-	TiXmlElement *subNode = node->FirstChildElement("laneSection");
-	while (subNode)
-	{
-		ReadLaneSections(road, subNode);
-		subNode=subNode->NextSiblingElement("laneSection");
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLaneSections (Road* road, TiXmlElement *node)
-{
-
-	int checker=TIXML_SUCCESS;
-	double s;
-	checker+=node->QueryDoubleAttribute("s",&s);
-
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane Section attributes"<<endl;
-		return false;
-	}
-
-	
-	road->AddLaneSection(s);
-	LaneSection* laneSection=road->GetLastAddedLaneSection();
-	TiXmlElement *subNode=node->FirstChildElement("left");
-	if (subNode)
-	{
-		subNode=subNode->FirstChildElement("lane");
-		while(subNode)
-		{
-			
-			ReadLane(laneSection,subNode,1);	//0 for left
-			subNode=subNode->NextSiblingElement("lane");
-		}
-
-	}
-
-	subNode=node->FirstChildElement("center");
-	if (subNode)
-	{
-		subNode=subNode->FirstChildElement("lane");
-		while(subNode)
-		{
-			
-			ReadLane(laneSection,subNode,0);	//1 for center	
-			subNode=subNode->NextSiblingElement("lane");
-		}
-	}
-
-	subNode=node->FirstChildElement("right");
-	if (subNode)
-	{
-		subNode=subNode->FirstChildElement("lane");
-		while(subNode)
-		{
-			
-			ReadLane(laneSection,subNode,-1);	//2 for right	
-			subNode=subNode->NextSiblingElement("lane");
-		}
-	}
-
-
-	//OutputDebugString( "\n") ;
-	for (unsigned int i=0;i<laneSection->GetLaneVector()->size();i++)
-	{
-		int id = static_cast<Lane>(laneSection->GetLaneVector()->at(i)).GetId();
-
-		/*char* buf;
-		buf=new char[5];
-		itoa(id,buf,10);
-
-		OutputDebugString( buf ) ;
-		OutputDebugString( " ") ;*/
-	}
-	//OutputDebugString( "\n") ;
-
-
-	//sort in descending order
-	std::sort(laneSection->GetLaneVector()->begin(),laneSection->GetLaneVector()->end());
-	std::reverse(laneSection->GetLaneVector()->begin(),laneSection->GetLaneVector()->end());
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLane (LaneSection* laneSection, TiXmlElement *node, short int laneType)
-{
-	//Read Lane attributes
-	short int side=laneType;
-	int id;
-	string type; 
-	string level; 
-	bool boolLevel;
-	int predecessor;
-	int successor;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryIntAttribute("id",&id);
-	checker+=node->QueryStringAttribute("type",&type);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane attributes"<<endl;
-		return false;
-	}
-	//in case "level" is missing, apply default value
-	checker=node->QueryStringAttribute("level",&level);
-	if (checker!=TIXML_SUCCESS)
-	{	level="false"; }
-
-	//convert level to bool
-
-	if (level.compare("false")==0 || level.compare("0")==0)
-		boolLevel=false;
-	else
-		boolLevel=true;
-
-	//pointer to the lane
-	Lane* lane; 
-	//Depending on the laneType, add it to the appropriate vector and get a pointer to it
-
-	laneSection->AddLane(side,id,type,boolLevel,false);
-	lane=laneSection->GetLastAddedLane();
-
-
-	//Read Link parameters and add them to the lane if available
-	TiXmlElement *subNode=node->FirstChildElement("link");
-	TiXmlElement *subSubNode;
-	if (subNode)
-		subSubNode=subNode->FirstChildElement("predecessor");
-			if (subSubNode)
-			{
-				checker=subSubNode->QueryIntAttribute("id",&predecessor);
-				if (checker==TIXML_SUCCESS)
-					lane->SetPredecessor(predecessor);
-			}
-	if (subNode)
-		subSubNode=subNode->FirstChildElement("successor");
-			if (subSubNode)
-			{
-				checker=subSubNode->QueryIntAttribute("id",&successor);
-				if (checker==TIXML_SUCCESS)
-					lane->SetSuccessor(successor);
-			}
-
-	//Proceed to the Road width
-	subNode=node->FirstChildElement("width");
-	while (subNode)
-	{
-		ReadLaneWidth(lane, subNode);
-		subNode=subNode->NextSiblingElement("width");
-	}
-
-	//Proceed to the Road Mark
-	subNode=node->FirstChildElement("roadMark");
-	while (subNode)
-	{
-		ReadLaneRoadMark(lane, subNode);
-		subNode=subNode->NextSiblingElement("roadMark");
-	}
-
-	//Proceed to the Lane Material
-	subNode=node->FirstChildElement("material");
-	while (subNode)
-	{
-		ReadLaneMaterial(lane, subNode);
-		subNode=subNode->NextSiblingElement("material");
-	}
-
-	//Proceed to the Lane Visibility
-	subNode=node->FirstChildElement("visibility");
-	while (subNode)
-	{
-		ReadLaneVisibility(lane, subNode);
-		subNode=subNode->NextSiblingElement("visibility");
-	}
-
-	//Proceed to the Lane speed
-	subNode=node->FirstChildElement("speed");
-	while (subNode)
-	{
-		ReadLaneSpeed(lane, subNode);
-		subNode=subNode->NextSiblingElement("speed");
-	}
-
-	//Proceed to the Lane access
-	subNode=node->FirstChildElement("access");
-	while (subNode)
-	{
-		ReadLaneAccess(lane, subNode);
-		subNode=subNode->NextSiblingElement("access");
-	}
-
-	//Proceed to the Lane height
-	subNode=node->FirstChildElement("height");
-	while (subNode)
-	{
-		ReadLaneHeight(lane, subNode);
-		subNode=subNode->NextSiblingElement("height");
-	}
-
-	return true;
-}
-//--------------
-
-
-bool OpenDriveXmlParser::ReadLaneWidth(Lane* lane, TiXmlElement *node)
-{
-	double sOffset, a, b, c, d;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("sOffset",&sOffset);
-	checker+=node->QueryDoubleAttribute("a",&a);
-	checker+=node->QueryDoubleAttribute("b",&b);
-	checker+=node->QueryDoubleAttribute("c",&c);
-	checker+=node->QueryDoubleAttribute("d",&d);
-
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane Weight attributes"<<endl;
-		return false;
-	}
-
-	lane->AddWidthRecord(sOffset,a,b,c,d);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLaneRoadMark(Lane* lane, TiXmlElement *node)
-{
-	
-	double sOffset;
-	string type;
-	string weight;
-	string color; 
-	double width;
-	string laneChange;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("sOffset",&sOffset);
-	checker+=node->QueryStringAttribute("type",&type);
-	checker+=node->QueryStringAttribute("weight",&weight);
-	checker+=node->QueryStringAttribute("color",&color);
-	
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane Weight attributes"<<endl;
-		return false;
-	}
-
-	checker+=node->QueryDoubleAttribute("width",&width);
-	if (checker!=TIXML_SUCCESS)
-	{	width=0;	}
-
-	checker=node->QueryStringAttribute("laneChange",&laneChange);
-	if (checker!=TIXML_SUCCESS)
-	{	laneChange = "both"; }
-
-	lane->AddRoadMarkRecord(sOffset,type,weight,color,width,laneChange);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLaneMaterial(Lane* lane, TiXmlElement *node)
-{
-	double sOffset;
-	string surface;
-	double friction;
-	double roughness;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("sOffset",&sOffset);
-	checker+=node->QueryStringAttribute("surface",&surface);
-	checker+=node->QueryDoubleAttribute("friction",&friction);
-	checker+=node->QueryDoubleAttribute("roughness",&roughness);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane Weight attributes"<<endl;
-		return false;
-	}
-
-	lane->AddMaterialRecord(sOffset,surface,friction,roughness);
-
-	return true;
-
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLaneVisibility(Lane* lane, TiXmlElement *node)
-{
-	double sOffset;
-	double forward;
-	double back;
-	double left;
-	double right;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("sOffset",&sOffset);
-	checker+=node->QueryDoubleAttribute("forward",&forward);
-	checker+=node->QueryDoubleAttribute("back",&back);
-	checker+=node->QueryDoubleAttribute("left",&left);
-	checker+=node->QueryDoubleAttribute("right",&right);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane Weight attributes"<<endl;
-		return false;
-	}
-
-	lane->AddVisibilityRecord(sOffset,forward,back,left,right);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLaneSpeed(Lane* lane, TiXmlElement *node)
-{	
-	double sOffset;
-	double max;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("sOffset",&sOffset);
-	checker+=node->QueryDoubleAttribute("max",&max);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane Weight attributes"<<endl;
-		return false;
-	}
-
-	lane->AddSpeedRecord(sOffset,max);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLaneAccess(Lane* lane, TiXmlElement *node)
-{
-	double sOffset;
-	string restriction;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("sOffset",&sOffset);
-	checker+=node->QueryStringAttribute("restriction",&restriction);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane Weight attributes"<<endl;
-		return false;
-	}
-
-	lane->AddAccessRecord(sOffset,restriction);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadLaneHeight(Lane* lane, TiXmlElement *node)
-{
-	double sOffset;
-	double inner;
-	double outer;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryDoubleAttribute("sOffset",&sOffset);
-	checker+=node->QueryDoubleAttribute("inner",&inner);
-	checker+=node->QueryDoubleAttribute("outer",&outer);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Lane Weight attributes"<<endl;
-		return false;
-	}
-
-	lane->AddHeightRecord(sOffset,inner,outer);
-
-	return true;
-}
-//--------------
-
-//--------------
-
-bool OpenDriveXmlParser::ReadObjects (Road* road, TiXmlElement *node)
-{
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadSignals (Road* road, TiXmlElement *node)
-{
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadSurface (Road* road, TiXmlElement *node)
-{
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlParser::ReadController (TiXmlElement *node)
-{	return true;	}
-//--------------
-
-bool OpenDriveXmlParser::ReadJunction (TiXmlElement *node)
-{	
-	string name;
-	string id;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryStringAttribute("name",&name);
-	checker+=node->QueryStringAttribute("id",&id);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Junction attributes"<<endl;
-		return false;
-	}
-
-	mOpenDrive->AddJunction(name,id);
-	Junction* junction=mOpenDrive->GetLastJunction();
-
-	//Read connection parameters and add them to the lane if available
-	TiXmlElement *subNode=node->FirstChildElement("connection");
-
-	while (subNode)
-	{
-		ReadJunctionConnection(junction, subNode);
-		subNode=subNode->NextSiblingElement("connection");
-	}
-
-
-	//Read connection parameters and add them to the lane if available
-	subNode=node->FirstChildElement("priority");
-
-	while (subNode)
-	{
-		ReadJunctionPriority(junction, subNode);
-		subNode=subNode->NextSiblingElement("priority");
-	}
-
-
-
-	//Read connection parameters and add them to the lane if available
-	subNode=node->FirstChildElement("controller");
-
-	while (subNode)
-	{
-		ReadJunctionController(junction, subNode);
-		subNode=subNode->NextSiblingElement("controller");
-	}
-
-
-	return true;
-	
-}
-//--------------
-bool OpenDriveXmlParser::ReadJunctionConnection (Junction* junction, TiXmlElement *node)
-{
-	string id;
-	string incomingRoad;
-	string connectingRoad;
-	string contactPoint;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryStringAttribute("id",&id);
-	checker+=node->QueryStringAttribute("incomingRoad",&incomingRoad);
-	checker+=node->QueryStringAttribute("connectingRoad",&connectingRoad);
-	checker+=node->QueryStringAttribute("contactPoint",&contactPoint);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Junction Connection attributes"<<endl;
-		return false;
-	}
-
-	junction->AddJunctionConnection(id,incomingRoad,connectingRoad,contactPoint);
-	JunctionConnection* junctionConnetion = junction->GetLastJunctionConnection();
-
-	TiXmlElement *subNode=node->FirstChildElement("laneLink");
-
-	while (subNode)
-	{
-		ReadJunctionConnectionLaneLink(junctionConnetion, subNode);
-		subNode=subNode->NextSiblingElement("laneLink");
-	}
-
-	return true;
-}
-bool OpenDriveXmlParser::ReadJunctionConnectionLaneLink (JunctionConnection* junctionConnection, TiXmlElement *node)
-{
-	int from;
-	int to;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryIntAttribute("from",&from);
-	checker+=node->QueryIntAttribute("to",&to);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Junction Lane Link attributes"<<endl;
-		return false;
-	}
-
-	junctionConnection->AddJunctionLaneLink(from,to);
-	return true;
-}
-
-bool OpenDriveXmlParser::ReadJunctionPriority (Junction* junction, TiXmlElement *node)
-{
-	string high;
-	string low;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryStringAttribute("high",&high);
-	checker+=node->QueryStringAttribute("low",&low);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Junction Priority attributes"<<endl;
-		return false;
-	}
-
-	junction->AddJunctionPriority(high,low);
-	return true;
-}
-bool OpenDriveXmlParser::ReadJunctionController (Junction* junction, TiXmlElement *node)
-{
-	string id;
-	string type;
-
-	int checker=TIXML_SUCCESS;
-	checker+=node->QueryStringAttribute("id",&id);
-	checker+=node->QueryStringAttribute("type",&type);
-	if (checker!=TIXML_SUCCESS)
-	{
-		cout<<"Error parsing Junction Controller attributes"<<endl;
-		return false;
-	}
-
-	junction->AddJunctionController(id,type);
-	return true;
-}
-
-
-//---------------------------------------------------------------------------
-/**
- * Reads the data from the OpenDrive structure to a file
- */
-bool OpenDriveXmlParser::ReadFile(std::string fileName)
-{
-	//Read and load File
-	TiXmlDocument doc( fileName );
-	bool loadOkay = doc.LoadFile();
-	if (loadOkay)
-	{
-		TiXmlElement *rootNode=doc.FirstChildElement();
-		//read header
-		int checker=TIXML_SUCCESS;
-		TiXmlElement *node=rootNode->FirstChildElement("header");
-		ReadHeader(node);
-
-		//read roads
-		node=rootNode->FirstChildElement("road");
-		while (node!=0)
-		{
-			ReadRoad(node);
-			node=node->NextSiblingElement("road");
-		}
-
-		//read controllers
-		node=rootNode->FirstChildElement("controller");
-		while (node!=0)
-		{
-			ReadController(node);
-			node=node->NextSiblingElement("controller");
-		}
-
-		//read junctions
-		node=rootNode->FirstChildElement("junction");
-		while (node!=0)
-		{
-			ReadJunction(node);
-			node=node->NextSiblingElement("junction");
-		}
-
-		return true;
-	}
-	
-	//failed to read the file
-	cout<<"Could not read file: "<<fileName<<endl;
-	return false;
-}
-//--------------

+ 0 - 86
src/tool/tool_xodrobj/OpenDrive/OpenDriveXmlParser.h

@@ -1,86 +0,0 @@
-#ifndef OPENDRIVEXMLPARSER_H
-#define OPENDRIVEXMLPARSER_H
-
-#include <vector>
-#include <string>
-
-#include <iostream>
-#include <fstream>
-#include "../TinyXML/tinyxml.h"
-
-#include "OpenDrive.h"
-
-/**
- * Class used to parse an XML file and fill in the OpenDrive structure
- *
- */
-class OpenDriveXmlParser
-{
-private:
-	OpenDrive* mOpenDrive;
-public:
-	/**
-	 * Constructor which saves a reference to OpenDrive structure
-	 */
-	OpenDriveXmlParser (OpenDrive* openDriveObj);
-
-	/**
-	 * Reads the data from the OpenDrive structure to a file
-	 */
-	bool ReadFile(std::string fileName);
-
-
-	/**
-	 * The following methods are used to read the data from the XML file and fill in the the OpenDrive structure
-	 * Methods follow the hierarchical structure and are called automatically when ReadFile is executed
-	 */
-	bool ReadHeader (TiXmlElement *node);
-	bool ReadRoad (TiXmlElement *node);
-	bool ReadRoadLinks (Road* road, TiXmlElement *node);
-	bool ReadRoadLink (Road* road, TiXmlElement *node, short int type);
-	bool ReadRoadType (Road* road, TiXmlElement *node);
-	//--------------
-
-	bool ReadPlanView(Road* road, TiXmlElement *node);
-	bool ReadGeometryBlock (Road* road, TiXmlElement *&node, short int blockType);
-	bool ReadGeometry(GeometryBlock* geomBlock, TiXmlElement *node, short int geometryType);
-	//--------------
-
-	bool ReadElevationProfile (Road* road, TiXmlElement *node);
-	bool ReadLateralProfile (Road* road, TiXmlElement *node);
-	//--------------
-
-	bool ReadLanes (Road* road, TiXmlElement *node);
-	bool ReadLaneSections (Road* road, TiXmlElement *node);
-	bool ReadLane (LaneSection* laneSection, TiXmlElement *node, short int laneType);
-	bool ReadLaneWidth(Lane* lane, TiXmlElement *node);
-	bool ReadLaneRoadMark(Lane* lane, TiXmlElement *node);
-	bool ReadLaneMaterial(Lane* lane, TiXmlElement *node);
-	bool ReadLaneVisibility(Lane* lane, TiXmlElement *node);
-	bool ReadLaneSpeed(Lane* lane, TiXmlElement *node);
-	bool ReadLaneAccess(Lane* lane, TiXmlElement *node);
-	bool ReadLaneHeight(Lane* lane, TiXmlElement *node);
-	//--------------
-
-	bool ReadObjects (Road* road, TiXmlElement *node);
-	bool ReadSignals (Road* road, TiXmlElement *node);
-	//--------------
-
-	bool ReadSurface (Road* road, TiXmlElement *node);
-	//--------------
-
-	bool ReadController (TiXmlElement *node);
-	//--------------
-
-	bool ReadJunction (TiXmlElement *node);
-	bool ReadJunctionConnection (Junction* junction, TiXmlElement *node);
-	bool ReadJunctionConnectionLaneLink (JunctionConnection* junctionConnection, TiXmlElement *node);
-	//--------------
-
-	bool ReadJunctionPriority (Junction* junction, TiXmlElement *node);
-	bool ReadJunctionController (Junction* junction, TiXmlElement *node);
-	//--------------
-};
-
-
-#endif

+ 0 - 1100
src/tool/tool_xodrobj/OpenDrive/OpenDriveXmlWriter.cpp

@@ -1,1100 +0,0 @@
-#include "OpenDriveXmlWriter.h"
-#include <iostream>
-#include <algorithm>
-//#include "windows.h"
-
-using std::cout;
-using std::endl;
-
-/**
- * Constructor which saves a reference to OpenDrive structure
- */
-OpenDriveXmlWriter::OpenDriveXmlWriter (OpenDrive* openDriveObj)
-{	
-	mOpenDrive=openDriveObj;	
-}
-
-/**
- * The following methods are used to create the XML representation of the OpenDrive structure
- * Methods follow the same hierarchical structure and are called automatically when WriteFile
- * is executed
- */
-bool OpenDriveXmlWriter::WriteHeader(TiXmlElement *node)
-{
-	//Write the Header
-	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;
-
-	Header *lHeader = mOpenDrive->GetHeader();
-    lHeader->GetAllParams(revMajor, revMinor, name, version, date, north, south, east, west,lat0,lon0,hdg0);
-
-	TiXmlElement *nodeHeader = new TiXmlElement("header");
-	node->LinkEndChild(nodeHeader);
-
-	nodeHeader->SetAttribute("revMajor",revMajor);
-	nodeHeader->SetAttribute("revMinor",revMinor);
-	nodeHeader->SetAttribute("name",name);
-	nodeHeader->SetDoubleAttribute("version",version);
-	nodeHeader->SetAttribute("date",date);
-
-	std::stringstream snorth;
-	snorth << setprecision(16) << setiosflags (ios_base::scientific) << north;
-	nodeHeader->SetAttribute("north",snorth.str());
-
-	std::stringstream ssouth;
-	ssouth << setprecision(16) << setiosflags (ios_base::scientific) << south;
-	nodeHeader->SetAttribute("south",ssouth.str());
-
-	std::stringstream seast;
-	seast << setprecision(16) << setiosflags (ios_base::scientific) << east;
-	nodeHeader->SetAttribute("east",seast.str());
-
-	std::stringstream swest;
-	swest << setprecision(16) << setiosflags (ios_base::scientific) << west;
-	nodeHeader->SetAttribute("west",swest.str());
-
-    std::stringstream slat0;
-    slat0 << setprecision(16) << setiosflags (ios_base::scientific) << lat0;
-    nodeHeader->SetAttribute("lat0",slat0.str());
-
-    std::stringstream slon0;
-    slon0 << setprecision(16) << setiosflags (ios_base::scientific) << lon0;
-    nodeHeader->SetAttribute("lon0",slon0.str());
-
-    std::stringstream shdg0;
-    shdg0 << setprecision(16) << setiosflags (ios_base::scientific) << hdg0;
-    nodeHeader->SetAttribute("hdg0",shdg0.str());
-
-
-	return true;
-}
-//--------------
-bool OpenDriveXmlWriter::WriteRoad(TiXmlElement *node, Road *road)
-{
-	//Write road attributes
-	string name;
-	double length;
-	string id;
-	string junction;
-
-	name = road->GetRoadName();
-	length = road->GetRoadLength();
-	id = road->GetRoadId();
-	junction = road->GetRoadJunction();
-
-	TiXmlElement *nodeRoad = new TiXmlElement("road");
-	node->LinkEndChild(nodeRoad);
-
-	nodeRoad->SetAttribute("name",name);
-	std::stringstream slength;
-	slength << setprecision(16) << setiosflags (ios_base::scientific) << length;
-	nodeRoad->SetAttribute("length",slength.str());
-	nodeRoad->SetAttribute("id",id);
-	nodeRoad->SetAttribute("junction",junction);
-
-	//Fill in
-
-	//Links
-	WriteRoadLinks (nodeRoad,road);
-
-	//Types
-	WriteRoadType(nodeRoad, road);
-
-	//PlanView
-	WritePlanView(nodeRoad, road);
-
-	//ElevationProfile
-	WriteElevationProfile(nodeRoad, road);
-
-	//LateralProfile
-	WriteLateralProfile(nodeRoad, road);
-
-	//Proceed to Lanes
-	WriteLanes(nodeRoad, road);
-
-
-	//Proceed to Objects
-	WriteObjects(nodeRoad, road);
-
-	//Proceed to Signals
-	WriteSignals(nodeRoad, road);
-
-	/*
-	//Proceed to Surface
-	subNode=node->FirstChildElement("surface");
-	if (subNode)
-	{
-	WriteSurface(road, subNode);
-	}
-	*/
-
-	return true;
-}
-//--------------
-
-bool  OpenDriveXmlWriter::WriteRoadLinks (TiXmlElement *node, Road* road)
-{
-	TiXmlElement* nodeLink = new TiXmlElement("link");
-	node->LinkEndChild(nodeLink);
-
-	RoadLink *lPredecessor = road->GetPredecessor();
-	if(lPredecessor)
-	{
-		TiXmlElement* nodeLinkPredecessor = new TiXmlElement("predecessor");
-		nodeLink->LinkEndChild(nodeLinkPredecessor);
-		nodeLinkPredecessor->SetAttribute("elementType", lPredecessor->GetElementType());
-		nodeLinkPredecessor->SetAttribute("elementId", lPredecessor->GetElementId());
-		nodeLinkPredecessor->SetAttribute("contactPoint", lPredecessor->GetContactPoint());
-	}
-	RoadLink *lSuccessor = road->GetSuccessor();
-	if(lSuccessor)
-	{
-		TiXmlElement* nodeLinkSuccessor = new TiXmlElement("successor");
-		nodeLink->LinkEndChild(nodeLinkSuccessor);
-		nodeLinkSuccessor->SetAttribute("elementType", lSuccessor->GetElementType());
-		nodeLinkSuccessor->SetAttribute("elementId", lSuccessor->GetElementId());
-		nodeLinkSuccessor->SetAttribute("contactPoint", lSuccessor->GetContactPoint());
-	}
-	RoadNeighbor *lNeighbor1 = road->GetNeighbor1();
-	if(lNeighbor1)
-	{
-		TiXmlElement* nodeLinkNeighbor1 = new TiXmlElement("neighbor");
-		nodeLink->LinkEndChild(nodeLinkNeighbor1);
-		nodeLinkNeighbor1->SetAttribute("side", lNeighbor1->GetSide());
-		nodeLinkNeighbor1->SetAttribute("elementId", lNeighbor1->GetElementId());
-		nodeLinkNeighbor1->SetAttribute("direction", lNeighbor1->GetDirection());
-	}
-	RoadNeighbor *lNeighbor2 = road->GetNeighbor2();
-	if(lNeighbor2)
-	{
-		TiXmlElement* nodeLinkNeighbor2 = new TiXmlElement("neighbor");
-		nodeLink->LinkEndChild(nodeLinkNeighbor2);
-		nodeLinkNeighbor2->SetAttribute("side", lNeighbor2->GetSide());
-		nodeLinkNeighbor2->SetAttribute("elementId", lNeighbor2->GetElementId());
-		nodeLinkNeighbor2->SetAttribute("direction", lNeighbor2->GetDirection());
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteRoadType (TiXmlElement *node, Road* road)
-{
-	double s;
-	string type;
-
-	unsigned int roadTypeCount = road->GetRoadTypeCount();
-	for(unsigned int i=0; i<roadTypeCount; i++)
-	{
-		RoadType *lRoadType = road->GetRoadType(i);
-
-		s=lRoadType->GetS();
-		type=lRoadType->GetType();
-
-		TiXmlElement *nodeRoadType = new TiXmlElement("type");
-		node->LinkEndChild(nodeRoadType);
-
-		std::stringstream ss;
-		ss << setprecision(16) << setiosflags (ios_base::scientific) << s;
-		nodeRoadType->SetAttribute("s",ss.str());
-		nodeRoadType->SetAttribute("type",type);
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WritePlanView(TiXmlElement *node, Road *road)
-{
-	TiXmlElement* nodePlanView = new TiXmlElement("planView");
-	node->LinkEndChild(nodePlanView);
-
-	unsigned int geometryCount = road->GetGeometryBlockCount();
-	for(unsigned int i=0; i<geometryCount; i++)
-	{
-		WriteGeometryBlock(nodePlanView, road->GetGeometryBlock(i));
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteGeometryBlock (TiXmlElement *node, GeometryBlock* geometryBlock)
-{
-
-	if(geometryBlock->CheckIfLine())
-	{
-
-        WriteGeometry(node, geometryBlock->GetGeometryAt(0), geometryBlock->GetGeometryAt(0)->GetGeomType());
-	}
-	else
-	{
-		WriteGeometry(node, geometryBlock->GetGeometryAt(0), 1);
-		WriteGeometry(node, geometryBlock->GetGeometryAt(1), 2);
-		WriteGeometry(node, geometryBlock->GetGeometryAt(2), 1);
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteGeometry(TiXmlElement *node, RoadGeometry* roadGeometry,  short int geometryType)
-{
-	double s, x, y, hdg, length;
-
-	s=roadGeometry->GetS();
-	x=roadGeometry->GetX();
-	y=roadGeometry->GetY();
-	hdg=roadGeometry->GetHdg();
-	length=roadGeometry->GetLength();
-
-	//Write the geometry node
-	TiXmlElement *nodeGeometry = new TiXmlElement("geometry");
-	node->LinkEndChild(nodeGeometry);
-
-	std::stringstream ss;
-	ss << setprecision(16) << setiosflags (ios_base::scientific) << s;
-	nodeGeometry->SetAttribute("s",ss.str());
-
-	std::stringstream sx;
-	sx << setprecision(16) << setiosflags (ios_base::scientific) << x;
-	nodeGeometry->SetAttribute("x",sx.str());
-
-	std::stringstream sy;
-	sy << setprecision(16) << setiosflags (ios_base::scientific) << y;
-	nodeGeometry->SetAttribute("y",sy.str());
-
-	std::stringstream shdg;
-	shdg << setprecision(16) << setiosflags (ios_base::scientific) << hdg;
-	nodeGeometry->SetAttribute("hdg",shdg.str());
-
-	std::stringstream slength;
-	slength << setprecision(16) << setiosflags (ios_base::scientific) << length;
-	nodeGeometry->SetAttribute("length",slength.str());
-
-
-	//Write the type nodes
-	switch ( geometryType )
-	{
-	case 0:	
-		{
-			//line
-			TiXmlElement *nodeLine = new TiXmlElement("line");
-			nodeGeometry->LinkEndChild(nodeLine);
-			break;
-		}
-	case 1:
-		{		
-			//spiral
-			double curvatureStart, curvatureEnd; 
-			GeometrySpiral *lSpiral=static_cast<GeometrySpiral*>(roadGeometry);
-			curvatureStart=lSpiral->GetCurvatureStart();
-			curvatureEnd=lSpiral->GetCurvatureEnd();
-
-			TiXmlElement *nodeSpiral = new TiXmlElement("spiral");
-			nodeGeometry->LinkEndChild(nodeSpiral);
-
-
-			std::stringstream scurvatureStart;
-			scurvatureStart << setprecision(16) << setiosflags (ios_base::scientific) << curvatureStart;
-			nodeSpiral->SetAttribute("curvStart",scurvatureStart.str());
-
-			std::stringstream scurvatureEnd;
-			scurvatureEnd << setprecision(16) << setiosflags (ios_base::scientific) << curvatureEnd;
-			nodeSpiral->SetAttribute("curvEnd",scurvatureEnd.str());
-			break;
-		}
-	case 2:
-		{		
-			//arc
-			double curvature;
-			GeometryArc *lArc=static_cast<GeometryArc*>(roadGeometry);
-			curvature=lArc->GetCurvature();
-
-			TiXmlElement *nodeArc = new TiXmlElement("arc");
-			nodeGeometry->LinkEndChild(nodeArc);
-
-			std::stringstream scurvature;
-			scurvature << setprecision(16) << setiosflags (ios_base::scientific) << curvature;
-			nodeArc->SetAttribute("curvature",scurvature.str());
-			break;
-		}
-	case 3:
-		{		
-			//poly3
-			break;
-		}
-
-    case 4:
-        {   //paramPoly3 add by Yu Chuli. 2019.11.1
-            double ua,ub,uc,ud,va,vb,vc,vd;
-            GeometryParamPoly3 *lpp3=static_cast<GeometryParamPoly3 *>(roadGeometry);
-
-            ua = lpp3->GetuA();
-            ub = lpp3->GetuB();
-            uc = lpp3->GetuC();
-            ud = lpp3->GetuD();
-            va = lpp3->GetvA();
-            vb = lpp3->GetvB();
-            vc = lpp3->GetvC();
-            vd = lpp3->GetvD();
-
-            TiXmlElement *nodeParamPoly3 = new TiXmlElement("paramPoly3");
-            nodeGeometry->LinkEndChild(nodeParamPoly3);
-
-            std::stringstream sua;
-            sua << setprecision(16) << setiosflags (ios_base::scientific) << ua;
-            nodeParamPoly3->SetAttribute("aU",sua.str());
-
-            std::stringstream sub;
-            sub << setprecision(16) << setiosflags (ios_base::scientific) << ub;
-            nodeParamPoly3->SetAttribute("bU",sub.str());
-
-            std::stringstream suc;
-            suc << setprecision(16) << setiosflags (ios_base::scientific) << uc;
-            nodeParamPoly3->SetAttribute("cU",suc.str());
-
-            std::stringstream sud;
-            sud << setprecision(16) << setiosflags (ios_base::scientific) << ud;
-            nodeParamPoly3->SetAttribute("dU",sud.str());
-
-            std::stringstream sva;
-            sva << setprecision(16) << setiosflags (ios_base::scientific) << va;
-            nodeParamPoly3->SetAttribute("aV",sva.str());
-
-            std::stringstream svb;
-            svb << setprecision(16) << setiosflags (ios_base::scientific) << vb;
-            nodeParamPoly3->SetAttribute("bV",svb.str());
-
-            std::stringstream svc;
-            svc << setprecision(16) << setiosflags (ios_base::scientific) << vc;
-            nodeParamPoly3->SetAttribute("cV",svc.str());
-
-            std::stringstream svd;
-            svd << setprecision(16) << setiosflags (ios_base::scientific) << vd;
-            nodeParamPoly3->SetAttribute("dV",svd.str());
-            break;
-
-        }
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteElevationProfile (TiXmlElement *node, Road* road)
-{
-	double s, a, b, c, d;
-
-	TiXmlElement* nodeElevationProfile = new TiXmlElement("elevationProfile");
-	node->LinkEndChild(nodeElevationProfile);
-
-	unsigned int lElevationCount = road->GetElevationCount();
-	for(unsigned int i=0; i<lElevationCount; i++)
-	{
-		Elevation *lElevation = road->GetElevation(i);
-		s=lElevation->GetS();
-		a=lElevation->GetA();
-		b=lElevation->GetB();
-		c=lElevation->GetC();
-		d=lElevation->GetD();
-
-		TiXmlElement *nodeElevation = new TiXmlElement("elevation");
-		nodeElevationProfile->LinkEndChild(nodeElevation);
-
-		std::stringstream ss;
-		ss << setprecision(16) << setiosflags (ios_base::scientific) << s;
-		nodeElevation->SetAttribute("s",ss.str());
-
-		std::stringstream sa;
-		sa << setprecision(16) << setiosflags (ios_base::scientific) << a;
-		nodeElevation->SetAttribute("a",sa.str());
-
-		std::stringstream sb;
-		sb << setprecision(16) << setiosflags (ios_base::scientific) << b;
-		nodeElevation->SetAttribute("b",sb.str());
-
-		std::stringstream sc;
-		sc << setprecision(16) << setiosflags (ios_base::scientific) << c;
-		nodeElevation->SetAttribute("c",sc.str());
-
-		std::stringstream sd;
-		sd << setprecision(16) << setiosflags (ios_base::scientific) << d;
-		nodeElevation->SetAttribute("d",sd.str());
-	}
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLateralProfile (TiXmlElement *node, Road* road)
-{
-	double s, a, b, c, d;
-	string side;
-
-	TiXmlElement* nodeLateralProfile = new TiXmlElement("lateralProfile");
-	node->LinkEndChild(nodeLateralProfile);
-
-	unsigned int lSuperElevationCount = road->GetSuperElevationCount();
-	for(unsigned int i=0; i<lSuperElevationCount; i++)
-	{
-		SuperElevation *lSuperElevation = road->GetSuperElevation(i);
-		s=lSuperElevation->GetS();
-		a=lSuperElevation->GetA();
-		b=lSuperElevation->GetB();
-		c=lSuperElevation->GetC();
-		d=lSuperElevation->GetD();
-
-		TiXmlElement *nodeSuperElevation = new TiXmlElement("superelevation");
-		nodeLateralProfile->LinkEndChild(nodeSuperElevation);
-
-		std::stringstream ss;
-		ss << setprecision(16) << setiosflags (ios_base::scientific) << s;
-		nodeSuperElevation->SetAttribute("s",ss.str());
-
-		std::stringstream sa;
-		sa << setprecision(16) << setiosflags (ios_base::scientific) << a;
-		nodeSuperElevation->SetAttribute("a",sa.str());
-
-		std::stringstream sb;
-		sb << setprecision(16) << setiosflags (ios_base::scientific) << b;
-		nodeSuperElevation->SetAttribute("b",sb.str());
-
-		std::stringstream sc;
-		sc << setprecision(16) << setiosflags (ios_base::scientific) << c;
-		nodeSuperElevation->SetAttribute("c",sc.str());
-
-		std::stringstream sd;
-		sd << setprecision(16) << setiosflags (ios_base::scientific) << d;
-		nodeSuperElevation->SetAttribute("d",sd.str());
-	}
-
-
-	unsigned int lCrossfallCount = road->GetCrossfallCount();
-	for(unsigned int i=0; i<lCrossfallCount; i++)
-	{
-		Crossfall *lCrossfall = road->GetCrossfall(i);
-		s=lCrossfall->GetS();
-		a=lCrossfall->GetA();
-		b=lCrossfall->GetB();
-		c=lCrossfall->GetC();
-		d=lCrossfall->GetD();
-		side=lCrossfall->GetSide();
-
-		TiXmlElement *nodeCrossfall = new TiXmlElement("crossfall");
-		nodeLateralProfile->LinkEndChild(nodeCrossfall);
-
-		nodeCrossfall->SetAttribute("side",side);
-
-		std::stringstream ss;
-		ss << setprecision(16) << setiosflags (ios_base::scientific) << s;
-		nodeCrossfall->SetAttribute("s",ss.str());
-
-		std::stringstream sa;
-		sa << setprecision(16) << setiosflags (ios_base::scientific) << a;
-		nodeCrossfall->SetAttribute("a",sa.str());
-
-		std::stringstream sb;
-		sb << setprecision(16) << setiosflags (ios_base::scientific) << b;
-		nodeCrossfall->SetAttribute("b",sb.str());
-
-		std::stringstream sc;
-		sc << setprecision(16) << setiosflags (ios_base::scientific) << c;
-		nodeCrossfall->SetAttribute("c",sc.str());
-
-		std::stringstream sd;
-		sd << setprecision(16) << setiosflags (ios_base::scientific) << d;
-		nodeCrossfall->SetAttribute("d",sd.str());
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLanes (TiXmlElement *node, Road* road)
-{
-	TiXmlElement* nodeLanes = new TiXmlElement("lanes");
-	node->LinkEndChild(nodeLanes);
-
-	unsigned int lLaneSectionCount = road->GetLaneSectionCount();
-	for(unsigned int i=0; i<lLaneSectionCount; i++)
-	{
-		WriteLaneSections(nodeLanes, road->GetLaneSection(i));
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLaneSections (TiXmlElement *node, LaneSection *laneSection)
-{
-	double s;
-	s=laneSection->GetS();
-
-	TiXmlElement* nodeLaneSection = new TiXmlElement("laneSection");
-	node->LinkEndChild(nodeLaneSection);
-
-	std::stringstream ss;
-	ss << setprecision(16) << setiosflags (ios_base::scientific) << s;
-	nodeLaneSection->SetAttribute("s",ss.str());
-
-	//Fill in lane section
-	short int curType=1;
-	TiXmlElement* nodeLanesLeft=NULL;
-	if(laneSection->GetLeftLaneCount()>0)
-	{
-		nodeLanesLeft = new TiXmlElement("left");
-		nodeLaneSection->LinkEndChild(nodeLanesLeft);
-	}
-	
-	TiXmlElement* nodeLanesCenter = new TiXmlElement("center");
-	nodeLaneSection->LinkEndChild(nodeLanesCenter);
-
-	TiXmlElement* nodeLanesRight=NULL;
-	if(laneSection->GetRightLaneCount()>0)
-	{
-		nodeLanesRight = new TiXmlElement("right");
-		nodeLaneSection->LinkEndChild(nodeLanesRight);
-	}
-
-
-	unsigned int lLaneCount = laneSection->GetLaneCount();
-	for(unsigned int i=0; i<lLaneCount; i++)
-	{
-		Lane *lLane = laneSection->GetLane(i);
-		short int lType=lLane->GetSide();
-		if(lType>0 && nodeLanesLeft!=NULL)
-		{
-			WriteLane(nodeLanesLeft, lLane);
-		}
-		else if(lType==0)
-		{
-			WriteLane(nodeLanesCenter, lLane);
-		}
-		else if(lType<0 && nodeLanesRight!=NULL)
-		{
-			WriteLane(nodeLanesRight, lLane);
-		}
-	}
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLane (TiXmlElement *node, Lane* lane)
-{
-	//Write Lane attributes
-	int id;
-	string type; 
-	string level; 
-	bool boolLevel;
-	int predecessor;
-	int successor;
-
-	id=lane->GetId();
-	type=lane->GetType();
-	boolLevel=lane->GetLevel();
-	if(boolLevel) level="true";
-	else level="false";
-	predecessor=lane->GetPredecessor();
-	successor=lane->GetSuccessor();
-	
-	TiXmlElement* nodeLane = new TiXmlElement("lane");
-	node->LinkEndChild(nodeLane);
-
-	//Attributes
-	nodeLane->SetAttribute("id",id);
-	nodeLane->SetAttribute("type",type);
-	nodeLane->SetAttribute("level",level);
-	
-	//Links
-	TiXmlElement* nodeLaneLink = new TiXmlElement("link");
-	nodeLane->LinkEndChild(nodeLaneLink);
-	if(lane->IsPredecessorSet())
-	{
-		TiXmlElement* nodeLaneLinkPredecessor = new TiXmlElement("predecessor");
-		nodeLaneLink->LinkEndChild(nodeLaneLinkPredecessor);
-		nodeLaneLinkPredecessor->SetAttribute("id",predecessor);
-	}
-	if(lane->IsSuccessorSet())
-	{
-		TiXmlElement* nodeLaneLinkSuccessor = new TiXmlElement("successor");
-		nodeLaneLink->LinkEndChild(nodeLaneLinkSuccessor);
-		nodeLaneLinkSuccessor->SetAttribute("id",successor);
-	}
-
-	//Lane Width
-	unsigned int lLaneWidthCount = lane->GetLaneWidthCount();
-	for(unsigned int i=0; i<lLaneWidthCount; i++)
-	{
-		WriteLaneWidth(nodeLane, lane->GetLaneWidth(i));
-	}
-
-	//Lane Road Mark
-	unsigned int lLaneRoadMark = lane->GetLaneRoadMarkCount();
-	for(unsigned int i=0; i<lLaneRoadMark; i++)
-	{
-		WriteLaneRoadMark(nodeLane, lane->GetLaneRoadMark(i));
-	}
-
-	//Lane Material
-	unsigned int lLaneMaterial = lane->GetLaneMaterialCount();
-	for(unsigned int i=0; i<lLaneMaterial; i++)
-	{
-		WriteLaneMaterial(nodeLane, lane->GetLaneMaterial(i));
-	}
-
-	//Lane Visibility
-	unsigned int lLaneVisibility = lane->GetLaneVisibilityCount();
-	for(unsigned int i=0; i<lLaneVisibility; i++)
-	{
-		WriteLaneVisibility(nodeLane, lane->GetLaneVisibility(i));
-	}
-
-	//Lane speed
-	unsigned int lLaneSpeed = lane->GetLaneSpeedCount();
-	for(unsigned int i=0; i<lLaneSpeed; i++)
-	{
-		WriteLaneSpeed(nodeLane, lane->GetLaneSpeed(i));
-	}
-
-	//Lane access
-	unsigned int lLaneAccess = lane->GetLaneAccessCount();
-	for(unsigned int i=0; i<lLaneAccess; i++)
-	{
-		WriteLaneAccess(nodeLane, lane->GetLaneAccess(i));
-	}
-
-	//Lane height
-	unsigned int lLaneHeight = lane->GetLaneHeightCount();
-	for(unsigned int i=0; i<lLaneHeight; i++)
-	{
-		WriteLaneHeight(nodeLane, lane->GetLaneHeight(i));
-	}
-
-	return true;
-}
-//--------------
-
-
-bool OpenDriveXmlWriter::WriteLaneWidth(TiXmlElement *node, LaneWidth* laneWidth)
-{
-	double sOffset, a, b, c, d;
-
-	sOffset=laneWidth->GetS();
-	a=laneWidth->GetA();
-	b=laneWidth->GetB();
-	c=laneWidth->GetC();
-	d=laneWidth->GetD();
-
-	TiXmlElement* nodeLaneWidth = new TiXmlElement("width");
-	node->LinkEndChild(nodeLaneWidth);
-
-	std::stringstream ssOffset;
-	ssOffset << setprecision(16) << setiosflags (ios_base::scientific) << sOffset;
-	nodeLaneWidth->SetAttribute("sOffset",ssOffset.str());
-
-	std::stringstream sa;
-	sa << setprecision(16) << setiosflags (ios_base::scientific) << a;
-	nodeLaneWidth->SetAttribute("a",sa.str());
-
-	std::stringstream sb;
-	sb << setprecision(16) << setiosflags (ios_base::scientific) << b;
-	nodeLaneWidth->SetAttribute("b",sb.str());
-
-	std::stringstream sc;
-	sc << setprecision(16) << setiosflags (ios_base::scientific) << c;
-	nodeLaneWidth->SetAttribute("c",sc.str());
-
-	std::stringstream sd;
-	sd << setprecision(16) << setiosflags (ios_base::scientific) << d;
-	nodeLaneWidth->SetAttribute("d",sd.str());
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLaneRoadMark(TiXmlElement *node, LaneRoadMark* laneRoadMark)
-{
-
-	double sOffset;
-	string type;
-	string weight;
-	string color; 
-	double width;
-	string laneChange;
-
-	sOffset=laneRoadMark->GetS();
-	type=laneRoadMark->GetType();
-	weight=laneRoadMark->GetWeight();
-	color=laneRoadMark->GetColor();
-	width=laneRoadMark->GetWidth();
-	laneChange=laneRoadMark->GetLaneChange();
-
-	TiXmlElement* nodeLaneRoadMark = new TiXmlElement("roadMark");
-	node->LinkEndChild(nodeLaneRoadMark);
-
-	std::stringstream ssOffset;
-	ssOffset << setprecision(16) << setiosflags (ios_base::scientific) << sOffset;
-	nodeLaneRoadMark->SetAttribute("sOffset",ssOffset.str());
-	nodeLaneRoadMark->SetAttribute("type",type);
-	nodeLaneRoadMark->SetAttribute("weight",weight);
-	nodeLaneRoadMark->SetAttribute("color",color);
-
-	std::stringstream swidth;
-	swidth << setprecision(16) << setiosflags (ios_base::scientific) << width;
-	nodeLaneRoadMark->SetAttribute("width",swidth.str());
-	nodeLaneRoadMark->SetAttribute("laneChange",laneChange);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLaneMaterial(TiXmlElement *node, LaneMaterial* laneMaterial)
-{
-	double sOffset;
-	string surface;
-	double friction;
-	double roughness;
-
-	sOffset=laneMaterial->GetS();
-	surface=laneMaterial->GetSurface();
-	friction=laneMaterial->GetFriction();
-	roughness=laneMaterial->GetRoughness();
-
-	TiXmlElement* nodeLaneMaterial = new TiXmlElement("material");
-	node->LinkEndChild(nodeLaneMaterial);
-
-	std::stringstream ssOffset;
-	ssOffset << setprecision(16) << setiosflags (ios_base::scientific) << sOffset;
-	nodeLaneMaterial->SetAttribute("sOffset",ssOffset.str());
-	nodeLaneMaterial->SetAttribute("surface",surface);
-
-	std::stringstream sfriction;
-	sfriction << setprecision(16) << setiosflags (ios_base::scientific) << friction;
-	nodeLaneMaterial->SetAttribute("friction",sfriction.str());
-
-	std::stringstream sroughness;
-	sroughness << setprecision(16) << setiosflags (ios_base::scientific) << roughness;
-	nodeLaneMaterial->SetAttribute("roughness",sroughness.str());
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLaneVisibility(TiXmlElement *node, LaneVisibility* laneVisibility)
-{
-	double sOffset;
-	double forward;
-	double back;
-	double left;
-	double right;
-
-	sOffset=laneVisibility->GetS();
-	forward=laneVisibility->GetForward();
-	back=laneVisibility->GetBack();
-	left=laneVisibility->GetLeft();
-	right=laneVisibility->GetRight();
-
-	TiXmlElement* nodeLaneVisibility = new TiXmlElement("visibility");
-	node->LinkEndChild(nodeLaneVisibility);
-
-	std::stringstream ssOffset;
-	ssOffset << setprecision(16) << setiosflags (ios_base::scientific) << sOffset;
-	nodeLaneVisibility->SetAttribute("sOffset",ssOffset.str());
-
-	std::stringstream sforward;
-	sforward << setprecision(16) << setiosflags (ios_base::scientific) << forward;
-	nodeLaneVisibility->SetAttribute("forward",sforward.str());
-
-	std::stringstream sback;
-	sback << setprecision(16) << setiosflags (ios_base::scientific) << back;
-	nodeLaneVisibility->SetAttribute("back",sback.str());
-
-	std::stringstream sleft;
-	sleft << setprecision(16) << setiosflags (ios_base::scientific) << left;
-	nodeLaneVisibility->SetAttribute("left",sleft.str());
-
-	std::stringstream sright;
-	sright << setprecision(16) << setiosflags (ios_base::scientific) << right;
-	nodeLaneVisibility->SetAttribute("right",sright.str());
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLaneSpeed(TiXmlElement *node, LaneSpeed* laneSpeed)
-{	
-	double sOffset;
-	double max;
-
-	sOffset=laneSpeed->GetS();
-	max=laneSpeed->GetMax();
-
-	TiXmlElement* nodeLaneSpeed = new TiXmlElement("speed");
-	node->LinkEndChild(nodeLaneSpeed);
-
-	std::stringstream ssOffset;
-	ssOffset << setprecision(16) << setiosflags (ios_base::scientific) << sOffset;
-	nodeLaneSpeed->SetAttribute("sOffset",ssOffset.str());
-
-	std::stringstream smax;
-	smax << setprecision(16) << setiosflags (ios_base::scientific) << max;
-	nodeLaneSpeed->SetAttribute("max",smax.str());
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLaneAccess(TiXmlElement *node, LaneAccess* laneAccess)
-{
-	double sOffset;
-	string restriction;
-
-	sOffset=laneAccess->GetS();
-	restriction=laneAccess->GetRestriction();
-
-	TiXmlElement* nodeLaneAccess = new TiXmlElement("access");
-	node->LinkEndChild(nodeLaneAccess);
-
-	std::stringstream ssOffset;
-	ssOffset << setprecision(16) << setiosflags (ios_base::scientific) << sOffset;
-	nodeLaneAccess->SetAttribute("sOffset",ssOffset.str());
-	nodeLaneAccess->SetAttribute("restriction",restriction);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteLaneHeight(TiXmlElement *node, LaneHeight* laneHeight)
-{
-	double sOffset;
-	double inner;
-	double outer;
-
-	sOffset=laneHeight->GetS();
-	inner=laneHeight->GetInner();
-	outer=laneHeight->GetOuter();
-
-	TiXmlElement* nodeLaneHeight = new TiXmlElement("height");
-	node->LinkEndChild(nodeLaneHeight);
-
-	std::stringstream ssOffset;
-	ssOffset << setprecision(16) << setiosflags (ios_base::scientific) << sOffset;
-	nodeLaneHeight->SetAttribute("sOffset",ssOffset.str());
-
-	std::stringstream sinner;
-	sinner << setprecision(16) << setiosflags (ios_base::scientific) << inner;
-	nodeLaneHeight->SetAttribute("inner",sinner.str());
-
-	std::stringstream souter;
-	souter << setprecision(16) << setiosflags (ios_base::scientific) << outer;
-	nodeLaneHeight->SetAttribute("outer",souter.str());
-	
-	return true;
-}
-//--------------
-
-//--------------
-
-bool OpenDriveXmlWriter::WriteObjects (TiXmlElement *node, Road* road)
-{
-	TiXmlElement* nodeObjects = new TiXmlElement("objects");
-	node->LinkEndChild(nodeObjects);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteSignals (TiXmlElement *node, Road* road)
-{
-	TiXmlElement* nodeSignals = new TiXmlElement("signals");
-	node->LinkEndChild(nodeSignals);
-
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteSurface (TiXmlElement *node, Road* road)
-{
-	return true;
-}
-//--------------
-
-bool OpenDriveXmlWriter::WriteController (TiXmlElement *node)
-{	return true;	}
-//--------------
-
-bool OpenDriveXmlWriter::WriteJunction (TiXmlElement *node, Junction *junction)
-{
-	string name;
-	string id;
-
-	name = junction->GetName();
-	id = junction->GetId();
-
-	TiXmlElement *nodeJunction = new TiXmlElement("junction");
-	node->LinkEndChild(nodeJunction);
-
-	nodeJunction->SetAttribute("name",name);
-	nodeJunction->SetAttribute("id",id);
-
-	//Connections
-	WriteJunctionConnection(nodeJunction, junction);
-
-	//Priorities
-	WriteJunctionPriority(nodeJunction, junction);
-
-	//Controllers
-	WriteJunctionController(nodeJunction, junction);
-
-	return true;
-}
-//--------------
-bool OpenDriveXmlWriter::WriteJunctionConnection (TiXmlElement *node, Junction* junction)
-{
-	string id;
-	string incomingRoad;
-	string connectingRoad;
-	string contactPoint;
-
-	unsigned int junctionConnectionCount = junction->GetJunctionConnectionCount();
-	for(unsigned int i=0; i<junctionConnectionCount; i++)
-	{
-		JunctionConnection *lJunctionConnection = junction->GetJunctionConnection(i);
-
-		id = lJunctionConnection->GetId();
-		incomingRoad = lJunctionConnection->GetIncomingRoad();
-		connectingRoad = lJunctionConnection->GetConnectingRoad();
-		contactPoint = lJunctionConnection->GetContactPoint();
-
-		TiXmlElement *nodeJunctionConnection = new TiXmlElement("connection");
-		node->LinkEndChild(nodeJunctionConnection);
-
-		nodeJunctionConnection->SetAttribute("id",id);
-		nodeJunctionConnection->SetAttribute("incomingRoad",incomingRoad);
-		nodeJunctionConnection->SetAttribute("connectingRoad",connectingRoad);
-		nodeJunctionConnection->SetAttribute("contactPoint",contactPoint);
-
-		//Lane links
-		WriteJunctionConnectionLaneLink(nodeJunctionConnection, lJunctionConnection);
-	}
-
-	return true;
-}
-bool OpenDriveXmlWriter::WriteJunctionConnectionLaneLink (TiXmlElement *node, JunctionConnection* junctionConnection)
-{
-	int from;
-	int to;
-	
-	unsigned int junctionLaneLinkCount = junctionConnection->GetJunctionLaneLinkCount();
-	for(unsigned int i=0; i<junctionLaneLinkCount; i++)
-	{
-		JunctionLaneLink *lJunctionLaneLink = junctionConnection->GetJunctionLaneLink(i);
-
-		from = lJunctionLaneLink->GetFrom();
-		to = lJunctionLaneLink->GetTo();
-
-		TiXmlElement *nodeJunctionLaneLink = new TiXmlElement("laneLink");
-		node->LinkEndChild(nodeJunctionLaneLink);
-
-		nodeJunctionLaneLink->SetAttribute("from",from);
-		nodeJunctionLaneLink->SetAttribute("to",to);
-	}
-	return true;
-}
-
-bool OpenDriveXmlWriter::WriteJunctionPriority (TiXmlElement *node, Junction* junction)
-{
-	string high;
-	string low;
-
-	unsigned int junctionPriorityCount = junction->GetJunctionPriorityCount();
-	for(unsigned int i=0; i<junctionPriorityCount; i++)
-	{
-		JunctionPriorityRoad *lJunctionPriority = junction->GetJunctionPriority(i);
-
-		high = lJunctionPriority->GetHigh();
-		low = lJunctionPriority->GetLow();
-
-		TiXmlElement *nodeJunctionPriority = new TiXmlElement("priority");
-		node->LinkEndChild(nodeJunctionPriority);
-
-		nodeJunctionPriority->SetAttribute("high",high);
-		nodeJunctionPriority->SetAttribute("low",low);
-	}
-
-	return true;
-}
-bool OpenDriveXmlWriter::WriteJunctionController (TiXmlElement *node, Junction* junction)
-{
-	string id;
-	string type;
-
-	unsigned int junctionControllerCount = junction->GetJunctionControllerCount();
-	for(unsigned int i=0; i<junctionControllerCount; i++)
-	{
-		JunctionController *lJunctionController = junction->GetJunctionController(i);
-
-		id = lJunctionController->GetId();
-		type = lJunctionController->GetType();
-
-		TiXmlElement *nodeJunctionController = new TiXmlElement("controller");
-		node->LinkEndChild(nodeJunctionController);
-
-		nodeJunctionController->SetAttribute("id",id);
-		nodeJunctionController->SetAttribute("type",type);
-	}
-	return true;
-}
-
-
-//---------------------------------------------------------------------------
-
-/**
- * Writes the data from the OpenDrive structure to a file
- */
-bool OpenDriveXmlWriter::WriteFile(std::string fileName)
-{
-	// XML document
-	TiXmlDocument doc;
-
-	TiXmlDeclaration* decl = new TiXmlDeclaration( "1.0", "", "" );  
-	doc.LinkEndChild( decl );
-
-	TiXmlElement *rootNode = new TiXmlElement("OpenDRIVE");
-	doc.LinkEndChild(rootNode);
-
-	// Write header
-	WriteHeader(rootNode);
-
-	// Write roads
-	unsigned int roadCount = mOpenDrive->GetRoadCount();
-	for(unsigned int i=0; i<roadCount; i++)
-	{
-		WriteRoad(rootNode, mOpenDrive->GetRoad(i));
-	}
-
-	// Write junctions
-	unsigned int junctionCount = mOpenDrive->GetJunctionCount();
-	for(unsigned int i=0; i<junctionCount; i++)
-	{
-		WriteJunction(rootNode, mOpenDrive->GetJunction(i));
-	}
-
-	// Saves the XML structure to the file
-	doc.SaveFile( fileName ); 
-
-	return true;
-
-}
-//--------------

+ 0 - 87
src/tool/tool_xodrobj/OpenDrive/OpenDriveXmlWriter.h

@@ -1,87 +0,0 @@
-#ifndef OPENDRIVEXMLWRITER_H
-#define OPENDRIVEXMLWRITER_H
-
-#include <vector>
-#include <string>
-
-#include <iostream>
-#include <iomanip>
-using namespace std;
-#include <fstream>
-#include "../TinyXML/tinyxml.h"
-
-#include "OpenDrive.h"
-
-/**
- * Class used to write the content of the OpenDrive structure to the file
- *
- */
-class OpenDriveXmlWriter
-{
-private:
-	OpenDrive* mOpenDrive;
-public:
-	/**
-	 * Constructor which saves a reference to OpenDrive structure
-	 */
-	OpenDriveXmlWriter (OpenDrive* openDriveObj);
-
-	/**
-	 * Writes the data from the OpenDrive structure to a file
-	 */
-	bool WriteFile(std::string fileName);
-	
-	/**
-	 * The following methods are used to create the XML representation of the OpenDrive structure
-	 * Methods follow the same hierarchical structure and are called automatically when WriteFile
-	 * is executed
-	 */
-	bool WriteHeader (TiXmlElement *node);
-	bool WriteRoad (TiXmlElement *node, Road *road);
-	bool WriteRoadLinks (TiXmlElement *node, Road* road);
-	bool WriteRoadType (TiXmlElement *node, Road* road);
-	//--------------
-
-	bool WritePlanView(TiXmlElement *node, Road* road);
-	bool WriteGeometryBlock (TiXmlElement *node, GeometryBlock *geometryBlock);
-	bool WriteGeometry(TiXmlElement *node, RoadGeometry* roadGeometry, short int geometryType);
-	//--------------
-
-	bool WriteElevationProfile (TiXmlElement *node, Road* road);
-	bool WriteLateralProfile (TiXmlElement *node, Road* road);
-	//--------------
-
-	bool WriteLanes (TiXmlElement *node, Road* road);
-	bool WriteLaneSections (TiXmlElement *node, LaneSection *laneSection);
-	bool WriteLane (TiXmlElement *node, Lane* lane);
-	bool WriteLaneWidth(TiXmlElement *node, LaneWidth* laneWidth);
-	bool WriteLaneRoadMark(TiXmlElement *node, LaneRoadMark* laneRoadMark);
-	bool WriteLaneMaterial(TiXmlElement *node, LaneMaterial* laneMaterial);
-	bool WriteLaneVisibility(TiXmlElement *node, LaneVisibility* laneVisibility);
-	bool WriteLaneSpeed(TiXmlElement *node, LaneSpeed* laneSpeed);
-	bool WriteLaneAccess(TiXmlElement *node, LaneAccess* laneAccess);
-	bool WriteLaneHeight(TiXmlElement *node, LaneHeight* laneHeight);
-	//--------------
-
-	bool WriteObjects (TiXmlElement *node, Road* road);
-	bool WriteSignals (TiXmlElement *node, Road* road);
-	//--------------
-
-	bool WriteSurface (TiXmlElement *node, Road* road);
-	//--------------
-
-	bool WriteController (TiXmlElement *node);
-	//--------------
-
-	bool WriteJunction (TiXmlElement *node, Junction *junction);
-	bool WriteJunctionConnection (TiXmlElement *node, Junction* junction);
-	bool WriteJunctionConnectionLaneLink (TiXmlElement *node, JunctionConnection* junctionConnection);
-	//--------------
-
-	bool WriteJunctionPriority (TiXmlElement *node, Junction* junction);
-	bool WriteJunctionController (TiXmlElement *node, Junction* junction);
-	//--------------
-};
-
-
-#endif

+ 0 - 90
src/tool/tool_xodrobj/OpenDrive/OtherStructures.cpp

@@ -1,90 +0,0 @@
-#include "OtherStructures.h"
-
-//***********************************************************************************
-//Polynom of third order
-//***********************************************************************************
-/**
- * Constructor that initializes the polynom with base properties
- * 
- * @param s S offset
- * @param a A parameter of the polynom
- * @param b B parameter of the polynom
- * @param c C parameter of the polynom
- * @param d D parameter of the polynom
- */
-ThirdOrderPolynom::ThirdOrderPolynom (double s, double a, double b, double c, double d)
-{	
-	mS=s; mA=a; mB=b; mC=c; mD=d;	
-}
-
-/**
- * Getters for base properties
- */	
-double ThirdOrderPolynom::GetS()
-{
-	return mS;
-}
-double ThirdOrderPolynom::GetA()
-{
-	return mA;
-}
-double ThirdOrderPolynom::GetB()
-{
-	return mB;
-}
-double ThirdOrderPolynom::GetC()
-{
-	return mC;
-}
-
-double ThirdOrderPolynom::GetD()
-{
-	return mD;
-}
-
-/**
- * Setters for base properties
- */
-void ThirdOrderPolynom::SetS(double s)
-{
-	mS=s;
-}
-void ThirdOrderPolynom::SetA(double a)
-{
-	mA=a;
-}
-void ThirdOrderPolynom::SetB(double b)
-{
-	mB=b;
-}
-void ThirdOrderPolynom::SetC(double c)
-{
-	mC=c;
-}
-void ThirdOrderPolynom::SetD(double d)
-{
-	mD=d;
-}
-
-
-/**
- * Method to check if sample S is inside the record interval
- */	
-bool ThirdOrderPolynom::CheckInterval (double s_check)
-{
-	if (s_check>=mS)
-		return true;
-	else 
-		return false;
-}
-
-/**
- * Returns the value at sample S
- */	
-double ThirdOrderPolynom::GetValue(double s_check)
-{
-	double ds = s_check-mS;
-	double value = mA+ mB*ds+ mC*ds*ds + mD*ds*ds*ds;
-	return value;
-}
-//----------------------------------------------------------------------------------

+ 0 - 66
src/tool/tool_xodrobj/OpenDrive/OtherStructures.h

@@ -1,66 +0,0 @@
-#ifndef OTHERSTRUCTURES_H
-#define OTHERSTRUCTURES_H
-#include <string>
-using std::string;
-
-/**
- * Polynom of third order
- *
- */
-class ThirdOrderPolynom
-{
-protected:
-	double mS;
-	double mA;
-	double mB;
-	double mC;
-	double mD;
-public:
-	/**
-	 * Constructor that initializes the polynom with base properties
-	 * 
-	 * @param s S offset
-	 * @param a A parameter of the polynom
-	 * @param b B parameter of the polynom
-	 * @param c C parameter of the polynom
-	 * @param d D parameter of the polynom
-	 */
-	ThirdOrderPolynom (double s, double a, double b, double c, double d);
-	
-
-	/**
-	 * Setters for base properties
-	 */	
-	void SetS(double s);
-	void SetA(double a);
-	void SetB(double b);
-	void SetC(double c);
-	void SetD(double d);
-	
-
-	/**
-	 * Getters for base properties
-	 */		
-	double GetS();
-	double GetA();
-	double GetB();
-	double GetC();
-	double GetD();
-	
-
-	/**
-	 * Method to check if sample S is inside the record interval
-	 */	
-	bool CheckInterval (double s_check);
-
-	/**
-	 * Returns the value at sample S
-	 */	
-	double GetValue(double s_check);
-
-};
-//----------------------------------------------------------------------------------
-
-
-
-#endif

+ 0 - 1252
src/tool/tool_xodrobj/OpenDrive/Road.cpp

@@ -1,1252 +0,0 @@
-#include "Road.h"
-#define _USE_MATH_DEFINES
-#include <math.h>
-
-
-
-
-//***********************************************************************************
-//Road segment
-//***********************************************************************************
-/**
- * Constructor 
- */
-Road::Road()
-{	
-	mPredecessor=NULL; mSuccessor=NULL; mNeighbor1=NULL; mNeighbor2=NULL;	
-}
-
-/**
- * Constructor that initializes the road with basic properties
- * 
- * @param name Name of the road
- * @param length Length of the road
- * @param id Unique ID of the road
- * @param junction ID of the junction, this road might be a part of
- */
-Road::Road(string name, double length, string id, string junction)
-{	
-	mPredecessor=NULL; mSuccessor=NULL; mNeighbor1=NULL; mNeighbor2=NULL;	mName=name; mLength=length; mId=id; mJunction=junction;
-}
-
-/**
- * Copy constructor
- */
-Road::Road (const Road& road)
-{
-	mName=road.mName;
-	mLength=road.mLength;
-	mId=road.mId;
-	mJunction=road.mJunction;
-
-	mPredecessor=NULL;
-	mSuccessor=NULL;
-	mNeighbor1=NULL;
-	mNeighbor2=NULL;
-
-	if (road.mPredecessor!=NULL)
-		mPredecessor = new RoadLink(road.mPredecessor->GetElementType(), road.mPredecessor->GetElementId(), road.mPredecessor->GetContactPoint());
-	if (road.mSuccessor!=NULL)
-		mSuccessor = new RoadLink(road.mSuccessor->GetElementType(), road.mSuccessor->GetElementId(), road.mSuccessor->GetContactPoint());
-	if (road.mNeighbor1!=NULL)
-		mNeighbor1 = new RoadNeighbor(road.mNeighbor1->GetSide(), road.mNeighbor1->GetElementId(), road.mNeighbor1->GetDirection());
-	if (road.mNeighbor2!=NULL)
-		mNeighbor2 = new RoadNeighbor(road.mNeighbor2->GetSide(), road.mNeighbor2->GetElementId(), road.mNeighbor2->GetDirection());
-
-	mRoadTypeVector=road.mRoadTypeVector;
-	mGeometryBlockVector=road.mGeometryBlockVector;
-	mElevationVector=road.mElevationVector;
-	mSuperElevationVector=road.mSuperElevationVector;
-	mCrossfallVector=road.mCrossfallVector;
-	mLaneSectionsVector=road.mLaneSectionsVector;
-	mObjectsVector=road.mObjectsVector;
-	mSignalsVector=road.mSignalsVector;
-}
-
-/**
- * Assignment operator overload
- */
-const Road& Road::operator=(const Road& otherRoad)
-{
-	if (this!= &otherRoad)
-	{
-		mName=otherRoad.mName;
-		mLength=otherRoad.mLength;
-		mId=otherRoad.mId;
-		mJunction=otherRoad.mJunction;
-
-		delete mPredecessor;
-		delete mSuccessor;
-		delete mNeighbor1;
-		delete mNeighbor2;
-
-		mPredecessor=NULL;
-		mSuccessor=NULL;
-		mNeighbor1=NULL;
-		mNeighbor2=NULL;
-
-		if (otherRoad.mPredecessor!=NULL)
-			mPredecessor = new RoadLink(otherRoad.mPredecessor->GetElementType(), otherRoad.mPredecessor->GetElementId(), otherRoad.mPredecessor->GetContactPoint());
-		if (otherRoad.mSuccessor!=NULL)
-			mSuccessor = new RoadLink(otherRoad.mSuccessor->GetElementType(), otherRoad.mSuccessor->GetElementId(), otherRoad.mSuccessor->GetContactPoint());
-		if (otherRoad.mNeighbor1!=NULL)
-			mNeighbor1 = new RoadNeighbor(otherRoad.mNeighbor1->GetSide(), otherRoad.mNeighbor1->GetElementId(), otherRoad.mNeighbor1->GetDirection());
-		if (otherRoad.mNeighbor2!=NULL)
-			mNeighbor2 = new RoadNeighbor(otherRoad.mNeighbor2->GetSide(), otherRoad.mNeighbor2->GetElementId(), otherRoad.mNeighbor2->GetDirection());
-
-		mRoadTypeVector=otherRoad.mRoadTypeVector;
-		mGeometryBlockVector=otherRoad.mGeometryBlockVector;
-		mElevationVector=otherRoad.mElevationVector;
-		mSuperElevationVector=otherRoad.mSuperElevationVector;
-		mCrossfallVector=otherRoad.mCrossfallVector;
-		mLaneSectionsVector=otherRoad.mLaneSectionsVector;
-		mObjectsVector=otherRoad.mObjectsVector;
-		mSignalsVector=otherRoad.mSignalsVector;
-	}
-	return *this;
-}
-//-------------------------------------------------
-
-/**
- * Recalculates the chordline geometry of the road
- */
-void Road::RecalculateGeometry()
-{
-	// Goes through geometry blocks and recalculates their coordinates and headings starting with the second record
-	// so the second geometry will start at the coordinates where the first one ended
-	double length=0;
-	unsigned int lGeometryVectorSize = mGeometryBlockVector.size();
-	if(lGeometryVectorSize>0)
-	{
-		double lS=0;
-		double lX=0;
-		double lY=0;
-		double lHdg=0;
-		mGeometryBlockVector.at(0).GetLastCoords(lS,lX,lY,lHdg);
-		length+=mGeometryBlockVector.at(0).GetBlockLength();
-
-		GeometryBlock *lGeometry;
-		for(unsigned int i=1; i<lGeometryVectorSize; i++)
-		{
-			lGeometry=&mGeometryBlockVector.at(i);
-			lGeometry->Recalculate(lS,lX,lY,lHdg);
-			lGeometry->GetLastCoords(lS,lX,lY,lHdg);
-			length+=lGeometry->GetBlockLength();
-		}
-	}
-
-	mLength=length;
-}
-
-/**
- * Getters for the basic properties of the road
- */
-string Road::GetRoadName() const
-{
-	return mName;
-}
-double Road::GetRoadLength() const
-{
-	return mLength;
-}
-string Road::GetRoadId() const
-{
-	return mId;
-}
-string Road::GetRoadJunction() const
-{
-	return mJunction;
-}
-
-/**
- * Getters for the linking properties of the road
- */
-RoadLink* Road::GetPredecessor()
-{	
-	return mPredecessor;	
-}
-RoadLink* Road::GetSuccessor()
-{	
-	return mSuccessor;	
-}
-RoadNeighbor* Road::GetNeighbor1()
-{	
-	return mNeighbor1;	
-}
-RoadNeighbor* Road::GetNeighbor2()
-{	
-	return mNeighbor2;	
-}
-
-
-/**
- * Getters for the child records and their vectors
- */
-// Road type records
-vector<RoadType> *Road::GetRoadTypeVector()
-{
-	return &mRoadTypeVector;
-}
-RoadType* Road::GetRoadType(unsigned int i)
-{	
-	if ((mRoadTypeVector.size()>0)&&(i<mRoadTypeVector.size()))
-		return &mRoadTypeVector.at(i);
-	else
-		return NULL;
-}
-unsigned int Road::GetRoadTypeCount()
-{
-	return mRoadTypeVector.size();
-}
-// Road geometry records
-vector<GeometryBlock> *Road::GetGeometryBlockVector()
-{
-	return &mGeometryBlockVector;
-}
-GeometryBlock* Road::GetGeometryBlock(unsigned int i)
-{	
-	if ((mGeometryBlockVector.size()>0)&&(i<mGeometryBlockVector.size()))
-		return &mGeometryBlockVector.at(i);
-	else
-		return NULL;
-}
-unsigned int Road::GetGeometryBlockCount()
-{
-	return mGeometryBlockVector.size();
-}
-// Road elevation records
-vector<Elevation> *Road::GetElevationVector()
-{
-	return &mElevationVector;
-}
-Elevation*	Road::GetElevation(unsigned int i)
-{	
-	if ((mElevationVector.size()>0)&&(i<mElevationVector.size()))
-		return &mElevationVector.at(i);
-	else
-		return NULL;
-}
-unsigned int Road::GetElevationCount()
-{
-	return mElevationVector.size();
-}
-// Road superelevation records
-vector<SuperElevation> *Road::GetSuperElevationVector()
-{
-	return &mSuperElevationVector;
-}
-SuperElevation*	Road::GetSuperElevation(unsigned int i)
-{	
-	if ((mSuperElevationVector.size()>0)&&(i<mSuperElevationVector.size()))
-		return &mSuperElevationVector.at(i);
-	else
-		return NULL;
-}
-unsigned int Road::GetSuperElevationCount()
-{
-	return mSuperElevationVector.size();
-}
-// Road crossfall records
-vector<Crossfall> *Road::GetCrossfallVector()
-{
-	return &mCrossfallVector;
-}
-Crossfall*	Road::GetCrossfall(unsigned int i)
-{	
-	if ((mCrossfallVector.size()>0)&&(i<mCrossfallVector.size()))
-		return &mCrossfallVector.at(i);
-	else
-		return NULL;
-}
-unsigned int Road::GetCrossfallCount()
-{
-	return mCrossfallVector.size();
-}
-// Road lane section records
-vector<LaneSection> *Road::GetLaneSectionVector()
-{
-	return &mLaneSectionsVector;
-}
-LaneSection*	Road::GetLaneSection(unsigned int i)
-{	
-	if ((mLaneSectionsVector.size()>0)&&(i<mLaneSectionsVector.size()))
-		return &mLaneSectionsVector.at(i);
-	else
-		return NULL;
-}
-unsigned int Road::GetLaneSectionCount()
-{
-	return mLaneSectionsVector.size();
-}
-// Road object records
-vector<Object> *Road::GetObjectVector()
-{
-	return &mObjectsVector;
-}
-Object*	Road::GetObject(unsigned int i)
-{	
-	if ((mObjectsVector.size()>0)&&(i<mObjectsVector.size()))
-		return &mObjectsVector.at(i);
-	else
-		return NULL;
-}
-unsigned int Road::GetObjectCount()
-{
-	return mObjectsVector.size();
-}
-// Road signal records
-vector<Signal> *Road::GetSignalVector()
-{
-	return &mSignalsVector;
-}
-Signal*	Road::GetSignal(unsigned int i)
-{	
-	if ((mSignalsVector.size()>0)&&(i<mSignalsVector.size()))
-		return &mSignalsVector.at(i);
-	else
-		return NULL;
-}
-unsigned int Road::GetSignalCount()
-{
-	return mSignalsVector.size();
-}
-//-------------------------------------------------
-
-/**
- * Getters for the last child records in their respective vectors
- */
-RoadType* Road::GetLastRoadType()
-{	
-	if (mRoadTypeVector.size()>0)
-		return &mRoadTypeVector.at(mRoadTypeVector.size()-1);
-	else
-		return NULL;
-}
-GeometryBlock* Road::GetLastGeometryBlock()
-{	
-	if (mGeometryBlockVector.size()>0)
-		return &mGeometryBlockVector.at(mGeometryBlockVector.size()-1);
-	else
-		return NULL;
-}
-Elevation*	Road::GetLastElevation()
-{	
-	if (mElevationVector.size()>0)
-		return &mElevationVector.at(mElevationVector.size()-1);
-	else
-		return NULL;
-}
-SuperElevation*	Road::GetLastSuperElevation()
-{	
-	if (mSuperElevationVector.size()>0)
-		return &mSuperElevationVector.at(mSuperElevationVector.size()-1);
-	else
-		return NULL;
-}
-Crossfall*	Road::GetLastCrossfall()
-{	
-	if (mCrossfallVector.size()>0)
-		return &mCrossfallVector.at(mCrossfallVector.size()-1);
-	else
-		return NULL;
-}
-LaneSection*	Road::GetLastLaneSection()
-{	
-	if (mLaneSectionsVector.size()>0)
-		return &mLaneSectionsVector.at(mLaneSectionsVector.size()-1);
-	else
-		return NULL;
-}
-Object*	Road::GetLastObject()
-{	
-	if (mObjectsVector.size()>0)
-		return &mObjectsVector.at(mObjectsVector.size()-1);
-	else
-		return NULL;
-}
-Signal*	Road::GetLastSignal()
-{	
-	if (mSignalsVector.size()>0)
-		return &mSignalsVector.at(mSignalsVector.size()-1);
-	else
-		return NULL;
-}
-
-
-/**
- * Getters for the last added child records in their respective vectors
- */
-RoadType* Road::GetLastAddedRoadType()
-{
-	if(mLastAddedRoadType<mRoadTypeVector.size())
-		return &mRoadTypeVector.at(mLastAddedRoadType);
-	else
-		return NULL;
-}
-GeometryBlock* Road::GetLastAddedGeometryBlock()
-{
-	if(mLastAddedGeometryBlock<mGeometryBlockVector.size())
-		return &mGeometryBlockVector.at(mLastAddedGeometryBlock);
-	else
-		return NULL;
-}
-Elevation* Road::GetLastAddedElevation()
-{
-	if(mLastAddedElevation<mElevationVector.size())
-		return &mElevationVector.at(mLastAddedElevation);
-	else
-		return NULL;
-}
-SuperElevation* Road::GetLastAddedSuperElevation()
-{
-	if(mLastAddedSuperElevation<mSuperElevationVector.size())
-		return &mSuperElevationVector.at(mLastAddedSuperElevation);
-	else
-		return NULL;
-}
-Crossfall* Road::GetLastAddedCrossfall()
-{
-	if(mLastAddedCrossfall<mCrossfallVector.size())
-		return &mCrossfallVector.at(mLastAddedCrossfall);
-	else
-		return NULL;
-}
-LaneSection* Road::GetLastAddedLaneSection()
-{
-	if(mLastAddedLaneSection<mLaneSectionsVector.size())
-		return &mLaneSectionsVector.at(mLastAddedLaneSection);
-	else
-		return NULL;
-}
-Object* Road::GetLastAddedObject()
-{
-	if(mLastAddedObject<mObjectsVector.size())
-		return &mObjectsVector.at(mLastAddedObject);
-	else
-		return NULL;
-}
-Signal* Road::GetLastAddedSignal()
-{
-	if(mLastAddedSignal<mSignalsVector.size())
-		return &mSignalsVector.at(mLastAddedSignal);
-	else
-		return NULL;
-}
-//-------------------------------------------------
-
-/**
- * Setters for the basic road properties
- */
-void Road::SetRoadName(string name)
-{
-	mName=name;
-}
-void Road::SetRoadLength(double length)
-{
-	mLength=length;
-}
-void Road::SetRoadId(string id)
-{
-	mId=id;
-}
-void Road::SetRoadJunction(string junction)
-{
-	mJunction=junction;
-}
-
-/**
- * Setters for the linking road properties
- */
-void Road::SetPredecessor(string elementType, string elementId, string contactPoint)
-{
-	if(mPredecessor!=NULL)
-	{
-		mPredecessor->SetElementType(elementType);
-		mPredecessor->SetElementId(elementId);
-		mPredecessor->SetContactPoint(contactPoint);
-	}
-	else mPredecessor = new RoadLink(elementType, elementId,contactPoint);	
-}
-void Road::SetSuccessor(string elementType, string elementId, string contactPoint)
-{
-	if(mSuccessor!=NULL)
-	{
-		mSuccessor->SetElementType(elementType);
-		mSuccessor->SetElementId(elementId);
-		mSuccessor->SetContactPoint(contactPoint);
-	}
-	else mSuccessor=new RoadLink(elementType, elementId,contactPoint);	
-}
-void Road::SetNeighbor(string side, string elementId, string direction)
-{
-	if (mNeighbor1==NULL)
-		mNeighbor1=new RoadNeighbor(side, elementId, direction);
-	else
-		mNeighbor2=new RoadNeighbor(side, elementId, direction);
-}
-void Road::SetNeighbor1(string side, string elementId, string direction)
-{
-	if (mNeighbor1==NULL) mNeighbor1=new RoadNeighbor(side, elementId, direction);
-}
-void Road::SetNeighbor2(string side, string elementId, string direction)
-{
-	if (mNeighbor2==NULL) mNeighbor2=new RoadNeighbor(side, elementId, direction);
-}
-
-/**
- * Removers for the linking road properties
- */
-void Road::RemovePredecessor()
-{
-	if(mPredecessor!=NULL)
-	{
-		delete mPredecessor;
-		mPredecessor = NULL;
-	}
-}
-void Road::RemoveSuccessor()
-{
-	if(mSuccessor!=NULL)
-	{
-		delete mSuccessor;
-		mSuccessor = NULL;
-	}
-}
-void Road::RemoveNeighbor1()
-{
-	if(mNeighbor1!=NULL)
-	{
-		delete mNeighbor1;
-		mNeighbor1 = NULL;
-	}
-}
-void Road::RemoveNeighbor2()
-{
-	if(mNeighbor2!=NULL)
-	{
-		delete mNeighbor2;
-		mNeighbor2 = NULL;
-	}
-}
-//-------------------------------------------------
-
-/**
- * Methods used to add child records to the respective vectors
- */
-unsigned int Road::AddRoadType(double s, string type)
-{	
-	// Gets the index where the record should be inserted in the vector
-	unsigned int index = CheckRoadTypeInterval(s)+1;
-	// If larger than the record count - push to the back
-	if(index>=GetRoadTypeCount()) mRoadTypeVector.push_back(RoadType(s, type));
-	// else insert in the middle
-	else mRoadTypeVector.insert(mRoadTypeVector.begin()+index, RoadType(s, type));
-	// Save the last added record index
-	mLastAddedRoadType=index;
-	return index;
-}
-//-------------
-unsigned int Road::AddGeometryBlock()
-{	
-	// Check the first method in the group for details
-
-	unsigned int index=GetGeometryBlockCount();
-	mGeometryBlockVector.push_back(GeometryBlock());
-	mLastAddedGeometryBlock=index;
-	return index;
-}
-//-------------
-unsigned int Road::AddElevation(double s, double a, double b, double c, double d)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckElevationInterval(s)+1;
-	if(index>=GetElevationCount()) mElevationVector.push_back(Elevation(s,a,b,c,d));
-	else mElevationVector.insert(mElevationVector.begin()+index, Elevation(s,a,b,c,d));
-	mLastAddedElevation=index;
-	return index;
-}
-//-------------
-unsigned int Road::AddSuperElevation(double s, double a, double b, double c, double d)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckSuperElevationInterval(s)+1;
-	if(index>=GetSuperElevationCount()) mSuperElevationVector.push_back(SuperElevation(s,a,b,c,d));
-	else mSuperElevationVector.insert(mSuperElevationVector.begin()+index, SuperElevation(s,a,b,c,d));
-	mLastAddedSuperElevation=index;
-	return index;
-}
-//-------------
-unsigned int Road::AddCrossfall (string side, double s, double a, double b, double c, double d)
-{	
-	// Check the first method in the group for details
-
-	unsigned int index = CheckCrossfallInterval(s)+1;
-	if(index>=GetCrossfallCount()) mCrossfallVector.push_back(Crossfall(side,s,a,b,c,d));
-	else mCrossfallVector.insert(mCrossfallVector.begin()+index, Crossfall(side,s,a,b,c,d));
-	mLastAddedCrossfall=index;
-	return index;
-}
-//-------------
-unsigned int Road::AddLaneSection(double s)
-{
-	// Check the first method in the group for details
-
-	unsigned int index = CheckLaneSectionInterval(s)+1;
-	if(index>=GetLaneSectionCount()) mLaneSectionsVector.push_back(LaneSection(s));
-	else mLaneSectionsVector.insert(mLaneSectionsVector.begin()+index, LaneSection(s));
-	mLastAddedLaneSection=index;
-	return index;
-}
-//-------------
-unsigned int Road::AddObject()
-{	
-	// Check the first method in the group for details
-
-	unsigned int index=GetObjectCount();
-	mObjectsVector.push_back(Object());
-	mLastAddedObject=index;
-	return index;
-}
-//-------------
-unsigned int Road::AddSignal()
-{
-	// Check the first method in the group for details
-
-	unsigned int index=GetSignalCount();
-	mSignalsVector.push_back(Signal());	
-	mLastAddedSignal=index;
-	return index;
-}
-//-----------
-
-
-/**
- * Methods used to clone child records in the respective vectors
- */
-unsigned int Road::CloneRoadType(unsigned int index)
-{
-	// Clone the object and insert it in the middle of the vector
-	if(index<mRoadTypeVector.size()-1)
-		mRoadTypeVector.insert(mRoadTypeVector.begin()+index+1, mRoadTypeVector[index]);
-	// or just push it to the back
-	else if(index==mRoadTypeVector.size()-1)
-		mRoadTypeVector.push_back(mRoadTypeVector[index]);
-	// Save the last added record index
-	mLastAddedRoadType=index+1;
-	return mLastAddedRoadType;
-}
-unsigned int Road::CloneElevation(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mElevationVector.size()-1)
-		mElevationVector.insert(mElevationVector.begin()+index+1, mElevationVector[index]);
-	else if(index==mElevationVector.size()-1)
-		mElevationVector.push_back(mElevationVector[index]);
-	mLastAddedElevation=index+1;
-	return mLastAddedElevation;
-}
-unsigned int Road::CloneSuperElevation(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mSuperElevationVector.size()-1)
-		mSuperElevationVector.insert(mSuperElevationVector.begin()+index+1, mSuperElevationVector[index]);
-	else if(index==mSuperElevationVector.size()-1)
-		mSuperElevationVector.push_back(mSuperElevationVector[index]);
-	mLastAddedSuperElevation=index+1;
-	return mLastAddedSuperElevation;
-}
-unsigned int Road::CloneCrossfall(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mCrossfallVector.size()-1)
-		mCrossfallVector.insert(mCrossfallVector.begin()+index+1, mCrossfallVector[index]);
-	else if(index==mCrossfallVector.size()-1)
-		mCrossfallVector.push_back(mCrossfallVector[index]);
-	mLastAddedCrossfall=index+1;
-	return mLastAddedCrossfall;
-}
-unsigned int Road::CloneLaneSection(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mLaneSectionsVector.size()-1)
-		mLaneSectionsVector.insert(mLaneSectionsVector.begin()+index+1, mLaneSectionsVector[index]);
-	else if(index==mLaneSectionsVector.size()-1)
-		mLaneSectionsVector.push_back(mLaneSectionsVector[index]);
-	mLastAddedLaneSection=index+1;
-	return mLastAddedLaneSection;
-}
-unsigned int Road::CloneLaneSectionEnd(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	// Clones the lane section, duplicating only the last records in each child category
-	LaneSection lNewLaneSection(mLaneSectionsVector[index].GetS());
-	unsigned int iLaneCount=mLaneSectionsVector[index].GetLaneCount();
-
-	double lHighestS = 0;
-
-	for(unsigned int iLane=0; iLane<iLaneCount; iLane++)
-	{
-		Lane *lLane = mLaneSectionsVector[index].GetLane(iLane);
-		lNewLaneSection.AddLane(lLane->GetSide(), lLane->GetId(), lLane->GetType(), lLane->GetLevel(),false);
-
-		Lane *lNewLane = lNewLaneSection.GetLastAddedLane();
-
-		//width
-		LaneWidth *lWidth = lLane->GetLaneWidth(lLane->GetLaneWidthCount()-1);
-		if(lWidth!=NULL) 
-		{
-			lNewLane->AddWidthRecord(0.0, lWidth->GetA(), lWidth->GetB(), lWidth->GetC(), lWidth->GetD());
-			if(lWidth->GetS()>lHighestS) lHighestS=lWidth->GetS();
-		}
-
-		//road mark
-		LaneRoadMark *lRoadMark = lLane->GetLaneRoadMark(lLane->GetLaneRoadMarkCount()-1);
-		if(lRoadMark!=NULL) 
-		{
-			lNewLane->AddRoadMarkRecord(0.0, lRoadMark->GetType(), lRoadMark->GetWeight(), lRoadMark->GetColor(), lRoadMark->GetWidth(), lRoadMark->GetLaneChange());
-			if(lRoadMark->GetS()>lHighestS) lHighestS=lRoadMark->GetS();
-		}
-
-		//material
-		LaneMaterial *lMaterial = lLane->GetLaneMaterial(lLane->GetLaneMaterialCount()-1);
-		if(lMaterial!=NULL) 
-		{
-			lNewLane->AddMaterialRecord(0.0, lMaterial->GetSurface(), lMaterial->GetFriction(), lMaterial->GetRoughness());
-			if(lMaterial->GetS()>lHighestS) lHighestS=lMaterial->GetS();
-		}
-
-		//visibility
-		LaneVisibility *lVisibility = lLane->GetLaneVisibility(lLane->GetLaneVisibilityCount()-1);
-		if(lVisibility!=NULL) 
-		{
-			lNewLane->AddVisibilityRecord(0.0, lVisibility->GetForward(), lVisibility->GetBack(), lVisibility->GetLeft(), lVisibility->GetRight());
-			if(lVisibility->GetS()>lHighestS) lHighestS=lVisibility->GetS();
-		}
-
-		//speed
-		LaneSpeed *lSpeed = lLane->GetLaneSpeed(lLane->GetLaneSpeedCount()-1);
-		if(lSpeed!=NULL) 
-		{
-			lNewLane->AddSpeedRecord(0.0, lSpeed->GetMax());
-			if(lSpeed->GetS()>lHighestS) lHighestS=lSpeed->GetS();
-		}
-
-		//access
-		LaneAccess *lAccess = lLane->GetLaneAccess(lLane->GetLaneAccessCount()-1);
-		if(lAccess!=NULL) 
-		{
-			lNewLane->AddAccessRecord(0.0, lAccess->GetRestriction());
-			if(lAccess->GetS()>lHighestS) lHighestS=lAccess->GetS();
-		}
-
-		//height
-		LaneHeight *lHeight = lLane->GetLaneHeight(lLane->GetLaneHeightCount()-1);
-		if(lHeight!=NULL) 
-		{
-			lNewLane->AddHeightRecord(0.0, lHeight->GetInner(), lHeight->GetOuter());
-			if(lHeight->GetS()>lHighestS) lHighestS=lHeight->GetS();
-		}
-	}
-
-	lHighestS += mLaneSectionsVector[index].GetS();
-
-	if(index+1 < mLaneSectionsVector.size())
-	{
-		if(lHighestS < mLaneSectionsVector[index+1].GetS())
-			lNewLaneSection.SetS(lHighestS);
-	}
-
-
-	if(index<mLaneSectionsVector.size()-1)
-		mLaneSectionsVector.insert(mLaneSectionsVector.begin()+index+1, lNewLaneSection);
-	else if(index==mLaneSectionsVector.size()-1)
-		mLaneSectionsVector.push_back(lNewLaneSection);
-	mLastAddedLaneSection=index+1;
-	return mLastAddedLaneSection;
-}
-unsigned int Road::CloneObject(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mSignalsVector.size()-1)
-		mSignalsVector.insert(mSignalsVector.begin()+index+1, mSignalsVector[index]);
-	else if(index==mSignalsVector.size()-1)
-		mSignalsVector.push_back(mSignalsVector[index]);
-	mLastAddedObject=index+1;
-	return mLastAddedObject;
-}
-unsigned int Road::CloneSignal(unsigned int index)
-{
-	// Check the first method in the group for details
-
-	if(index<mSignalsVector.size()-1)
-		mSignalsVector.insert(mSignalsVector.begin()+index+1, mSignalsVector[index]);
-	else if(index==mSignalsVector.size()-1)
-		mSignalsVector.push_back(mSignalsVector[index]);
-	mLastAddedSignal=index+1;
-	return mLastAddedSignal;
-}
-
-/**
- * Methods used to delete child records from the respective vectors
- */
-void Road::DeleteRoadType(unsigned int index)
-{
-	mRoadTypeVector.erase(mRoadTypeVector.begin()+index);
-}
-void Road::DeleteGeometryBlock(unsigned int index)
-{
-	mGeometryBlockVector.erase(mGeometryBlockVector.begin()+index);
-}
-void Road::DeleteElevation(unsigned int index)
-{
-	mElevationVector.erase(mElevationVector.begin()+index);
-}
-void Road::DeleteSuperElevation(unsigned int index)
-{
-	mSuperElevationVector.erase(mSuperElevationVector.begin()+index);
-}
-void Road::DeleteCrossfall(unsigned int index)
-{
-	mCrossfallVector.erase(mCrossfallVector.begin()+index);
-}
-void Road::DeleteLaneSection(unsigned int index)
-{
-	mLaneSectionsVector.erase(mLaneSectionsVector.begin()+index);
-}
-void Road::DeleteObject(unsigned int index)
-{
-	mObjectsVector.erase(mObjectsVector.begin()+index);
-}
-void Road::DeleteSignal(unsigned int index)
-{
-	mSignalsVector.erase(mSignalsVector.begin()+index);
-}
-
-//-------------------------------------------------
-// EVALUATION METHODS
-
-/**
- * Geometry evaluation
- */
-bool Road::CheckGeometryInterval (double s_check)
-{
-	string tmp;
-	return CheckGeometryInterval(s_check,tmp);
-}
-//-----------
-bool Road::CheckGeometryInterval (double s_check, string &roadId)
-{
-	for (unsigned int i=0;i<mGeometryBlockVector.size();i++)
-	{
-		if (mGeometryBlockVector.at(i).CheckInterval(s_check))
-		{
-			roadId=mId;
-			return true;
-		}
-	}
-	roadId="N/A";
-	return false;
-}
-//-----------
-short int Road::GetGeometryCoords(double s_check, double &retX, double &retY)
-{
-	double tmp;
-	return GetGeometryCoords(s_check,retX,retY, tmp);
-}
-//-------------
-short int Road::GetGeometryCoords(double s_check, double &retX, double &retY, double &retHDG)
-{
-	//go trough all of the blocks
-	for (unsigned int i=0; i<mGeometryBlockVector.size();i++)
-	{
-		//Check the block and get coords.
-		short int res=mGeometryBlockVector.at(i).GetCoords(s_check,retX,retY, retHDG);
-		// If the returned value is one of the geometry types (for 0=line,1=arc and 2=spiral) then the result has been found and parameters filled, so, return the value
-		if (res>=0  ) 
-			return res;
-	}
-	//if s_check does not belong to the road, return -999
-	return -999;
-}
-//-----------
-
-/**
- * Other evaluation
- */
-int  Road::CheckRoadTypeInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the road type records
-	for (unsigned int i=0;i<mRoadTypeVector.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (s_check >= mRoadTypeVector.at(i).GetS())
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-//-----------
-string  Road::GetRoadTypeValue(double s_check)
-{
-	string retType="unknown";
-	//find the record where s_check belongs
-	int index=	CheckRoadTypeInterval(s_check);
-	//If found, return the type
-	if (index>=0)
-		retType= mRoadTypeVector.at(index).GetType();
-	return retType;
-}
-//-----------
-int  Road::CheckElevationInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the road type records
-	for (unsigned int i=0;i<mElevationVector.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (mElevationVector.at(i).CheckInterval(s_check))
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-//-----------
-double  Road::GetElevationValue (double s_check)
-{
-	double retVal=0;
-	//find the record where s_check belongs
-	int index=CheckElevationInterval(s_check);
-	//If found, return the type
-	if (index>=0)
-		retVal= (mElevationVector.at(index).GetValue(s_check));
-	return retVal;
-
-}
-//-----------
-int  Road::CheckSuperElevationInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the road type records
-	for (unsigned int i=0;i<mSuperElevationVector.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (mSuperElevationVector.at(i).CheckInterval(s_check))
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-//-----------
-double  Road::GetSuperElevationValue (double s_check)
-{
-	double retVal=0;
-	//find the record where s_check belongs
-	int index=CheckSuperElevationInterval(s_check);
-	//If found, return the type
-	if (index>=0)
-		retVal= (mSuperElevationVector.at(index).GetValue(s_check));
-
-	return retVal;
-}
-//-----------
-int  Road::CheckCrossfallInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the road type records
-	for (unsigned int i=0;i<mCrossfallVector.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (mCrossfallVector.at(i).CheckInterval(s_check))
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-//-----------
-void  Road::GetCrossfallValue (double s_check, double &angleLeft, double &angleRight)
-{
-	angleLeft=0.0;
-	angleRight=0.0;
-	//find the record where s_check belongs
-	int index=CheckCrossfallInterval(s_check);
-	//If found, return the type
-	string side;
-	double angle=0.0;
-	if (index>=0)
-	{
-		angle =(mCrossfallVector.at(index).GetValue(s_check));
-		side=(mCrossfallVector.at(index).GetSide());
-	}
-	
-	if (side.compare("left")==0)
-	{
-		angleLeft=-angle;
-	}
-	else if (side.compare("right")==0)
-	{
-		angleRight=-angle;
-	}
-	else
-	{
-		angleLeft=-angle;
-		angleRight=-angle;
-	}
-}
-//-----------
-int  Road::CheckLaneSectionInterval(double s_check)
-{
-	int res=-1;
-	//Go through all the lane section records
-	for (unsigned int i=0;i<mLaneSectionsVector.size();i++)
-	{
-		//check if the s_check belongs to the current record
-		if (mLaneSectionsVector.at(i).CheckInterval(s_check))
-			res=i;	//assign it to the result id
-		else 
-			break;	//if not, break;
-	}
-	return res;		//return the result: 0 to MaxInt as the index to the record containing s_check or -1 if nothing found
-}
-//-----------
-void  Road::FillLaneSectionSample(double s_check, LaneSectionSample& laneSectionSample)
-{
-	int index=CheckLaneSectionInterval(s_check);
-	if (index>=0)
-		mLaneSectionsVector.at(index).FillLaneSectionSample(s_check,laneSectionSample);
-}
-
-//-------------------------------------------------
-
-/**
- * Destructor
- */
-Road::~Road()
-{
-	delete mPredecessor;
-	delete mSuccessor;
-	delete mNeighbor1;
-	delete mNeighbor2;
-
-	// DELETING ROAD TYPES
-	mRoadTypeVector.clear();
-
-	// DELETING GEOMETRY BLOKS
-	mGeometryBlockVector.clear();
-
-	// DELETING ELEVATIONS
-	mElevationVector.clear();
-
-	// DELETING SUPERELEVATION
-	mSuperElevationVector.clear();
-
-	// DELETING CROSSFALL
-	mCrossfallVector.clear();
-
-	// DELETING LANE SECTIONS
-	mLaneSectionsVector.clear();
-
-	// DELETING OBJECTS
-	mObjectsVector.clear();
-
-	// DELETING SIGNALS
-	mSignalsVector.clear();
-}
-
-
-
-
-//***********************************************************************************
-//Road Link Record
-//***********************************************************************************
-/**
- * Constructor which intializes the basic properties
- */
-RoadLink::RoadLink(string elementType, string elementId, string contactPoint)
-{
-	mElementType=elementType;
-	mElementId=elementId;
-	mContactPoint=contactPoint;
-}
-
-/**
- * Getters for the basic properties
- */
-string RoadLink::GetElementType()
-{	
-	return mElementType;	
-}
-string RoadLink::GetElementId()
-{	
-	return mElementId;	
-}
-string RoadLink::GetContactPoint()
-{	
-	return mContactPoint;	
-}
-
-/**
- * Setters for the basic properties
- */
-void RoadLink::SetElementType(string elementType)
-{	
-	mElementType=elementType;	
-}
-void RoadLink::SetElementId(string elementId)
-{	
-	mElementId=elementId;
-}
-void RoadLink::SetContactPoint(string contactPoint)
-{	
-	mContactPoint=contactPoint;	
-}
-
-
-//***********************************************************************************
-//Road Neighbor Record
-//***********************************************************************************
-/**
- * Constructor which intializes the basic properties
- */
-RoadNeighbor::RoadNeighbor(string side, string elementId, string direction)
-{
-	mSide=side;
-	mElementId=elementId;
-	mDirection=direction;
-}
-/**
- * Getters for the basic properties
- */
-string RoadNeighbor::GetSide()
-{	
-	return mSide;	
-}
-string RoadNeighbor::GetElementId()
-{	
-	return mElementId;	
-}
-string RoadNeighbor::GetDirection()
-{	
-	return mDirection;	
-}
-
-/**
- * Setters for the basic properties
- */
-void RoadNeighbor::SetSide(string side)
-{	
-	mSide=side;	
-}
-void RoadNeighbor::SetElementId(string elementId)
-{	
-	mElementId=elementId;	
-}
-void RoadNeighbor::SetDirection(string direction)
-{	
-	mDirection=direction;	
-}
-
-
-//***********************************************************************************
-//Road Type
-//***********************************************************************************
-/**
- * Constructor which intializes the basic properties
- */
-RoadType::RoadType (double s, string type)
-{	
-	mS=s; mType=type;	
-}
-
-/**
- * Setters for the basic properties
- */
-void RoadType::SetS(double value)
-{
-	mS=value;
-}
-void RoadType::SetType(string type)
-{
-	mType=type;
-}
-
-/**
- * Getters for the basic properties
- */
-double RoadType::GetS()
-{
-	return mS;
-}
-string RoadType::GetType()
-{
-	return mType;
-}
-
-
-
-
-//***********************************************************************************
-//Elevation record
-//***********************************************************************************
-/**
- * Constructor which intializes the basic properties
- */
-Elevation::Elevation(double s, double a, double b, double c, double d): ThirdOrderPolynom(s,a,b,c,d)
-{}
-
-
-
-
-
-//***********************************************************************************
-//Elevation record
-//***********************************************************************************
-/**
- * Constructor which intializes the basic properties
- */
-SuperElevation::SuperElevation(double s, double a, double b, double c, double d): ThirdOrderPolynom(s,a,b,c,d)
-{}
-
-
-
-
-
-//***********************************************************************************
-//Crossfall Record
-//***********************************************************************************
-/**
- * Constructor which intializes the basic properties
- */
-Crossfall::Crossfall (string side, double s, double a, double b, double c, double d):ThirdOrderPolynom(s,a,b,c,d)
-{	
-	mSide=side;	
-}
-
-/**
- * Getters for the crossfall side
- */
-string Crossfall::GetSide()
-{
-	return mSide;
-}
-
-/**
- * Setters for the crossfall side
- */
-void Crossfall::SetSide(string side)
-{
-	mSide=side;
-}
-

+ 0 - 489
src/tool/tool_xodrobj/OpenDrive/Road.h

@@ -1,489 +0,0 @@
-#ifndef ROAD_H
-#define ROAD_H
-
-#include <vector>
-#include <string>
-
-#include "RoadGeometry.h"
-#include "Lane.h"
-#include "Junction.h"
-#include "ObjectSignal.h"
-#include "OtherStructures.h"
-
-//--Prototypes--
-//road
-class Road;
-class RoadLink;
-class RoadNeighbor;
-class RoadType;
-class GeometryBlock;
-class Elevation;
-class SuperElevation;
-class Crossfall;
-//lanes
-class LaneSection;
-class LaneSectionSample;
-//objects, signals
-class Object;
-class Signal;
-//--------------
-
-using std::vector;
-using std::string;
-
-/**
- * One of the main classes in OpenDrive structure
- * Holds the properties of the Road record and vectors for child records
- * Has methods to add, clone, get and delete those child records
- * as well as evaluation methods used, for example, to render the road
- *
- */
-class Road
-{
-private:
-	// Main road record properties
-	string mName;
-	double mLength;
-	string mId;
-	string mJunction;
-
-	// Linking complex properties (have multiple sub-properties)
-	RoadLink* mPredecessor;
-	RoadLink* mSuccessor;
-	RoadNeighbor* mNeighbor1;
-	RoadNeighbor* mNeighbor2;
-
-	/**
-	 * Vectors used to store the child records of the road
-	 * such as chordline geometry, elevation profiles, etc
-	 */
-	// Road type vector
-	vector<RoadType> mRoadTypeVector;
-	// Geometry block vector
-	vector<GeometryBlock> mGeometryBlockVector; 
-	// Elevation Profile vector
-	vector<Elevation> mElevationVector;
-	// Superelevation vector
-	vector<SuperElevation> mSuperElevationVector;
-	// Crossfall vector
-	vector<Crossfall> mCrossfallVector;
-	// Lane Section vector
-	vector<LaneSection> mLaneSectionsVector;
-	// Objects vectors
-	vector<Object> mObjectsVector;
-	// Signal vector
-	vector<Signal> mSignalsVector;
-
-	/**
-	 * Indices of the last added child records
-	 */
-	unsigned int mLastAddedRoadType;
-	unsigned int mLastAddedGeometryBlock;
-	unsigned int mLastAddedElevation;
-	unsigned int mLastAddedSuperElevation;
-	unsigned int mLastAddedCrossfall;
-	unsigned int mLastAddedLaneSection;
-	unsigned int mLastAddedObject;
-	unsigned int mLastAddedSignal;
-
-public:
-	/**
-	 * Constructor
-	 */
-	Road();
-
-	/**
-	 * Constructor that initializes the road with base properties
-	 * 
-	 * @param name Name of the road
-	 * @param length Length of the road
-	 * @param id Unique ID of the road
-	 * @param junction ID of the junction, this road might be a part of
-	 */
-	Road(string name, double length, string id, string junction);
-
-	/**
-	 * Copy constructor
-	 */
-	Road (const Road& road);
-
-	/**
-	 * Assignment operator overload
-	 */
-	const Road& operator=(const Road& rhs);
-	//-------------------------------------------------
-
-	/**
-	 * Getters for the base properties of the road
-	 */
-	string GetRoadName() const;
-	double GetRoadLength() const;
-	string GetRoadId() const;
-	string GetRoadJunction() const;
-	
-	/**
-	 * Getters for the linking properties of the road
-	 */
-	RoadLink* GetPredecessor();
-	RoadLink* GetSuccessor();
-	RoadNeighbor* GetNeighbor1();
-	RoadNeighbor* GetNeighbor2();
-
-	/**
-	 * Getters for the child records and their vectors
-	 */
-	// Road type records
-	vector<RoadType> *GetRoadTypeVector();
-	RoadType* GetRoadType(unsigned int i);
-	unsigned int GetRoadTypeCount();
-	// Road geometry records
-	vector<GeometryBlock> *GetGeometryBlockVector();
-	GeometryBlock* GetGeometryBlock(unsigned int i);
-	unsigned int GetGeometryBlockCount();
-	// Road elevation records
-	vector<Elevation> *GetElevationVector();
-	Elevation*	GetElevation(unsigned int i);
-	unsigned int GetElevationCount();
-	// Road superelevation records
-	vector<SuperElevation> *GetSuperElevationVector();
-	SuperElevation*	GetSuperElevation(unsigned int i);
-	unsigned int GetSuperElevationCount();
-	// Road crossfall records
-	vector<Crossfall> *GetCrossfallVector();
-	Crossfall*	GetCrossfall(unsigned int i);
-	unsigned int GetCrossfallCount();
-	// Road lane section records
-	vector<LaneSection> *GetLaneSectionVector();
-	LaneSection*	GetLaneSection(unsigned int i);
-	unsigned int GetLaneSectionCount();
-	// Road object records
-	vector<Object> *GetObjectVector();
-	Object*	GetObject(unsigned int i);
-	unsigned int GetObjectCount();
-	// Road signal records
-	vector<Signal> *GetSignalVector();
-	Signal*	GetSignal(unsigned int i);
-	unsigned int GetSignalCount();
-	//-------------------------------------------------
-
-	/**
-	 * Getters for the last child records in their respective vectors
-	 */
-	RoadType*		GetLastRoadType();
-	GeometryBlock*	GetLastGeometryBlock();
-	Elevation*		GetLastElevation();
-	SuperElevation*	GetLastSuperElevation();
-	Crossfall*		GetLastCrossfall();
-	LaneSection*	GetLastLaneSection();
-	Object*			GetLastObject();
-	Signal*			GetLastSignal();
-
-	/**
-	 * Getters for the last added child records in their respective vectors
-	 */
-	RoadType*		GetLastAddedRoadType();
-	GeometryBlock*	GetLastAddedGeometryBlock();
-	Elevation*		GetLastAddedElevation();
-	SuperElevation*	GetLastAddedSuperElevation();
-	Crossfall*		GetLastAddedCrossfall();
-	LaneSection*	GetLastAddedLaneSection();
-	Object*			GetLastAddedObject();
-	Signal*			GetLastAddedSignal();
-
-	//-------------------------------------------------
-
-	/**
-	 * Setters for the base road properties
-	 */
-	void SetRoadName(string name);
-	void SetRoadLength(double length);
-	void SetRoadId(string roadId);
-	void SetRoadJunction(string junction);
-
-	/**
-	 * Setters for the linking road properties
-	 */
-	void SetPredecessor(string elementType, string elementId, string contactPoint);
-	void SetSuccessor(string elementType, string elementId, string contactPoint);
-	void SetNeighbor(string side, string elementId, string direction);
-	void SetNeighbor1(string side, string elementId, string direction);
-	void SetNeighbor2(string side, string elementId, string direction);
-	
-	/**
-	 * Removers for the linking road properties
-	 */
-	void RemovePredecessor();
-	void RemoveSuccessor();
-	void RemoveNeighbor1();
-	void RemoveNeighbor2();
-
-	//-------------------------------------------------
-
-	/**
-	 * Methods used to add child records to the respective vectors
-	 */
-	unsigned int AddRoadType(double s, string type);
-	unsigned int AddGeometryBlock();
-	unsigned int AddElevation(double s, double a, double b, double c, double d);
-	unsigned int AddSuperElevation(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 AddObject();
-	unsigned int AddSignal();
-
-	/**
-	 * Methods used to clone child records in the respective vectors
-	 */
-	unsigned int CloneRoadType(unsigned int index);
-	unsigned int CloneElevation(unsigned int index);
-	unsigned int CloneSuperElevation(unsigned int index);
-	unsigned int CloneCrossfall(unsigned int index);
-	unsigned int CloneLaneSection(unsigned int index);
-	unsigned int CloneLaneSectionEnd(unsigned int index);
-	unsigned int CloneObject(unsigned int index);
-	unsigned int CloneSignal(unsigned int index);
-
-	/**
-	 * Methods used to delete child records from the respective vectors
-	 */
-	void DeleteRoadType(unsigned int index);
-	void DeleteGeometryBlock(unsigned int index);
-	void DeleteElevation(unsigned int index);
-	void DeleteSuperElevation(unsigned int index);
-	void DeleteCrossfall(unsigned int index);
-	void DeleteLaneSection(unsigned int index);
-	void DeleteObject(unsigned int index);
-	void DeleteSignal(unsigned int index);
-	
-	//-------------------------------------------------
-
-	/**
-	 * Recalculates the chordline geometry of the road
-	 */
-	void RecalculateGeometry();
-
-	//-------------------------------------------------
-	// EVALUATION METHODS
-
-	/**
-	 * Geometry evaluation
-	 */
-	bool CheckGeometryInterval (double s_check);
-	bool CheckGeometryInterval (double s_check, string &roadId);
-	short int GetGeometryCoords(double s_check, double &retX, double &retY);
-	short int GetGeometryCoords(double s_check, double &retX, double &retY, double &retHDG);
-	
-
-	/**
-	 * Other evaluation
-	 */
-	int CheckRoadTypeInterval(double s_check);
-	string GetRoadTypeValue(double s_check);
-
-	int CheckElevationInterval(double s_check);
-	double GetElevationValue (double s_check);
-
-	int CheckSuperElevationInterval(double s_check);
-	double GetSuperElevationValue (double s_check);
-
-	int CheckCrossfallInterval(double s_check);
-	void GetCrossfallValue (double s_check, double &angleLeft, double &angleRight);
-
-	int CheckLaneSectionInterval(double s_check);
-	void FillLaneSectionSample(double s_check, LaneSectionSample &laneSectionSample);
-	
-	//-------------------------------------------------
-
-	/**
-	 * Destructor
-	 */
-	~Road();
-};
-
-
-//----------------------------------------------------------------------------------
-/**
- * RoadLink class is used to store information about road's predecessors/successors
- *
- *
- *
- *
- */
-class RoadLink
-{
-private:
-	/**
-	 * Base properties of a successor/predecessor record
-	 */
-	string mElementType;
-	string mElementId;
-	string mContactPoint;
-public:
-	/**
-	 * Constructor which intializes the base properties
-	 */
-	RoadLink(string elementType, string elementId, string contactPoint);
-	
-	/**
-	 * Setters for the base properties
-	 */
-	void SetElementType(string elementType);
-	void SetElementId(string elementId);
-	void SetContactPoint(string contactPoint);
-	
-
-	/**
-	 * Getters for the base properties
-	 */
-	string GetElementType();
-	string GetElementId();
-	string GetContactPoint();
-};
-
-
-
-//----------------------------------------------------------------------------------
-/**
- * RoadLink class is used to store information about road's neighbors
- *
- *
- *
- *
- */
-class RoadNeighbor
-{
-private:
-	/**
-	 * Base properties of a neighbor record
-	 */
-	string mSide;
-	string mElementId;
-	string mDirection;
-public:
-	/**
-	 * Constructor which intializes the base properties
-	 */
-	RoadNeighbor(string side, string elementId, string direction);
-	
-	/**
-	 * Setters for the base properties
-	 */
-	void SetSide(string side);
-	void SetElementId(string elementId);
-	void SetDirection(string direction);
-	
-	/**
-	 * Getters for the base properties
-	 */
-	string GetSide();
-	string GetElementId();
-	string GetDirection();
-};
-
-//----------------------------------------------------------------------------------
-/**
- * RoadType class is used to store information about a road type record
- *
- *
- *
- *
- */
-class RoadType
-{
-private:
-	/**
-	 * Base properties of a road type
-	 */
-	double mS;
-	string mType;
-public:
-	/**
-	 * Constructor which intializes the base properties
-	 */
-	RoadType (double s, string type);
-	
-	/**
-	 * Setters for the base properties
-	 */
-	void SetS(double value);
-	void SetType(string type);
-	
-	/**
-	 * Getters for the base properties
-	 */
-	double GetS();
-	string GetType();
-};
-
-//----------------------------------------------------------------------------------
-/**
- * Elevation class is used to store information about a road elevation record
- * It inherits the Polynom class and has no additional properties
- *
- *
- *
- */
-class Elevation : public ThirdOrderPolynom
-{
-public:
-	/**
-	 * Constructor which intializes the base properties
-	 */
-	Elevation(double s, double a, double b, double c, double d);
-};
-//----------------------------------------------------------------------------------
-
-
-/**
- * Superlevation class is used to store information about a road superelevation record
- * It inherits the Polynom class and has no additional properties
- *
- *
- *
- */
-class SuperElevation : public ThirdOrderPolynom
-{
-public:
-	/**
-	 * Constructor which intializes the base properties
-	 */
-	SuperElevation(double s, double a, double b, double c, double d);
-};
-//----------------------------------------------------------------------------------
-
-/**
- * Crossfall class is used to store information about a road superelevation record
- * It inherits the Polynom class and has one additional properties
- *
- *
- *
- */
-class Crossfall : public ThirdOrderPolynom
-{
-private:
-	/**
-	 * Base crossfall property
-	 */
-	string mSide;
-	
-public:
-	/**
-	 * Constructor which intializes the base properties
-	 */
-	Crossfall (string side, double s, double a, double b, double c, double d);
-	
-	/**
-	 * Setter for the crossfall side
-	 */
-	void SetSide(string side);
-	
-	/**
-	 * Getter for the crossfall side
-	 */
-	string GetSide();
-};
-
-//----------------------------------------------------------------------------------
-
-
-#endif

+ 0 - 853
src/tool/tool_xodrobj/OpenDrive/RoadGeometry.cpp

@@ -1,853 +0,0 @@
-#include "RoadGeometry.h"
-#define _USE_MATH_DEFINES
-#include <math.h>
-
-//#define PI 3.14159265358979323846264338327950288
-extern int fresnl( double , double *, double * );
-
-
-//***********************************************************************************
-//Road Geometry Base Class
-//***********************************************************************************
-/**
- * Constructor that initializes the base properties of teh record
- */
-RoadGeometry::RoadGeometry(double s, double x, double y, double hdg, double length)
-{
-	mS=s;	mX=x; mY=y, mHdg=hdg, mLength=length;
-	mS2=s+length;
-}
-
-/**
- * Computes the required vars
- */
-void RoadGeometry::ComputeVars()
-{}
-
-/**
- * Clones and returns the new geometry record
- */
-RoadGeometry* RoadGeometry::Clone() const
-{
-	return new RoadGeometry(mS,mX,mY, mHdg, mLength);
-}
-//-------------------------------------------------
-
-/**
- * Sets the type of the geometry
- * 0: Line, 1: Arc, 2: Spiral
- */
-void RoadGeometry::SetGeomType(short int geomType)
-{	
-	mGeomType = geomType;	
-}
-
-
-/**
- * Setter for the base properties
- */
-void RoadGeometry::SetBase(double s, double x, double y, double hdg, double length, bool recalculate)
-{
-	mS=s;
-	mX=x;
-	mY=y;
-	mHdg=hdg;
-	mLength=length;
-	mS2=mS+mLength;
-	if(recalculate) ComputeVars();
-}
-void RoadGeometry::SetS(double s)
-{
-	mS=s;
-	mS2=mS+mLength;
-	ComputeVars();
-}
-void RoadGeometry::SetX(double x)
-{
-	mX=x;
-}
-void RoadGeometry::SetY(double y)
-{
-	mY=y;
-}
-void RoadGeometry::SetHdg(double hdg)
-{
-	mHdg=hdg;
-	ComputeVars();
-}
-void RoadGeometry::SetLength(double length)
-{
-	mLength=length;
-	mS2=mS+mLength;
-	ComputeVars();
-}
-//-------------------------------------------------
-
-/**
- * Getter for the geometry type
- */
-short int RoadGeometry::GetGeomType()
-{	
-	return mGeomType;
-}
-
-/**
- * Getter for the base properties
- */
-double RoadGeometry::GetS()
-{
-	return mS;
-}
-double RoadGeometry::GetS2()
-{
-	return mS2;
-}
-double RoadGeometry::GetX()
-{
-	return mX;
-}
-double RoadGeometry::GetY()
-{
-	return mY;
-}
-double RoadGeometry::GetHdg()
-{
-	return mHdg;
-}
-double RoadGeometry::GetLength()
-{
-	return mLength;
-}
-
-//-------------------------------------------------
-
-/**
- * Checks if the sample S gets in the current block interval
- */
-bool RoadGeometry::CheckInterval (double s_check)
-{
-	if ((s_check >= mS) && (s_check<=mS2))
-		return true;
-	else
-		return false;
-}
-
-/**
- * Gets the coordinates at the sample S offset
- */
-void  RoadGeometry::GetCoords(double s_check, double &retX, double &retY)
-{
-	double tmp;
-	GetCoords(s_check, retX, retY, tmp);
-}
-void RoadGeometry::GetCoords(double s_check, double &retX, double &retY, double &retHDG)
-{}
-
-
-
-//***********************************************************************************
-//Line geometry 
-//***********************************************************************************
-/**
- * Constructor that initializes the base properties of the record
- */
-GeometryLine::GeometryLine (double s, double x, double y, double hdg, double length):	RoadGeometry(s, x, y, hdg, length)
-{	
-	SetGeomType(0);	
-}
-
-/**
- * Clones and returns the new geometry record
- */
-RoadGeometry* GeometryLine::Clone() const
-{
-	GeometryLine* ret=new GeometryLine(mS,mX,mY, mHdg, mLength);
-	return ret;
-}
-
-//-------------------------------------------------
-
-/**
- * Setter for the base properties
- */
-void GeometryLine::SetAll(double s, double x, double y, double hdg, double length)
-{
-	SetBase(s,x,y,hdg,length,false);
-	ComputeVars();
-}
-
-//-------------------------------------------------
-
-/**
- * Gets the coordinates at the sample S offset
- */
-void GeometryLine::GetCoords(double s_check, double &retX, double &retY, double &retHDG)
-{
-	double newLength=s_check-mS;
-	//find the end of the chord line
-	retX=mX+cos(mHdg)*newLength;
-	retY=mY+sin(mHdg)*newLength;
-
-	retHDG=mHdg;
-}
-
-
-
-
-
-//***********************************************************************************
-//Arc geometry
-//***********************************************************************************
-/**
- * Constructor that initializes the base properties of the record
- */
-GeometryArc::GeometryArc (double s, double x, double y, double hdg, double length, double curvature):	RoadGeometry(s, x, y, hdg, length)
-{
-    SetGeomType(2);
-	mCurvature=curvature;
-
-	ComputeVars();
-}
-
-/**
- * Computes the required vars
- */
-void GeometryArc::ComputeVars()
-{
-	double radius=0.0;
-	//if curvature is 0, radius is also 0, otherwise, radius is 1/curvature
-	if (fabs(mCurvature)>1.00e-15)
-	{
-		radius = fabs(1.0/mCurvature);
-	}
-	//calculate the start angle for the arc plot
-	if (mCurvature<=0)
-		mStartAngle=mHdg+M_PI_2; 
-	else
-		mStartAngle=mHdg-M_PI_2;
-
-	mCircleX=mX+cos(mStartAngle-M_PI)*radius;
-	mCircleY=mY+sin(mStartAngle-M_PI)*radius;
-}
-
-/**
- * Clones and returns the new geometry record
- */
-RoadGeometry* GeometryArc::Clone() const
-{
-	GeometryArc* ret=new GeometryArc(mS,mX,mY, mHdg, mLength, mCurvature);
-	return ret;
-}
-
-//-------------------------------------------------
-
-/**
- * Setter for the base properties
- */
-void GeometryArc::SetAll(double s, double x, double y, double hdg, double length, double curvature)
-{
-	SetBase(s,x,y,hdg,length,false);
-	mCurvature=curvature;
-	
-	ComputeVars();
-}
-void GeometryArc::SetCurvature(double curvature)
-{
-	mCurvature=curvature;
-	ComputeVars();
-}
-
-//-------------------------------------------------
-
-/**
- * Getter for the base properties
- */
-double GeometryArc::GetCurvature()
-{
-	return mCurvature;
-}
-
-//-------------------------------------------------
-
-/**
- * Gets the coordinates at the sample S offset
- */
-void GeometryArc::GetCoords(double s_check, double &retX, double &retY, double &retHDG)
-{
-	//s from the beginning of the segment
-	double currentLength = s_check - mS;
-	double endAngle=mStartAngle;
-	double radius=0.0;
-	//if curvature is 0, radius is also 0, so don't add anything to the initial radius, 
-	//otherwise, radius is 1/curvature so the central angle can be calculated and added to the initial direction
-	if (fabs(mCurvature)>1.00e-15)
-	{
-		endAngle+= currentLength/(1.0/mCurvature);
-		radius = fabs(1.0/mCurvature);
-	}
-
-	//coords on the arc for given s value
-	retX=mCircleX+cos(endAngle)*radius;
-	retY=mCircleY+sin(endAngle)*radius;
-
-	//heading at the given position
-	if (mCurvature<=0)
-		retHDG=endAngle-M_PI_2; 
-	else
-		retHDG=endAngle+M_PI_2;
-}
-
-
-
-
-
-
-//***********************************************************************************
-//Spiral geometry
-//***********************************************************************************
-const double GeometrySpiral::sqrtPiO2=sqrt(M_PI_2);
-/**
- * Constructor that initializes the base properties of the record
- */
-GeometrySpiral::GeometrySpiral (double s, double x, double y, double hdg, double length, double curvatureStart,double curvatureEnd):	RoadGeometry(s, x, y, hdg, length)
-{
-    SetGeomType(1);
-	mCurvatureStart=curvatureStart;
-	mCurvatureEnd=curvatureEnd;
-	ComputeVars();
-}
-
-/**
- * Computes the required vars
- */
-void GeometrySpiral::ComputeVars()
-{
-	mA=0;
-
-	//if the curvatureEnd is the non-zero curvature, then the motion is in normal direction along the spiral
-	if ((fabs(mCurvatureEnd)>1.00e-15)&&(fabs(mCurvatureStart)<=1.00e-15))
-	{
-		mNormalDir=true;
-		mCurvature=mCurvatureEnd;
-		//Calculate the normalization term : a = 1.0/sqrt(2*End_Radius*Total_Curve_Length) 
-		mA=1.0/sqrt(2*1.0/fabs(double(mCurvature))*mLength);			
-		//Denormalization Factor
-		mDenormalizeFactor=1.0/mA;	
-
-		//Calculate the sine and cosine of the heading angle used to rotate the spiral according to the heading
-		mRotCos=cos(mHdg);
-		mRotSin=sin(mHdg);
-	}
-	//else the motion is in the inverse direction along the spiral
-	else
-	{
-		mNormalDir=false;
-		mCurvature=mCurvatureStart;
-		//Calculate the normalization term : a = 1.0/sqrt(2*End_Radius*Total_Curve_Length) 
-		mA=1.0/sqrt(2*1.0/fabs(mCurvature)*mLength);			
-
-		//Because we move in the inverse direction, we need to rotate the curve according to the heading
-		//around the last point of the normalized spiral
-		//Calculate the total length, normalize it and divide by sqrtPiO2, then, calculate the position of the final point.
-		double L=(mS2-mS)*mA/sqrtPiO2;							
-		fresnl(L,&mEndY,&mEndX);
-		//Invert the curve if the curvature is negative
-		if (mCurvature<0)
-			mEndY=-mEndY;
-
-		//Denormalization factor
-		mDenormalizeFactor=1.0/mA;									
-		//Find the x,y coords of the final point of the curve in local curve coordinates
-		mEndX*=mDenormalizeFactor*sqrtPiO2;						
-		mEndY*=mDenormalizeFactor*sqrtPiO2;
-
-		//Calculate the tangent angle
-		differenceAngle=L*L*(sqrtPiO2*sqrtPiO2);
-		double diffAngle;
-		//Calculate the tangent and heading angle difference that will be used to rotate the spiral
-		if (mCurvature<0)
-		{
-			diffAngle=mHdg-differenceAngle-M_PI;
-		}
-		else
-		{
-			diffAngle=mHdg+differenceAngle-M_PI;
-		}
-
-		//Calculate the sine and cosine of the difference angle
-		mRotCos=cos(diffAngle);
-		mRotSin=sin(diffAngle);
-	}
-}
-
-/**
- * Clones and returns the new geometry record
- */
-RoadGeometry* GeometrySpiral::Clone() const
-{
-	GeometrySpiral* ret=new GeometrySpiral(mS,mX,mY, mHdg, mLength, mCurvatureStart, mCurvatureEnd);
-	return ret;
-}
-
-
-//-------------------------------------------------
-
-/**
- * Setter for the base properties
- */
-void GeometrySpiral::SetAll(double s, double x, double y, double hdg, double length, double curvatureStart,double curvatureEnd)
-{
-	SetBase(s,x,y,hdg,length,false);
-	mCurvatureStart=curvatureStart;
-	mCurvatureEnd=curvatureEnd;
-	ComputeVars();
-}
-void GeometrySpiral::SetCurvatureStart(double curvature)
-{
-	mCurvatureStart=curvature;
-	ComputeVars();
-}
-void GeometrySpiral::SetCurvatureEnd(double curvature)
-{
-	mCurvatureEnd=curvature;
-	ComputeVars();
-}
-
-//-------------------------------------------------
-
-/**
- * Getter for the base properties
- */
-double GeometrySpiral::GetCurvatureStart()
-{
-	return mCurvatureStart;
-}
-double GeometrySpiral::GetCurvatureEnd()
-{
-	return mCurvatureEnd;
-}
-
-//-------------------------------------------------
-/**
- * Gets the coordinates at the sample S offset
- */
-void GeometrySpiral::GetCoords(double s_check, double &retX, double &retY, double &retHDG)
-{
-	double l=0.0;
-	double tmpX=0.0, tmpY=0.0;
-
-	//Depending on the moving direction, calculate the length of the curve from its beginning to the current point and normalize
-	//it by multiplying with the "a" normalization term
-	//Cephes lib for solving Fresnel Integrals, uses cos/sin (PI/2 * X^2) format in its function.
-	//So, in order to use the function, transform the argument (which is just L) by dividing it by the sqrt(PI/2) factor and multiply the results by it.
-	if (mNormalDir)
-	{ 
-		l=(s_check-mS)*mA/sqrtPiO2;
-	}
-	else
-	{
-		l=(mS2-s_check)*mA/sqrtPiO2;		
-	}
-
-	//Solve the Fresnel Integrals
-	fresnl(l,&tmpY,&tmpX);
-	//If the curvature is negative, invert the curve on the Y axis
-	if (mCurvature<0)
-		tmpY=-tmpY;
-
-	//Denormalize the results and multiply by the sqrt(PI/2) term
-	tmpX*=mDenormalizeFactor*sqrtPiO2;	
-	tmpY*=mDenormalizeFactor*sqrtPiO2;
-
-	//Calculate the heading at the found position. Kill the sqrt(PI/2) term that was added to the L
-	l=(s_check-mS)*mA;
-	double tangentAngle = l*l;
-	if (mCurvature<0)
-		tangentAngle=-tangentAngle;
-	retHDG=mHdg+tangentAngle;
-
-
-	if (!mNormalDir)
-	{
-		//If we move in the inverse direction, translate the spiral in order to rotate around its final point
-		tmpX-=mEndX;	
-		tmpY-=mEndY;
-		//also invert the spiral in the y axis
-		tmpY=-tmpY;
-	}
-
-	//Translate the curve to the required position and rotate it according to the heading
-	retX=mX+ tmpX*mRotCos-tmpY*mRotSin;
-	retY=mY+ tmpY*mRotCos+tmpX*mRotSin;
-}
-
-
-
-
-
-//***********************************************************************************
-//Cubic Polynom geometry. Has to be implemented
-//***********************************************************************************
-/**
- * Constructor that initializes the base properties of the record
- */
-GeometryPoly3::GeometryPoly3 (double s, double x, double y, double hdg, double length, double a, double b,double c, double d ):	RoadGeometry(s, x, y, hdg, length)
-{	
-	SetGeomType(3); mA=a; mB=b; mC=c; mD=d;	
-}
-
-/**
- * Clones and returns the new geometry record
- */
-RoadGeometry* GeometryPoly3::Clone() const
-{
-	GeometryPoly3* ret=new GeometryPoly3(mS,mX,mY, mHdg, mLength, mA, mB, mC, mD);
-	return ret;
-}
-
-//-------------------------------------------------
-/**
- * Setter for the base properties
- */
-void GeometryPoly3::SetAll(double s, double x, double y, double hdg, double length, double a,double b,double c,double d)
-{
-	SetBase(s,x,y,hdg,length,false);
-	mA=a;
-	mB=b;
-	mC=c;
-	mD=d;
-	ComputeVars();
-}
-
-
-//***********************************************************************************
-//Cubic Polynom geometry. Has to be implemented.  Added By Yuchuli
-//***********************************************************************************
-
-/**
- * Constructor that initializes the base properties of the record
- */
-GeometryParamPoly3::GeometryParamPoly3 (double s, double x, double y, double hdg, double length,double ua,double ub,double uc,double ud,double va, double vb, double vc,double vd  ):	RoadGeometry(s, x, y, hdg, length)
-{
-    SetGeomType(4); muA=ua; muB=ub; muC=uc; muD=ud;mvA=va; mvB=vb; mvC=vc; mvD=vd;
-}
-
-/**
- * Clones and returns the new geometry record
- */
-RoadGeometry* GeometryParamPoly3::Clone() const
-{
-    GeometryParamPoly3* ret=new GeometryParamPoly3(mS,mX,mY, mHdg, mLength, muA, muB, muC, muD,mvA,mvB,mvC,mvD);
-    return ret;
-}
-
-//-------------------------------------------------
-/**
- * Setter for the base properties
- */
-void GeometryParamPoly3::SetAll(double s, double x, double y, double hdg, double length, double ua,double ub,double uc,double ud,double va, double vb, double vc,double vd )
-{
-    SetBase(s,x,y,hdg,length,false);
-    muA=ua;
-    muB=ub;
-    muC=uc;
-    muD=ud;
-    mvA=va;
-    mvB=vb;
-    mvC=vc;
-    mvD=vd;
-    ComputeVars();
-}
-
-double GeometryParamPoly3::GetuA(){return muA;}
-double GeometryParamPoly3::GetuB(){return muB;}
-double GeometryParamPoly3::GetuC(){return muC;}
-double GeometryParamPoly3::GetuD(){return muD;}
-double GeometryParamPoly3::GetvA(){return mvA;}
-double GeometryParamPoly3::GetvB(){return mvB;}
-double GeometryParamPoly3::GetvC(){return mvC;}
-double GeometryParamPoly3::GetvD(){return mvD;}
-
-//***********************************************************************************
-//Base class for Geometry blocks
-//***********************************************************************************
-/**
- * Constructor
- */
-GeometryBlock::GeometryBlock()
-{}
-
-/**
- * Copy constructor
- */
-GeometryBlock::GeometryBlock(const GeometryBlock& geomBlock)
-{
-	for (vector<RoadGeometry*>::const_iterator member = geomBlock.mGeometryBlockElement.begin();	member != geomBlock.mGeometryBlockElement.end();	 member++)
-		mGeometryBlockElement.push_back((*member)->Clone());
-
-}
-
-/**
- * Assignment operator overload
- */
-const GeometryBlock& GeometryBlock::operator=(const GeometryBlock& otherGeomBlock)
-{
-	if (this!= &otherGeomBlock)
-	{
-
-		for (vector<RoadGeometry*>::iterator member = mGeometryBlockElement.begin();	member != mGeometryBlockElement.end();	 member++)
-		{
-			if(GeometryLine *line = dynamic_cast<GeometryLine *>(*member))
-			{
-				delete line;
-			}
-			else if(GeometryArc *arc = dynamic_cast<GeometryArc *>(*member))
-			{
-				delete arc;
-			}
-			else if(GeometrySpiral *spiral = dynamic_cast<GeometrySpiral *>(*member))
-			{
-				delete spiral;
-			}
-			else if(GeometryPoly3 *poly = dynamic_cast<GeometryPoly3 *>(*member))
-			{
-				delete poly;
-			}
-		}
-		mGeometryBlockElement.clear();
-
-		for (vector<RoadGeometry*>::const_iterator member = otherGeomBlock.mGeometryBlockElement.begin();	member != otherGeomBlock.mGeometryBlockElement.end();	 member++)
-			mGeometryBlockElement.push_back((*member)->Clone());
-	}
-	return *this;
-}
-
-
-//-------------------------------------------------
-
-/**
- * Methods used to add geometry recors to the geometry record vector
- */
-void GeometryBlock::AddGeometryLine(double s, double x, double y, double hdg, double length)
-{	
-	mGeometryBlockElement.push_back(new GeometryLine(s, x, y, hdg, length));	
-}
-void GeometryBlock::AddGeometryArc(double s, double x, double y, double hdg, double length, double curvature)
-{	
-	mGeometryBlockElement.push_back(new GeometryArc(s, x, y, hdg, length, curvature));	
-}
-void GeometryBlock::AddGeometrySpiral(double s, double x, double y, double hdg, double length, double curvatureStart,double curvatureEnd)
-{	
-	mGeometryBlockElement.push_back(new GeometrySpiral(s, x, y, hdg, length, curvatureStart, curvatureEnd));	
-}
-void GeometryBlock::AddGeometryPoly3(double s, double x, double y, double hdg, double length, double a,double b,double c,double d)
-{	
-	mGeometryBlockElement.push_back(new GeometryPoly3(s, x, y, hdg, length, a, b, c, d));	
-}
-void GeometryBlock::AddGeometryParamPoly3(double s, double x, double y, double hdg, double length, double ua, double ub, double uc, double ud, double va, double vb, double vc, double vd)
-{
-    mGeometryBlockElement.push_back(new GeometryParamPoly3(s,x,y,hdg,length,ua,ub,uc,ud,va,vb,vc,vd));
-}
-
-//-------------------------------------------------
-
-/**
- * Getter for the geometry record at a given index position of the vector
- */
-RoadGeometry* GeometryBlock::GetGeometryAt(int index)
-{
-	return mGeometryBlockElement.at(index);
-}
-
-/**
- * Getter for the overal block length (summ of geometry record lengths)
- */
-double GeometryBlock::GetBlockLength()
-{
-	double lTotal=0;
-	for (unsigned int i=0;i<mGeometryBlockElement.size();i++)
-	{
-		lTotal+=mGeometryBlockElement.at(i)->GetLength();
-	}
-	return lTotal;
-}
-
-/**
- *  Checks if the block is a straight line block or a turn
- */
-bool GeometryBlock::CheckIfLine()
-{
-	if(mGeometryBlockElement.size()>1) return false;
-	else return true;
-}
-
-//-------------------------------------------------
-
-/**
- * Recalculates the geometry blocks when one of the geometry records is modified
- * Makes sure that every geometry records starts where the previous record ends
- */
-void GeometryBlock::Recalculate(double s, double x, double y, double hdg)
-{
-	double lS=s;
-	double lX=x;
-	double lY=y;
-	double lHdg=hdg;
-
-	if(mGeometryBlockElement.size()==1)
-	{
-		GeometryLine *lGeometryLine	=  static_cast<GeometryLine*>(mGeometryBlockElement.at(0));
-		if(lGeometryLine!=NULL)
-		{
-			// Updates the line to reflect the changes of the previous block
-			lGeometryLine->SetBase(lS,lX,lY,lHdg,lGeometryLine->GetLength());
-		}
-	}
-	else if(mGeometryBlockElement.size()==3)
-	{
-		GeometrySpiral *lGeometrySpiral1	=  static_cast<GeometrySpiral*>(mGeometryBlockElement.at(0));
-		GeometryArc *lGeometryArc			=  static_cast<GeometryArc*>(mGeometryBlockElement.at(1));
-		GeometrySpiral *lGeometrySpiral2	=  static_cast<GeometrySpiral*>(mGeometryBlockElement.at(2));
-		if(lGeometrySpiral1!=NULL && lGeometryArc!=NULL && lGeometrySpiral2!=NULL)
-		{
-			// Updates the first spiral to reflect the changes of the previous block
-			lGeometrySpiral1->SetBase(lS,lX,lY,lHdg,lGeometrySpiral1->GetLength());
-
-			// Reads the new coords of the spiral
-			lS=lGeometrySpiral1->GetS2();
-			lGeometrySpiral1->GetCoords(lS,lX,lY,lHdg);
-
-			// Updates the arc to reflect the changes to the first spiral
-			lGeometryArc->SetBase(lS,lX,lY,lHdg,lGeometryArc->GetLength());
-
-			// Reads the new coords of the arc
-			lS=lGeometryArc->GetS2();
-			lGeometryArc->GetCoords(lS,lX,lY,lHdg);
-
-			// Updates the second spiral to reflect hte changes to the arc
-			lGeometrySpiral2->SetBase(lS,lX,lY,lHdg,lGeometrySpiral2->GetLength());
-		}
-	}
-}
-
-//-------------------------------------------------
-
-/**
- *  Gets the S at the end of the block
- */
-double GeometryBlock::GetLastS2()
-{
-	if(mGeometryBlockElement.size()>0)
-		return mGeometryBlockElement.at(mGeometryBlockElement.size()-1)->GetS2();
-	else
-		return 0;
-}
-
-/**
- *  Gets the last geometry in the geometry vector
- */
-RoadGeometry* GeometryBlock::GetLastGeometry()
-{
-	return mGeometryBlockElement.at(mGeometryBlockElement.size()-1);
-}
-
-/**
- *  Gets the coordinates at the end of the last geometry
- */
-short int GeometryBlock::GetLastCoords(double &s, double &retX, double &retY, double &retHDG)
-{
-	int lSize = mGeometryBlockElement.size();
-	if(lSize>0)
-	{
-		RoadGeometry* lGeometry = mGeometryBlockElement.at(lSize-1);
-		s = lGeometry->GetS2();
-		lGeometry->GetCoords(s, retX, retY, retHDG);
-	}
-	else
-	{
-		s=0;
-		retX=0;
-		retY=0;
-		retHDG=0;
-	}
-	return 0;
-}
-
-/**
- *  Check if sample S belongs to this block
- */
-bool GeometryBlock::CheckInterval(double s_check)
-{
-	for (unsigned int i=0;i<mGeometryBlockElement.size();i++)
-	{
-		//if the s_check belongs to one of the geometries
-		if (mGeometryBlockElement.at(i)->CheckInterval(s_check))
-			return true;
-	}
-	return false;
-}
-
-/**
- *  Gets the coordinates at the sample S offset
- */
-short int GeometryBlock::GetCoords(double s_check, double &retX, double &retY)
-{
-	double tmp;
-	return GetCoords(s_check, retX, retY, tmp);
-}
-
-/**
- *  Gets the coordinates and heading at the end of the last geometry 
- */
-short int  GeometryBlock::GetCoords(double s_check, double &retX, double &retY, double &retHDG)
-{
-	// go through all the elements
-	for (unsigned int i=0;i<mGeometryBlockElement.size();i++)
-	{
-		//if the s_check belongs to one of the geometries
-		if (mGeometryBlockElement.at(i)->CheckInterval(s_check))
-		{
-			//get the x,y coords and return the type of the geometry
-			mGeometryBlockElement.at(i)->GetCoords(s_check, retX, retY, retHDG);
-			return mGeometryBlockElement.at(i)->GetGeomType();
-		}
-	}
-	//if nothing found, return -999
-	return -999;
-
-}
-
-//-------------------------------------------------
-/**
- *  Destructor
- */
-GeometryBlock::~GeometryBlock()
-{
-	// Clears the geometry record vector
-	for (vector<RoadGeometry*>::iterator member = mGeometryBlockElement.begin();	member != mGeometryBlockElement.end();	 member++)
-	{
-		if(GeometryLine *line = dynamic_cast<GeometryLine *>(*member))
-		{
-			delete line;
-		}
-		else if(GeometryArc *arc = dynamic_cast<GeometryArc *>(*member))
-		{
-			delete arc;
-		}
-		else if(GeometrySpiral *spiral = dynamic_cast<GeometrySpiral *>(*member))
-		{
-			delete spiral;
-		}
-		else if(GeometryPoly3 *poly = dynamic_cast<GeometryPoly3 *>(*member))
-		{
-			delete poly;
-		}
-        else if(GeometryParamPoly3 *parampoly = dynamic_cast<GeometryParamPoly3 *>(*member))
-        {
-            delete parampoly;
-        }
-	}
-	mGeometryBlockElement.clear();
-}
-
-//----------------------------------------------------------------------------------

+ 0 - 435
src/tool/tool_xodrobj/OpenDrive/RoadGeometry.h

@@ -1,435 +0,0 @@
-#ifndef ROADGEOMETRY_H
-#define ROADGEOMETRY_H
-
-#include <vector>
-#include <string>
-
-//Prototypes
-class RoadGeometry;
-class GeometryLine;
-class GeometrySpiral;
-class GeometryArc;
-
-using std::vector;
-using std::string;
-
-
-/**
- * RoadGeometry class is responsible for storing the basic chordline geometry properties
- *
- */
-class RoadGeometry
-{
-protected:
-	/**
-	 * Base record properties
-	 */
-	double mS;
-	double mX;
-	double mY;
-	double mHdg;
-	double mLength;
-	double mS2;
-    short int mGeomType;	//0-line, 1-arc, 2-spiral 3-poly3 4-parampoly3
-public:
-	/**
-	 * Constructor that initializes the base properties of teh record
-	 */
-	RoadGeometry(double s, double x, double y, double hdg, double length);
-	
-	/**
-	 * Clones and returns the new geometry record
-	 */
-	virtual RoadGeometry* Clone() const;
-	
-	//-------------------------------------------------
-
-	/**
-	 * Sets the type of the geometry
-	 * 0: Line, 1: Arc, 2: Spiral
-	 */
-	void SetGeomType(short int geomType);
-	
-	/**
-	 * Setter for the base properties
-	 */
-	void SetBase(double s, double x, double y, double hdg, double length, bool recalculate=true);
-	void SetS(double s);
-	void SetX(double x);
-	void SetY(double y);
-	void SetHdg(double hdg);
-	void SetLength(double length);
-
-	//-------------------------------------------------
-	/**
-	 * Getter for the geometry type
-	 */
-	short int GetGeomType();
-	
-	/**
-	 * Getter for the base properties
-	 */
-	double GetS();
-	double GetS2();
-	double GetX();
-	double GetY();
-	double GetHdg();
-	double GetLength();
-
-	//-------------------------------------------------
-
-	/**
-	 * Evaluation methods
-	 */
-	virtual bool CheckInterval (double s_check);
-	virtual void GetCoords(double s_check, double &retX, double &retY);
-	virtual void GetCoords(double s_check, double &retX, double &retY, double &retHDG);
-protected:
-
-	/**
-	 * Computes the required vars
-	 */
-	virtual void ComputeVars();
-};
-
-
-//----------------------------------------------------------------------------------
-/**
- * GeometryLine inherits the RoadGeometry class but adds no additional properties
- *
- */
-class GeometryLine:public RoadGeometry
-{
-public:
-	/**
-	 * Constructor that initializes the base properties of the record
-	 */
-	GeometryLine (double s, double x, double y, double hdg, double length);
-
-	/**
-	 * Clones and returns the new geometry record
-	 */
-	RoadGeometry* Clone() const;
-	
-	//-------------------------------------------------
-
-	/**
-	 * Setter for the base properties
-	 */
-	void SetAll(double s, double x, double y, double hdg, double length);
-
-	//-------------------------------------------------
-
-	/**
-	 * Gets the coordinates at the sample S offset
-	 */
-	void GetCoords(double s_check, double &retX, double &retY, double &retHDG);
-
-};
-//----------------------------------------------------------------------------------
-/**
- * GeometryArc inherits the RoadGeometry class and adds Curvature property
- *
- */
-class GeometryArc: public RoadGeometry
-{
-private:
-	/**
-	 * Base record properties
-	 */
-	double mCurvature;
-	
-	/**
-	 * Optimization related variables
-	 */ 
-	double mCircleX;
-	double mCircleY;
-
-	/**
-	 * Computation variables
-	 */
-	double mStartAngle;
-
-public:
-	/**
-	 * Constructor that initializes the base properties of the record
-	 */
-	GeometryArc (double s, double x, double y, double hdg, double length, double curvature);
-
-	/**
-	 * Clones and returns the new geometry record
-	 */
-	RoadGeometry* Clone() const;
-
-	//-------------------------------------------------
-	
-	/**
-	 * Setter for the base properties
-	 */
-	void SetAll(double s, double x, double y, double hdg, double length, double curvature);
-	void SetCurvature(double curvature);
-
-	//-------------------------------------------------
-
-	/**
-	 * Getter for the base properties
-	 */
-	double GetCurvature();
-	
-	//-------------------------------------------------
-
-	/**
-	 * Gets the coordinates at the sample S offset
-	 */
-	void GetCoords(double s_check, double &retX, double &retY, double &retHDG);
-protected:
-
-	/**
-	 * Computes the required vars
-	 */
-	virtual void ComputeVars();
-};
-
-
-
-//----------------------------------------------------------------------------------
-/**
- * GeometrySpiral inherits the RoadGeometry class and adds Curvature properties
- *
- */
-class GeometrySpiral: public RoadGeometry
-{
-private:
-	/**
-	 * Base record properties
-	 */
-	double mCurvatureStart;
-	double mCurvatureEnd;
-
-	/**
-	 * Computation variables
-	 */
-	static const double sqrtPiO2;
-	double mA;
-	double mCurvature;
-	double mDenormalizeFactor;
-	double mEndX;
-	double mEndY;
-	bool mNormalDir;
-
-	double differenceAngle;
-	double mRotCos;
-	double mRotSin;
-
-public:
-	/**
-	 * Constructor that initializes the base properties of the record
-	 */
-	GeometrySpiral (double s, double x, double y, double hdg, double length, double curvatureStart,double curvatureEnd);
-
-	/**
-	 * Clones and returns the new geometry record
-	 */
-	RoadGeometry* Clone() const;
-
-	//-------------------------------------------------
-
-	/**
-	 * Setter for the base properties
-	 */
-	void SetAll(double s, double x, double y, double hdg, double length, double curvatureStart,double curvatureEnd);
-	void SetCurvatureStart(double curvature);
-	void SetCurvatureEnd(double curvature);
-	
-	//-------------------------------------------------
-	/**
-	 * Getter for the base properties
-	 */
-	double GetCurvatureStart();
-	double GetCurvatureEnd();
-	
-	//-------------------------------------------------
-	/**
-	 * Gets the coordinates at the sample S offset
-	 */
-	void GetCoords(double s_check, double &retX, double &retY, double &retHDG);
-protected:
-
-	/**
-	 * Computes the required vars
-	 */
-	virtual void ComputeVars();
-};
-
-
-//----------------------------------------------------------------------------------
-/**
- * GeometryPoly3 inherits the RoadGeometry class and adds polynomial properties
- *
- */
-class GeometryPoly3: public RoadGeometry
-{
-private:
-	/**
-	 * Base record properties
-	 */
-	double mA;
-	double mB;
-	double mC;
-	double mD;
-public:
-	/**
-	 * Constructor that initializes the base properties of the record
-	 */
-	GeometryPoly3 (double s, double x, double y, double hdg, double length, double a,double b,double c,double d );
-
-	/**
-	 * Clones and returns the new geometry record
-	 */
-	RoadGeometry* Clone() const;
-	
-	//-------------------------------------------------
-	/**
-	 * Setter for the base properties
-	 */
-	void SetAll(double s, double x, double y, double hdg, double length, double a,double b,double c,double d);
-
-};
-
-//----------------------------------------------------------------------------------
-/**
- * GeometryPoly3 inherits the RoadGeometry class and adds polynomial properties, Added By Yuchuli,2019.11.1
- *
- */
-class GeometryParamPoly3: public RoadGeometry
-{
-private:
-    /**
-     * Base record properties
-     */
-    double muA;
-    double muB;
-    double muC;
-    double muD;
-
-    double mvA;
-    double mvB;
-    double mvC;
-    double mvD;
-public:
-    /**
-     * Constructor that initializes the base properties of the record
-     */
-    GeometryParamPoly3 (double s, double x, double y, double hdg, double length, double ua,double ub,double uc,double ud,double va, double vb, double vc,double vd );
-
-    /**
-     * Clones and returns the new geometry record
-     */
-    RoadGeometry* Clone() const;
-
-    //-------------------------------------------------
-    /**
-     * Setter for the base properties
-     */
-    void SetAll(double s, double x, double y, double hdg, double length, double a,double b,double c,double d,double va, double vb, double vc,double vd );
-
-
-    double GetuA();
-    double GetuB();
-    double GetuC();
-    double GetuD();
-    double GetvA();
-    double GetvB();
-    double GetvC();
-    double GetvD();
-};
-
-
-
-//----------------------------------------------------------------------------------
-/**
- * GeometryBlock is a class used to combine multiple geometry records into blocks.
- * The basic use for this is to combine spiral-arc-spiral sequence of records into 
- * a signel "Turn" block for an easier way to define turns, keeping close to the
- * road building practice of curvature use for transitions between straight segments and arcs
- */
-class GeometryBlock
-{
-private:
-	/**
-	 * Vector of geometry records that make up a block
-	 */
-	vector<RoadGeometry*> mGeometryBlockElement;
-public:
-	/**
-	 * Constructor
-	 */
-	GeometryBlock();
-	
-	/**
-	 * Copy constructor
-	 */
-	GeometryBlock(const GeometryBlock& geomBlock);
-
-	/**
-	 * Assignment operator overload
-	 */
-	const GeometryBlock& operator=(const GeometryBlock& otherGeomBlock);
-	
-	//-------------------------------------------------
-
-	/**
-	 * Methods used to add geometry recors to the geometry record vector
-	 */
-	void AddGeometryLine(double s, double x, double y, double hdg, double length);
-	void AddGeometryArc(double s, double x, double y, double hdg, double length, double curvature);
-	void AddGeometrySpiral(double s, double x, double y, double hdg, double length, double curvatureStart,double curvatureEnd);
-	void AddGeometryPoly3(double s, double x, double y, double hdg, double length, double a,double b,double c,double d);
-    void AddGeometryParamPoly3(double s, double x, double y, double hdg, double length, double ua,double ub,double uc,double ud,double va,double vb,double vc,double vd);
-	
-	//-------------------------------------------------
-
-	/**
-	 * Getter for the geometry record at a given index position of the vector
-	 */
-	RoadGeometry* GetGeometryAt(int index);
-
-	/**
-	 * Getter for the overal block length (summ of geometry record lengths)
-	 */
-	double GetBlockLength();
-
-	/**
-	 *  Checks if the block is a straight line block or a turn
-	 */
-	bool CheckIfLine();
-	
-	//-------------------------------------------------
-
-	/**
-	 * Recalculates the geometry blocks when one of the geometry records is modified
-	 * Makes sure that every geometry records starts where the previous record ends
-	 */
-	void Recalculate(double s, double x, double y, double hdg);
-
-	//-------------------------------------------------
-
-	/**
-	 *  Evaluation methods
-	 */
-	double GetLastS2();
-	RoadGeometry* GetLastGeometry();
-	virtual short int GetLastCoords(double &s, double &retX, double &retY, double &retHDG);
-	bool CheckInterval(double s_check);
-	virtual short int GetCoords(double s_check, double &retX, double &retY);
-	virtual short int GetCoords(double s_check, double &retX, double &retY, double &retHDG);
-
-	//-------------------------------------------------
-	/**
-	 *  Destructor
-	 */
-	~GeometryBlock();
-};
-
-
-#endif

+ 0 - 116
src/tool/tool_xodrobj/TinyXML/tinystr.cpp

@@ -1,116 +0,0 @@
-/*
-www.sourceforge.net/projects/tinyxml
-Original file by Yves Berquin.
-
-This software is provided 'as-is', without any express or implied
-warranty. In no event will the authors be held liable for any
-damages arising from the use of this software.
-
-Permission is granted to anyone to use this software for any
-purpose, including commercial applications, and to alter it and
-redistribute it freely, subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must
-not claim that you wrote the original software. If you use this
-software in a product, an acknowledgment in the product documentation
-would be appreciated but is not required.
-
-2. Altered source versions must be plainly marked as such, and
-must not be misrepresented as being the original software.
-
-3. This notice may not be removed or altered from any source
-distribution.
-*/
-
-/*
- * THIS FILE WAS ALTERED BY Tyge Løvset, 7. April 2005.
- */
-
-
-#ifndef TIXML_USE_STL
-
-#include "tinystr.h"
-
-// Error value for find primitive
-const TiXmlString::size_type TiXmlString::npos = static_cast< TiXmlString::size_type >(-1);
-
-
-// Null rep.
-TiXmlString::Rep TiXmlString::nullrep_ = { 0, 0, { '\0' } };
-
-
-void TiXmlString::reserve (size_type cap)
-{
-	if (cap > capacity())
-	{
-		TiXmlString tmp;
-		tmp.init(length(), cap);
-		memcpy(tmp.start(), data(), length());
-		swap(tmp);
-	}
-}
-
-
-TiXmlString& TiXmlString::assign(const char* str, size_type len)
-{
-	size_type cap = capacity();
-	if (len > cap || cap > 3*(len + 8))
-	{
-		TiXmlString tmp;
-		tmp.init(len);
-		memcpy(tmp.start(), str, len);
-		swap(tmp);
-	}
-	else
-	{
-		memmove(start(), str, len);
-		set_size(len);
-	}
-	return *this;
-}
-
-
-TiXmlString& TiXmlString::append(const char* str, size_type len)
-{
-	size_type newsize = length() + len;
-	if (newsize > capacity())
-	{
-		reserve (newsize + capacity());
-	}
-	memmove(finish(), str, len);
-	set_size(newsize);
-	return *this;
-}
-
-
-TiXmlString operator + (const TiXmlString & a, const TiXmlString & b)
-{
-	TiXmlString tmp;
-	tmp.reserve(a.length() + b.length());
-	tmp += a;
-	tmp += b;
-	return tmp;
-}
-
-TiXmlString operator + (const TiXmlString & a, const char* b)
-{
-	TiXmlString tmp;
-	TiXmlString::size_type b_len = static_cast<TiXmlString::size_type>( strlen(b) );
-	tmp.reserve(a.length() + b_len);
-	tmp += a;
-	tmp.append(b, b_len);
-	return tmp;
-}
-
-TiXmlString operator + (const char* a, const TiXmlString & b)
-{
-	TiXmlString tmp;
-	TiXmlString::size_type a_len = static_cast<TiXmlString::size_type>( strlen(a) );
-	tmp.reserve(a_len + b.length());
-	tmp.append(a, a_len);
-	tmp += b;
-	return tmp;
-}
-
-
-#endif	// TIXML_USE_STL

+ 0 - 319
src/tool/tool_xodrobj/TinyXML/tinystr.h

@@ -1,319 +0,0 @@
-/*
-www.sourceforge.net/projects/tinyxml
-Original file by Yves Berquin.
-
-This software is provided 'as-is', without any express or implied
-warranty. In no event will the authors be held liable for any
-damages arising from the use of this software.
-
-Permission is granted to anyone to use this software for any
-purpose, including commercial applications, and to alter it and
-redistribute it freely, subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must
-not claim that you wrote the original software. If you use this
-software in a product, an acknowledgment in the product documentation
-would be appreciated but is not required.
-
-2. Altered source versions must be plainly marked as such, and
-must not be misrepresented as being the original software.
-
-3. This notice may not be removed or altered from any source
-distribution.
-*/
-
-/*
- * THIS FILE WAS ALTERED BY Tyge Lovset, 7. April 2005.
- *
- * - completely rewritten. compact, clean, and fast implementation.
- * - sizeof(TiXmlString) = pointer size (4 bytes on 32-bit systems)
- * - fixed reserve() to work as per specification.
- * - fixed buggy compares operator==(), operator<(), and operator>()
- * - fixed operator+=() to take a const ref argument, following spec.
- * - added "copy" constructor with length, and most compare operators.
- * - added swap(), clear(), size(), capacity(), operator+().
- */
-
-#ifndef TIXML_USE_STL
-
-#ifndef TIXML_STRING_INCLUDED
-#define TIXML_STRING_INCLUDED
-
-#include <assert.h>
-#include <string.h>
-
-/*	The support for explicit isn't that universal, and it isn't really
-	required - it is used to check that the TiXmlString class isn't incorrectly
-	used. Be nice to old compilers and macro it here:
-*/
-#if defined(_MSC_VER) && (_MSC_VER >= 1200 )
-	// Microsoft visual studio, version 6 and higher.
-	#define TIXML_EXPLICIT explicit
-#elif defined(__GNUC__) && (__GNUC__ >= 3 )
-	// GCC version 3 and higher.s
-	#define TIXML_EXPLICIT explicit
-#else
-	#define TIXML_EXPLICIT
-#endif
-
-
-/*
-   TiXmlString is an emulation of a subset of the std::string template.
-   Its purpose is to allow compiling TinyXML on compilers with no or poor STL support.
-   Only the member functions relevant to the TinyXML project have been implemented.
-   The buffer allocation is made by a simplistic power of 2 like mechanism : if we increase
-   a string and there's no more room, we allocate a buffer twice as big as we need.
-*/
-class TiXmlString
-{
-  public :
-	// The size type used
-  	typedef size_t size_type;
-
-	// Error value for find primitive
-	static const size_type npos; // = -1;
-
-
-	// TiXmlString empty constructor
-	TiXmlString () : rep_(&nullrep_)
-	{
-	}
-
-	// TiXmlString copy constructor
-	TiXmlString ( const TiXmlString & copy) : rep_(0)
-	{
-		init(copy.length());
-		memcpy(start(), copy.data(), length());
-	}
-
-	// TiXmlString constructor, based on a string
-	TIXML_EXPLICIT TiXmlString ( const char * copy) : rep_(0)
-	{
-		init( static_cast<size_type>( strlen(copy) ));
-		memcpy(start(), copy, length());
-	}
-
-	// TiXmlString constructor, based on a string
-	TIXML_EXPLICIT TiXmlString ( const char * str, size_type len) : rep_(0)
-	{
-		init(len);
-		memcpy(start(), str, len);
-	}
-
-	// TiXmlString destructor
-	~TiXmlString ()
-	{
-		quit();
-	}
-
-	// = operator
-	TiXmlString& operator = (const char * copy)
-	{
-		return assign( copy, (size_type)strlen(copy));
-	}
-
-	// = operator
-	TiXmlString& operator = (const TiXmlString & copy)
-	{
-		return assign(copy.start(), copy.length());
-	}
-
-
-	// += operator. Maps to append
-	TiXmlString& operator += (const char * suffix)
-	{
-		return append(suffix, static_cast<size_type>( strlen(suffix) ));
-	}
-
-	// += operator. Maps to append
-	TiXmlString& operator += (char single)
-	{
-		return append(&single, 1);
-	}
-
-	// += operator. Maps to append
-	TiXmlString& operator += (const TiXmlString & suffix)
-	{
-		return append(suffix.data(), suffix.length());
-	}
-
-
-	// Convert a TiXmlString into a null-terminated char *
-	const char * c_str () const { return rep_->str; }
-
-	// Convert a TiXmlString into a char * (need not be null terminated).
-	const char * data () const { return rep_->str; }
-
-	// Return the length of a TiXmlString
-	size_type length () const { return rep_->size; }
-
-	// Alias for length()
-	size_type size () const { return rep_->size; }
-
-	// Checks if a TiXmlString is empty
-	bool empty () const { return rep_->size == 0; }
-
-	// Return capacity of string
-	size_type capacity () const { return rep_->capacity; }
-
-
-	// single char extraction
-	const char& at (size_type index) const
-	{
-		assert( index < length() );
-		return rep_->str[ index ];
-	}
-
-	// [] operator
-	char& operator [] (size_type index) const
-	{
-		assert( index < length() );
-		return rep_->str[ index ];
-	}
-
-	// find a char in a string. Return TiXmlString::npos if not found
-	size_type find (char lookup) const
-	{
-		return find(lookup, 0);
-	}
-
-	// find a char in a string from an offset. Return TiXmlString::npos if not found
-	size_type find (char tofind, size_type offset) const
-	{
-		if (offset >= length()) return npos;
-
-		for (const char* p = c_str() + offset; *p != '\0'; ++p)
-		{
-		   if (*p == tofind) return static_cast< size_type >( p - c_str() );
-		}
-		return npos;
-	}
-
-	void clear ()
-	{
-		//Lee:
-		//The original was just too strange, though correct:
-		//	TiXmlString().swap(*this);
-		//Instead use the quit & re-init:
-		quit();
-		init(0,0);
-	}
-
-	/*	Function to reserve a big amount of data when we know we'll need it. Be aware that this
-		function DOES NOT clear the content of the TiXmlString if any exists.
-	*/
-	void reserve (size_type cap);
-
-	TiXmlString& assign (const char* str, size_type len);
-
-	TiXmlString& append (const char* str, size_type len);
-
-	void swap (TiXmlString& other)
-	{
-		Rep* r = rep_;
-		rep_ = other.rep_;
-		other.rep_ = r;
-	}
-
-  private:
-
-	void init(size_type sz) { init(sz, sz); }
-	void set_size(size_type sz) { rep_->str[ rep_->size = sz ] = '\0'; }
-	char* start() const { return rep_->str; }
-	char* finish() const { return rep_->str + rep_->size; }
-
-	struct Rep
-	{
-		size_type size, capacity;
-		char str[1];
-	};
-
-	void init(size_type sz, size_type cap)
-	{
-		if (cap)
-		{
-			// Lee: the original form:
-			//	rep_ = static_cast<Rep*>(operator new(sizeof(Rep) + cap));
-			// doesn't work in some cases of new being overloaded. Switching
-			// to the normal allocation, although use an 'int' for systems
-			// that are overly picky about structure alignment.
-			const size_type bytesNeeded = sizeof(Rep) + cap;
-			const size_type intsNeeded = ( bytesNeeded + sizeof(int) - 1 ) / sizeof( int ); 
-			rep_ = reinterpret_cast<Rep*>( new int[ intsNeeded ] );
-
-			rep_->str[ rep_->size = sz ] = '\0';
-			rep_->capacity = cap;
-		}
-		else
-		{
-			rep_ = &nullrep_;
-		}
-	}
-
-	void quit()
-	{
-		if (rep_ != &nullrep_)
-		{
-			// The rep_ is really an array of ints. (see the allocator, above).
-			// Cast it back before delete, so the compiler won't incorrectly call destructors.
-			delete [] ( reinterpret_cast<int*>( rep_ ) );
-		}
-	}
-
-	Rep * rep_;
-	static Rep nullrep_;
-
-} ;
-
-
-inline bool operator == (const TiXmlString & a, const TiXmlString & b)
-{
-	return    ( a.length() == b.length() )				// optimization on some platforms
-	       && ( strcmp(a.c_str(), b.c_str()) == 0 );	// actual compare
-}
-inline bool operator < (const TiXmlString & a, const TiXmlString & b)
-{
-	return strcmp(a.c_str(), b.c_str()) < 0;
-}
-
-inline bool operator != (const TiXmlString & a, const TiXmlString & b) { return !(a == b); }
-inline bool operator >  (const TiXmlString & a, const TiXmlString & b) { return b < a; }
-inline bool operator <= (const TiXmlString & a, const TiXmlString & b) { return !(b < a); }
-inline bool operator >= (const TiXmlString & a, const TiXmlString & b) { return !(a < b); }
-
-inline bool operator == (const TiXmlString & a, const char* b) { return strcmp(a.c_str(), b) == 0; }
-inline bool operator == (const char* a, const TiXmlString & b) { return b == a; }
-inline bool operator != (const TiXmlString & a, const char* b) { return !(a == b); }
-inline bool operator != (const char* a, const TiXmlString & b) { return !(b == a); }
-
-TiXmlString operator + (const TiXmlString & a, const TiXmlString & b);
-TiXmlString operator + (const TiXmlString & a, const char* b);
-TiXmlString operator + (const char* a, const TiXmlString & b);
-
-
-/*
-   TiXmlOutStream is an emulation of std::ostream. It is based on TiXmlString.
-   Only the operators that we need for TinyXML have been developped.
-*/
-class TiXmlOutStream : public TiXmlString
-{
-public :
-
-	// TiXmlOutStream << operator.
-	TiXmlOutStream & operator << (const TiXmlString & in)
-	{
-		*this += in;
-		return *this;
-	}
-
-	// TiXmlOutStream << operator.
-	TiXmlOutStream & operator << (const char * in)
-	{
-		*this += in;
-		return *this;
-	}
-
-} ;
-
-#endif	// TIXML_STRING_INCLUDED
-#endif	// TIXML_USE_STL

+ 0 - 1856
src/tool/tool_xodrobj/TinyXML/tinyxml.cpp

@@ -1,1856 +0,0 @@
-/*
-www.sourceforge.net/projects/tinyxml
-Original code (2.0 and earlier )copyright (c) 2000-2006 Lee Thomason (www.grinninglizard.com)
-
-This software is provided 'as-is', without any express or implied
-warranty. In no event will the authors be held liable for any
-damages arising from the use of this software.
-
-Permission is granted to anyone to use this software for any
-purpose, including commercial applications, and to alter it and
-redistribute it freely, subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must
-not claim that you wrote the original software. If you use this
-software in a product, an acknowledgment in the product documentation
-would be appreciated but is not required.
-
-2. Altered source versions must be plainly marked as such, and
-must not be misrepresented as being the original software.
-
-3. This notice may not be removed or altered from any source
-distribution.
-*/
-
-#include <ctype.h>
-
-#ifdef TIXML_USE_STL
-#include <sstream>
-#include <iostream>
-#endif
-
-#include "tinyxml.h"
-
-FILE* TiXmlFOpen( const char* filename, const char* mode );
-
-bool TiXmlBase::condenseWhiteSpace = true;
-
-// Microsoft compiler security
-FILE* TiXmlFOpen( const char* filename, const char* mode )
-{
-	#if defined(_MSC_VER) && (_MSC_VER >= 1400 )
-		FILE* fp = 0;
-		errno_t err = fopen_s( &fp, filename, mode );
-		if ( !err && fp )
-			return fp;
-		return 0;
-	#else
-		return fopen( filename, mode );
-	#endif
-}
-
-void TiXmlBase::EncodeString( const TIXML_STRING& str, TIXML_STRING* outString )
-{
-	int i=0;
-
-	while( i<(int)str.length() )
-	{
-		unsigned char c = (unsigned char) str[i];
-
-		if (    c == '&' 
-		     && i < ( (int)str.length() - 2 )
-			 && str[i+1] == '#'
-			 && str[i+2] == 'x' )
-		{
-			// Hexadecimal character reference.
-			// Pass through unchanged.
-			// &#xA9;	-- copyright symbol, for example.
-			//
-			// The -1 is a bug fix from Rob Laveaux. It keeps
-			// an overflow from happening if there is no ';'.
-			// There are actually 2 ways to exit this loop -
-			// while fails (error case) and break (semicolon found).
-			// However, there is no mechanism (currently) for
-			// this function to return an error.
-			while ( i<(int)str.length()-1 )
-			{
-				outString->append( str.c_str() + i, 1 );
-				++i;
-				if ( str[i] == ';' )
-					break;
-			}
-		}
-		else if ( c == '&' )
-		{
-			outString->append( entity[0].str, entity[0].strLength );
-			++i;
-		}
-		else if ( c == '<' )
-		{
-			outString->append( entity[1].str, entity[1].strLength );
-			++i;
-		}
-		else if ( c == '>' )
-		{
-			outString->append( entity[2].str, entity[2].strLength );
-			++i;
-		}
-		else if ( c == '\"' )
-		{
-			outString->append( entity[3].str, entity[3].strLength );
-			++i;
-		}
-		else if ( c == '\'' )
-		{
-			outString->append( entity[4].str, entity[4].strLength );
-			++i;
-		}
-		else if ( c < 32 )
-		{
-			// Easy pass at non-alpha/numeric/symbol
-			// Below 32 is symbolic.
-			char buf[ 32 ];
-			
-			#if defined(TIXML_SNPRINTF)		
-				TIXML_SNPRINTF( buf, sizeof(buf), "&#x%02X;", (unsigned) ( c & 0xff ) );
-			#else
-				sprintf( buf, "&#x%02X;", (unsigned) ( c & 0xff ) );
-			#endif		
-
-			//*ME:	warning C4267: convert 'size_t' to 'int'
-			//*ME:	Int-Cast to make compiler happy ...
-			outString->append( buf, (int)strlen( buf ) );
-			++i;
-		}
-		else
-		{
-			//char realc = (char) c;
-			//outString->append( &realc, 1 );
-			*outString += (char) c;	// somewhat more efficient function call.
-			++i;
-		}
-	}
-}
-
-
-TiXmlNode::TiXmlNode( NodeType _type ) : TiXmlBase()
-{
-	parent = 0;
-	type = _type;
-	firstChild = 0;
-	lastChild = 0;
-	prev = 0;
-	next = 0;
-}
-
-
-TiXmlNode::~TiXmlNode()
-{
-	TiXmlNode* node = firstChild;
-	TiXmlNode* temp = 0;
-
-	while ( node )
-	{
-		temp = node;
-		node = node->next;
-		delete temp;
-	}	
-}
-
-
-void TiXmlNode::CopyTo( TiXmlNode* target ) const
-{
-	target->SetValue (value.c_str() );
-	target->userData = userData; 
-	target->location = location;
-}
-
-
-void TiXmlNode::Clear()
-{
-	TiXmlNode* node = firstChild;
-	TiXmlNode* temp = 0;
-
-	while ( node )
-	{
-		temp = node;
-		node = node->next;
-		delete temp;
-	}	
-
-	firstChild = 0;
-	lastChild = 0;
-}
-
-
-TiXmlNode* TiXmlNode::LinkEndChild( TiXmlNode* node )
-{
-	assert( node->parent == 0 || node->parent == this );
-	assert( node->GetDocument() == 0 || node->GetDocument() == this->GetDocument() );
-
-	if ( node->Type() == TiXmlNode::TINYXML_DOCUMENT )
-	{
-		delete node;
-		if ( GetDocument() ) GetDocument()->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return 0;
-	}
-
-	node->parent = this;
-
-	node->prev = lastChild;
-	node->next = 0;
-
-	if ( lastChild )
-		lastChild->next = node;
-	else
-		firstChild = node;			// it was an empty list.
-
-	lastChild = node;
-	return node;
-}
-
-
-TiXmlNode* TiXmlNode::InsertEndChild( const TiXmlNode& addThis )
-{
-	if ( addThis.Type() == TiXmlNode::TINYXML_DOCUMENT )
-	{
-		if ( GetDocument() ) GetDocument()->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return 0;
-	}
-	TiXmlNode* node = addThis.Clone();
-	if ( !node )
-		return 0;
-
-	return LinkEndChild( node );
-}
-
-
-TiXmlNode* TiXmlNode::InsertBeforeChild( TiXmlNode* beforeThis, const TiXmlNode& addThis )
-{	
-	if ( !beforeThis || beforeThis->parent != this ) {
-		return 0;
-	}
-	if ( addThis.Type() == TiXmlNode::TINYXML_DOCUMENT )
-	{
-		if ( GetDocument() ) GetDocument()->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return 0;
-	}
-
-	TiXmlNode* node = addThis.Clone();
-	if ( !node )
-		return 0;
-	node->parent = this;
-
-	node->next = beforeThis;
-	node->prev = beforeThis->prev;
-	if ( beforeThis->prev )
-	{
-		beforeThis->prev->next = node;
-	}
-	else
-	{
-		assert( firstChild == beforeThis );
-		firstChild = node;
-	}
-	beforeThis->prev = node;
-	return node;
-}
-
-
-TiXmlNode* TiXmlNode::InsertAfterChild( TiXmlNode* afterThis, const TiXmlNode& addThis )
-{
-	if ( !afterThis || afterThis->parent != this ) {
-		return 0;
-	}
-	if ( addThis.Type() == TiXmlNode::TINYXML_DOCUMENT )
-	{
-		if ( GetDocument() ) GetDocument()->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return 0;
-	}
-
-	TiXmlNode* node = addThis.Clone();
-	if ( !node )
-		return 0;
-	node->parent = this;
-
-	node->prev = afterThis;
-	node->next = afterThis->next;
-	if ( afterThis->next )
-	{
-		afterThis->next->prev = node;
-	}
-	else
-	{
-		assert( lastChild == afterThis );
-		lastChild = node;
-	}
-	afterThis->next = node;
-	return node;
-}
-
-
-TiXmlNode* TiXmlNode::ReplaceChild( TiXmlNode* replaceThis, const TiXmlNode& withThis )
-{
-	if ( !replaceThis )
-		return 0;
-
-	if ( replaceThis->parent != this )
-		return 0;
-
-	if ( withThis.ToDocument() ) {
-		// A document can never be a child.	Thanks to Noam.
-		TiXmlDocument* document = GetDocument();
-		if ( document ) 
-			document->SetError( TIXML_ERROR_DOCUMENT_TOP_ONLY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return 0;
-	}
-
-	TiXmlNode* node = withThis.Clone();
-	if ( !node )
-		return 0;
-
-	node->next = replaceThis->next;
-	node->prev = replaceThis->prev;
-
-	if ( replaceThis->next )
-		replaceThis->next->prev = node;
-	else
-		lastChild = node;
-
-	if ( replaceThis->prev )
-		replaceThis->prev->next = node;
-	else
-		firstChild = node;
-
-	delete replaceThis;
-	node->parent = this;
-	return node;
-}
-
-
-bool TiXmlNode::RemoveChild( TiXmlNode* removeThis )
-{
-	if ( !removeThis ) {
-		return false;
-	}
-
-	if ( removeThis->parent != this )
-	{	
-		assert( 0 );
-		return false;
-	}
-
-	if ( removeThis->next )
-		removeThis->next->prev = removeThis->prev;
-	else
-		lastChild = removeThis->prev;
-
-	if ( removeThis->prev )
-		removeThis->prev->next = removeThis->next;
-	else
-		firstChild = removeThis->next;
-
-	delete removeThis;
-	return true;
-}
-
-const TiXmlNode* TiXmlNode::FirstChild( const char * _value ) const
-{
-	const TiXmlNode* node;
-	for ( node = firstChild; node; node = node->next )
-	{
-		if ( strcmp( node->Value(), _value ) == 0 )
-			return node;
-	}
-	return 0;
-}
-
-
-const TiXmlNode* TiXmlNode::LastChild( const char * _value ) const
-{
-	const TiXmlNode* node;
-	for ( node = lastChild; node; node = node->prev )
-	{
-		if ( strcmp( node->Value(), _value ) == 0 )
-			return node;
-	}
-	return 0;
-}
-
-
-const TiXmlNode* TiXmlNode::IterateChildren( const TiXmlNode* previous ) const
-{
-	if ( !previous )
-	{
-		return FirstChild();
-	}
-	else
-	{
-		assert( previous->parent == this );
-		return previous->NextSibling();
-	}
-}
-
-
-const TiXmlNode* TiXmlNode::IterateChildren( const char * val, const TiXmlNode* previous ) const
-{
-	if ( !previous )
-	{
-		return FirstChild( val );
-	}
-	else
-	{
-		assert( previous->parent == this );
-		return previous->NextSibling( val );
-	}
-}
-
-
-const TiXmlNode* TiXmlNode::NextSibling( const char * _value ) const 
-{
-	const TiXmlNode* node;
-	for ( node = next; node; node = node->next )
-	{
-		if ( strcmp( node->Value(), _value ) == 0 )
-			return node;
-	}
-	return 0;
-}
-
-
-const TiXmlNode* TiXmlNode::PreviousSibling( const char * _value ) const
-{
-	const TiXmlNode* node;
-	for ( node = prev; node; node = node->prev )
-	{
-		if ( strcmp( node->Value(), _value ) == 0 )
-			return node;
-	}
-	return 0;
-}
-
-
-void TiXmlElement::RemoveAttribute( const char * name )
-{
-    #ifdef TIXML_USE_STL
-	TIXML_STRING str( name );
-	TiXmlAttribute* node = attributeSet.Find( str );
-	#else
-	TiXmlAttribute* node = attributeSet.Find( name );
-	#endif
-	if ( node )
-	{
-		attributeSet.Remove( node );
-		delete node;
-	}
-}
-
-const TiXmlElement* TiXmlNode::FirstChildElement() const
-{
-	const TiXmlNode* node;
-
-	for (	node = FirstChild();
-			node;
-			node = node->NextSibling() )
-	{
-		if ( node->ToElement() )
-			return node->ToElement();
-	}
-	return 0;
-}
-
-
-const TiXmlElement* TiXmlNode::FirstChildElement( const char * _value ) const
-{
-	const TiXmlNode* node;
-
-	for (	node = FirstChild( _value );
-			node;
-			node = node->NextSibling( _value ) )
-	{
-		if ( node->ToElement() )
-			return node->ToElement();
-	}
-	return 0;
-}
-
-
-const TiXmlElement* TiXmlNode::NextSiblingElement() const
-{
-	const TiXmlNode* node;
-
-	for (	node = NextSibling();
-			node;
-			node = node->NextSibling() )
-	{
-		if ( node->ToElement() )
-			return node->ToElement();
-	}
-	return 0;
-}
-
-
-const TiXmlElement* TiXmlNode::NextSiblingElement( const char * _value ) const
-{
-	const TiXmlNode* node;
-
-	for (	node = NextSibling( _value );
-			node;
-			node = node->NextSibling( _value ) )
-	{
-		if ( node->ToElement() )
-			return node->ToElement();
-	}
-	return 0;
-}
-
-
-const TiXmlDocument* TiXmlNode::GetDocument() const
-{
-	const TiXmlNode* node;
-
-	for( node = this; node; node = node->parent )
-	{
-		if ( node->ToDocument() )
-			return node->ToDocument();
-	}
-	return 0;
-}
-
-
-TiXmlElement::TiXmlElement (const char * _value)
-	: TiXmlNode( TiXmlNode::TINYXML_ELEMENT )
-{
-	firstChild = lastChild = 0;
-	value = _value;
-}
-
-
-#ifdef TIXML_USE_STL
-TiXmlElement::TiXmlElement( const std::string& _value ) 
-	: TiXmlNode( TiXmlNode::TINYXML_ELEMENT )
-{
-	firstChild = lastChild = 0;
-	value = _value;
-}
-#endif
-
-
-TiXmlElement::TiXmlElement( const TiXmlElement& copy)
-	: TiXmlNode( TiXmlNode::TINYXML_ELEMENT )
-{
-	firstChild = lastChild = 0;
-	copy.CopyTo( this );	
-}
-
-
-void TiXmlElement::operator=( const TiXmlElement& base )
-{
-	ClearThis();
-	base.CopyTo( this );
-}
-
-
-TiXmlElement::~TiXmlElement()
-{
-	ClearThis();
-}
-
-
-void TiXmlElement::ClearThis()
-{
-	Clear();
-	while( attributeSet.First() )
-	{
-		TiXmlAttribute* node = attributeSet.First();
-		attributeSet.Remove( node );
-		delete node;
-	}
-}
-
-
-const char* TiXmlElement::Attribute( const char* name ) const
-{
-	const TiXmlAttribute* node = attributeSet.Find( name );
-	if ( node )
-		return node->Value();
-	return 0;
-}
-
-
-#ifdef TIXML_USE_STL
-const std::string* TiXmlElement::Attribute( const std::string& name ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	if ( attrib )
-		return &attrib->ValueStr();
-	return 0;
-}
-#endif
-
-
-const char* TiXmlElement::Attribute( const char* name, int* i ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	const char* result = 0;
-
-	if ( attrib ) {
-		result = attrib->Value();
-		if ( i ) {
-			attrib->QueryIntValue( i );
-		}
-	}
-	return result;
-}
-
-
-#ifdef TIXML_USE_STL
-const std::string* TiXmlElement::Attribute( const std::string& name, int* i ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	const std::string* result = 0;
-
-	if ( attrib ) {
-		result = &attrib->ValueStr();
-		if ( i ) {
-			attrib->QueryIntValue( i );
-		}
-	}
-	return result;
-}
-#endif
-
-
-const char* TiXmlElement::Attribute( const char* name, double* d ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	const char* result = 0;
-
-	if ( attrib ) {
-		result = attrib->Value();
-		if ( d ) {
-			attrib->QueryDoubleValue( d );
-		}
-	}
-	return result;
-}
-
-
-#ifdef TIXML_USE_STL
-const std::string* TiXmlElement::Attribute( const std::string& name, double* d ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	const std::string* result = 0;
-
-	if ( attrib ) {
-		result = &attrib->ValueStr();
-		if ( d ) {
-			attrib->QueryDoubleValue( d );
-		}
-	}
-	return result;
-}
-#endif
-
-
-int TiXmlElement::QueryIntAttribute( const char* name, int* ival ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	if ( !attrib )
-		return TIXML_NO_ATTRIBUTE;
-	return attrib->QueryIntValue( ival );
-}
-
-
-#ifdef TIXML_USE_STL
-int TiXmlElement::QueryIntAttribute( const std::string& name, int* ival ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	if ( !attrib )
-		return TIXML_NO_ATTRIBUTE;
-	return attrib->QueryIntValue( ival );
-}
-#endif
-
-
-int TiXmlElement::QueryDoubleAttribute( const char* name, double* dval ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	if ( !attrib )
-		return TIXML_NO_ATTRIBUTE;
-	return attrib->QueryDoubleValue( dval );
-}
-
-
-#ifdef TIXML_USE_STL
-int TiXmlElement::QueryDoubleAttribute( const std::string& name, double* dval ) const
-{
-	const TiXmlAttribute* attrib = attributeSet.Find( name );
-	if ( !attrib )
-		return TIXML_NO_ATTRIBUTE;
-	return attrib->QueryDoubleValue( dval );
-}
-#endif
-
-
-void TiXmlElement::SetAttribute( const char * name, int val )
-{	
-	TiXmlAttribute* attrib = attributeSet.FindOrCreate( name );
-	if ( attrib ) {
-		attrib->SetIntValue( val );
-	}
-}
-
-
-#ifdef TIXML_USE_STL
-void TiXmlElement::SetAttribute( const std::string& name, int val )
-{	
-	TiXmlAttribute* attrib = attributeSet.FindOrCreate( name );
-	if ( attrib ) {
-		attrib->SetIntValue( val );
-	}
-}
-#endif
-
-
-void TiXmlElement::SetDoubleAttribute( const char * name, double val )
-{	
-	TiXmlAttribute* attrib = attributeSet.FindOrCreate( name );
-	if ( attrib ) {
-		attrib->SetDoubleValue( val );
-	}
-}
-
-
-#ifdef TIXML_USE_STL
-void TiXmlElement::SetDoubleAttribute( const std::string& name, double val )
-{	
-	TiXmlAttribute* attrib = attributeSet.FindOrCreate( name );
-	if ( attrib ) {
-		attrib->SetDoubleValue( val );
-	}
-}
-#endif 
-
-
-void TiXmlElement::SetAttribute( const char * cname, const char * cvalue )
-{
-	TiXmlAttribute* attrib = attributeSet.FindOrCreate( cname );
-	if ( attrib ) {
-		attrib->SetValue( cvalue );
-	}
-}
-
-
-#ifdef TIXML_USE_STL
-void TiXmlElement::SetAttribute( const std::string& _name, const std::string& _value )
-{
-	TiXmlAttribute* attrib = attributeSet.FindOrCreate( _name );
-	if ( attrib ) {
-		attrib->SetValue( _value );
-	}
-}
-#endif
-
-
-void TiXmlElement::Print( FILE* cfile, int depth ) const
-{
-	int i;
-	assert( cfile );
-	for ( i=0; i<depth; i++ ) {
-		fprintf( cfile, "    " );
-	}
-
-	fprintf( cfile, "<%s", value.c_str() );
-
-	const TiXmlAttribute* attrib;
-	for ( attrib = attributeSet.First(); attrib; attrib = attrib->Next() )
-	{
-		fprintf( cfile, " " );
-		attrib->Print( cfile, depth );
-	}
-
-	// There are 3 different formatting approaches:
-	// 1) An element without children is printed as a <foo /> node
-	// 2) An element with only a text child is printed as <foo> text </foo>
-	// 3) An element with children is printed on multiple lines.
-	TiXmlNode* node;
-	if ( !firstChild )
-	{
-		fprintf( cfile, " />" );
-	}
-	else if ( firstChild == lastChild && firstChild->ToText() )
-	{
-		fprintf( cfile, ">" );
-		firstChild->Print( cfile, depth + 1 );
-		fprintf( cfile, "</%s>", value.c_str() );
-	}
-	else
-	{
-		fprintf( cfile, ">" );
-
-		for ( node = firstChild; node; node=node->NextSibling() )
-		{
-			if ( !node->ToText() )
-			{
-				fprintf( cfile, "\n" );
-			}
-			node->Print( cfile, depth+1 );
-		}
-		fprintf( cfile, "\n" );
-		for( i=0; i<depth; ++i ) {
-			fprintf( cfile, "    " );
-		}
-		fprintf( cfile, "</%s>", value.c_str() );
-	}
-}
-
-
-void TiXmlElement::CopyTo( TiXmlElement* target ) const
-{
-	// superclass:
-	TiXmlNode::CopyTo( target );
-
-	// Element class: 
-	// Clone the attributes, then clone the children.
-	const TiXmlAttribute* attribute = 0;
-	for(	attribute = attributeSet.First();
-	attribute;
-	attribute = attribute->Next() )
-	{
-		target->SetAttribute( attribute->Name(), attribute->Value() );
-	}
-
-	TiXmlNode* node = 0;
-	for ( node = firstChild; node; node = node->NextSibling() )
-	{
-		target->LinkEndChild( node->Clone() );
-	}
-}
-
-bool TiXmlElement::Accept( TiXmlVisitor* visitor ) const
-{
-	if ( visitor->VisitEnter( *this, attributeSet.First() ) ) 
-	{
-		for ( const TiXmlNode* node=FirstChild(); node; node=node->NextSibling() )
-		{
-			if ( !node->Accept( visitor ) )
-				break;
-		}
-	}
-	return visitor->VisitExit( *this );
-}
-
-
-TiXmlNode* TiXmlElement::Clone() const
-{
-	TiXmlElement* clone = new TiXmlElement( Value() );
-	if ( !clone )
-		return 0;
-
-	CopyTo( clone );
-	return clone;
-}
-
-
-const char* TiXmlElement::GetText() const
-{
-	const TiXmlNode* child = this->FirstChild();
-	if ( child ) {
-		const TiXmlText* childText = child->ToText();
-		if ( childText ) {
-			return childText->Value();
-		}
-	}
-	return 0;
-}
-
-
-TiXmlDocument::TiXmlDocument() : TiXmlNode( TiXmlNode::TINYXML_DOCUMENT )
-{
-	tabsize = 4;
-	useMicrosoftBOM = false;
-	ClearError();
-}
-
-TiXmlDocument::TiXmlDocument( const char * documentName ) : TiXmlNode( TiXmlNode::TINYXML_DOCUMENT )
-{
-	tabsize = 4;
-	useMicrosoftBOM = false;
-	value = documentName;
-	ClearError();
-}
-
-
-#ifdef TIXML_USE_STL
-TiXmlDocument::TiXmlDocument( const std::string& documentName ) : TiXmlNode( TiXmlNode::TINYXML_DOCUMENT )
-{
-	tabsize = 4;
-	useMicrosoftBOM = false;
-    value = documentName;
-	ClearError();
-}
-#endif
-
-
-TiXmlDocument::TiXmlDocument( const TiXmlDocument& copy ) : TiXmlNode( TiXmlNode::TINYXML_DOCUMENT )
-{
-	copy.CopyTo( this );
-}
-
-
-void TiXmlDocument::operator=( const TiXmlDocument& copy )
-{
-	Clear();
-	copy.CopyTo( this );
-}
-
-
-bool TiXmlDocument::LoadFile( TiXmlEncoding encoding )
-{
-	return LoadFile( Value(), encoding );
-}
-
-
-bool TiXmlDocument::SaveFile() const
-{
-	return SaveFile( Value() );
-}
-
-bool TiXmlDocument::LoadFile( const char* _filename, TiXmlEncoding encoding )
-{
-	TIXML_STRING filename( _filename );
-	value = filename;
-
-	// reading in binary mode so that tinyxml can normalize the EOL
-	FILE* file = TiXmlFOpen( value.c_str (), "rb" );	
-
-	if ( file )
-	{
-		bool result = LoadFile( file, encoding );
-		fclose( file );
-		return result;
-	}
-	else
-	{
-		SetError( TIXML_ERROR_OPENING_FILE, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return false;
-	}
-}
-
-bool TiXmlDocument::LoadFile( FILE* file, TiXmlEncoding encoding )
-{
-	if ( !file ) 
-	{
-		SetError( TIXML_ERROR_OPENING_FILE, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return false;
-	}
-
-	// Delete the existing data:
-	Clear();
-	location.Clear();
-
-	// Get the file size, so we can pre-allocate the string. HUGE speed impact.
-	long length = 0;
-	fseek( file, 0, SEEK_END );
-	length = ftell( file );
-	fseek( file, 0, SEEK_SET );
-
-	// Strange case, but good to handle up front.
-	if ( length <= 0 )
-	{
-		SetError( TIXML_ERROR_DOCUMENT_EMPTY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return false;
-	}
-
-	// If we have a file, assume it is all one big XML file, and read it in.
-	// The document parser may decide the document ends sooner than the entire file, however.
-	TIXML_STRING data;
-	data.reserve( length );
-
-	// Subtle bug here. TinyXml did use fgets. But from the XML spec:
-	// 2.11 End-of-Line Handling
-	// <snip>
-	// <quote>
-	// ...the XML processor MUST behave as if it normalized all line breaks in external 
-	// parsed entities (including the document entity) on input, before parsing, by translating 
-	// both the two-character sequence #xD #xA and any #xD that is not followed by #xA to 
-	// a single #xA character.
-	// </quote>
-	//
-	// It is not clear fgets does that, and certainly isn't clear it works cross platform. 
-	// Generally, you expect fgets to translate from the convention of the OS to the c/unix
-	// convention, and not work generally.
-
-	/*
-	while( fgets( buf, sizeof(buf), file ) )
-	{
-		data += buf;
-	}
-	*/
-
-	char* buf = new char[ length+1 ];
-	buf[0] = 0;
-
-	if ( fread( buf, length, 1, file ) != 1 ) {
-		delete [] buf;
-		SetError( TIXML_ERROR_OPENING_FILE, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return false;
-	}
-
-	const char* lastPos = buf;
-	const char* p = buf;
-
-	buf[length] = 0;
-	while( *p ) {
-		assert( p < (buf+length) );
-		if ( *p == 0xa ) {
-			// Newline character. No special rules for this. Append all the characters
-			// since the last string, and include the newline.
-			data.append( lastPos, (p-lastPos+1) );	// append, include the newline
-			++p;									// move past the newline
-			lastPos = p;							// and point to the new buffer (may be 0)
-			assert( p <= (buf+length) );
-		}
-		else if ( *p == 0xd ) {
-			// Carriage return. Append what we have so far, then
-			// handle moving forward in the buffer.
-			if ( (p-lastPos) > 0 ) {
-				data.append( lastPos, p-lastPos );	// do not add the CR
-			}
-			data += (char)0xa;						// a proper newline
-
-			if ( *(p+1) == 0xa ) {
-				// Carriage return - new line sequence
-				p += 2;
-				lastPos = p;
-				assert( p <= (buf+length) );
-			}
-			else {
-				// it was followed by something else...that is presumably characters again.
-				++p;
-				lastPos = p;
-				assert( p <= (buf+length) );
-			}
-		}
-		else {
-			++p;
-		}
-	}
-	// Handle any left over characters.
-	if ( p-lastPos ) {
-		data.append( lastPos, p-lastPos );
-	}		
-	delete [] buf;
-	buf = 0;
-
-	Parse( data.c_str(), 0, encoding );
-
-	if (  Error() )
-        return false;
-    else
-		return true;
-}
-
-
-bool TiXmlDocument::SaveFile( const char * filename ) const
-{
-	// The old c stuff lives on...
-	FILE* fp = TiXmlFOpen( filename, "w" );
-	if ( fp )
-	{
-		bool result = SaveFile( fp );
-		fclose( fp );
-		return result;
-	}
-	return false;
-}
-
-
-bool TiXmlDocument::SaveFile( FILE* fp ) const
-{
-	if ( useMicrosoftBOM ) 
-	{
-		const unsigned char TIXML_UTF_LEAD_0 = 0xefU;
-		const unsigned char TIXML_UTF_LEAD_1 = 0xbbU;
-		const unsigned char TIXML_UTF_LEAD_2 = 0xbfU;
-
-		fputc( TIXML_UTF_LEAD_0, fp );
-		fputc( TIXML_UTF_LEAD_1, fp );
-		fputc( TIXML_UTF_LEAD_2, fp );
-	}
-	Print( fp, 0 );
-	return (ferror(fp) == 0);
-}
-
-
-void TiXmlDocument::CopyTo( TiXmlDocument* target ) const
-{
-	TiXmlNode::CopyTo( target );
-
-	target->error = error;
-	target->errorId = errorId;
-	target->errorDesc = errorDesc;
-	target->tabsize = tabsize;
-	target->errorLocation = errorLocation;
-	target->useMicrosoftBOM = useMicrosoftBOM;
-
-	TiXmlNode* node = 0;
-	for ( node = firstChild; node; node = node->NextSibling() )
-	{
-		target->LinkEndChild( node->Clone() );
-	}	
-}
-
-
-TiXmlNode* TiXmlDocument::Clone() const
-{
-	TiXmlDocument* clone = new TiXmlDocument();
-	if ( !clone )
-		return 0;
-
-	CopyTo( clone );
-	return clone;
-}
-
-
-void TiXmlDocument::Print( FILE* cfile, int depth ) const
-{
-	assert( cfile );
-	for ( const TiXmlNode* node=FirstChild(); node; node=node->NextSibling() )
-	{
-		node->Print( cfile, depth );
-		fprintf( cfile, "\n" );
-	}
-}
-
-
-bool TiXmlDocument::Accept( TiXmlVisitor* visitor ) const
-{
-	if ( visitor->VisitEnter( *this ) )
-	{
-		for ( const TiXmlNode* node=FirstChild(); node; node=node->NextSibling() )
-		{
-			if ( !node->Accept( visitor ) )
-				break;
-		}
-	}
-	return visitor->VisitExit( *this );
-}
-
-
-const TiXmlAttribute* TiXmlAttribute::Next() const
-{
-	// We are using knowledge of the sentinel. The sentinel
-	// have a value or name.
-	if ( next->value.empty() && next->name.empty() )
-		return 0;
-	return next;
-}
-
-/*
-TiXmlAttribute* TiXmlAttribute::Next()
-{
-	// We are using knowledge of the sentinel. The sentinel
-	// have a value or name.
-	if ( next->value.empty() && next->name.empty() )
-		return 0;
-	return next;
-}
-*/
-
-const TiXmlAttribute* TiXmlAttribute::Previous() const
-{
-	// We are using knowledge of the sentinel. The sentinel
-	// have a value or name.
-	if ( prev->value.empty() && prev->name.empty() )
-		return 0;
-	return prev;
-}
-
-/*
-TiXmlAttribute* TiXmlAttribute::Previous()
-{
-	// We are using knowledge of the sentinel. The sentinel
-	// have a value or name.
-	if ( prev->value.empty() && prev->name.empty() )
-		return 0;
-	return prev;
-}
-*/
-
-void TiXmlAttribute::Print( FILE* cfile, int /*depth*/, TIXML_STRING* str ) const
-{
-	TIXML_STRING n, v;
-
-	EncodeString( name, &n );
-	EncodeString( value, &v );
-
-	if (value.find ('\"') == TIXML_STRING::npos) {
-		if ( cfile ) {
-		fprintf (cfile, "%s=\"%s\"", n.c_str(), v.c_str() );
-		}
-		if ( str ) {
-			(*str) += n; (*str) += "=\""; (*str) += v; (*str) += "\"";
-		}
-	}
-	else {
-		if ( cfile ) {
-		fprintf (cfile, "%s='%s'", n.c_str(), v.c_str() );
-		}
-		if ( str ) {
-			(*str) += n; (*str) += "='"; (*str) += v; (*str) += "'";
-		}
-	}
-}
-
-
-int TiXmlAttribute::QueryIntValue( int* ival ) const
-{
-	if ( TIXML_SSCANF( value.c_str(), "%d", ival ) == 1 )
-		return TIXML_SUCCESS;
-	return TIXML_WRONG_TYPE;
-}
-
-int TiXmlAttribute::QueryDoubleValue( double* dval ) const
-{
-	if ( TIXML_SSCANF( value.c_str(), "%lf", dval ) == 1 )
-		return TIXML_SUCCESS;
-	return TIXML_WRONG_TYPE;
-}
-
-void TiXmlAttribute::SetIntValue( int _value )
-{
-	char buf [64];
-	#if defined(TIXML_SNPRINTF)		
-		TIXML_SNPRINTF(buf, sizeof(buf), "%d", _value);
-	#else
-		sprintf (buf, "%d", _value);
-	#endif
-	SetValue (buf);
-}
-
-void TiXmlAttribute::SetDoubleValue( double _value )
-{
-	char buf [256];
-	#if defined(TIXML_SNPRINTF)		
-		TIXML_SNPRINTF( buf, sizeof(buf), "%g", _value);
-	#else
-		sprintf (buf, "%g", _value);
-	#endif
-	SetValue (buf);
-}
-
-int TiXmlAttribute::IntValue() const
-{
-	return atoi (value.c_str ());
-}
-
-double  TiXmlAttribute::DoubleValue() const
-{
-	return atof (value.c_str ());
-}
-
-
-TiXmlComment::TiXmlComment( const TiXmlComment& copy ) : TiXmlNode( TiXmlNode::TINYXML_COMMENT )
-{
-	copy.CopyTo( this );
-}
-
-
-void TiXmlComment::operator=( const TiXmlComment& base )
-{
-	Clear();
-	base.CopyTo( this );
-}
-
-
-void TiXmlComment::Print( FILE* cfile, int depth ) const
-{
-	assert( cfile );
-	for ( int i=0; i<depth; i++ )
-	{
-		fprintf( cfile,  "    " );
-	}
-	fprintf( cfile, "<!--%s-->", value.c_str() );
-}
-
-
-void TiXmlComment::CopyTo( TiXmlComment* target ) const
-{
-	TiXmlNode::CopyTo( target );
-}
-
-
-bool TiXmlComment::Accept( TiXmlVisitor* visitor ) const
-{
-	return visitor->Visit( *this );
-}
-
-
-TiXmlNode* TiXmlComment::Clone() const
-{
-	TiXmlComment* clone = new TiXmlComment();
-
-	if ( !clone )
-		return 0;
-
-	CopyTo( clone );
-	return clone;
-}
-
-
-void TiXmlText::Print( FILE* cfile, int depth ) const
-{
-	assert( cfile );
-	if ( cdata )
-	{
-		int i;
-		fprintf( cfile, "\n" );
-		for ( i=0; i<depth; i++ ) {
-			fprintf( cfile, "    " );
-		}
-		fprintf( cfile, "<![CDATA[%s]]>\n", value.c_str() );	// unformatted output
-	}
-	else
-	{
-		TIXML_STRING buffer;
-		EncodeString( value, &buffer );
-		fprintf( cfile, "%s", buffer.c_str() );
-	}
-}
-
-
-void TiXmlText::CopyTo( TiXmlText* target ) const
-{
-	TiXmlNode::CopyTo( target );
-	target->cdata = cdata;
-}
-
-
-bool TiXmlText::Accept( TiXmlVisitor* visitor ) const
-{
-	return visitor->Visit( *this );
-}
-
-
-TiXmlNode* TiXmlText::Clone() const
-{	
-	TiXmlText* clone = 0;
-	clone = new TiXmlText( "" );
-
-	if ( !clone )
-		return 0;
-
-	CopyTo( clone );
-	return clone;
-}
-
-
-TiXmlDeclaration::TiXmlDeclaration( const char * _version,
-									const char * _encoding,
-									const char * _standalone )
-	: TiXmlNode( TiXmlNode::TINYXML_DECLARATION )
-{
-	version = _version;
-	encoding = _encoding;
-	standalone = _standalone;
-}
-
-
-#ifdef TIXML_USE_STL
-TiXmlDeclaration::TiXmlDeclaration(	const std::string& _version,
-									const std::string& _encoding,
-									const std::string& _standalone )
-	: TiXmlNode( TiXmlNode::TINYXML_DECLARATION )
-{
-	version = _version;
-	encoding = _encoding;
-	standalone = _standalone;
-}
-#endif
-
-
-TiXmlDeclaration::TiXmlDeclaration( const TiXmlDeclaration& copy )
-	: TiXmlNode( TiXmlNode::TINYXML_DECLARATION )
-{
-	copy.CopyTo( this );	
-}
-
-
-void TiXmlDeclaration::operator=( const TiXmlDeclaration& copy )
-{
-	Clear();
-	copy.CopyTo( this );
-}
-
-
-void TiXmlDeclaration::Print( FILE* cfile, int /*depth*/, TIXML_STRING* str ) const
-{
-	if ( cfile ) fprintf( cfile, "<?xml " );
-	if ( str )	 (*str) += "<?xml ";
-
-	if ( !version.empty() ) {
-		if ( cfile ) fprintf (cfile, "version=\"%s\" ", version.c_str ());
-		if ( str ) { (*str) += "version=\""; (*str) += version; (*str) += "\" "; }
-	}
-	if ( !encoding.empty() ) {
-		if ( cfile ) fprintf (cfile, "encoding=\"%s\" ", encoding.c_str ());
-		if ( str ) { (*str) += "encoding=\""; (*str) += encoding; (*str) += "\" "; }
-	}
-	if ( !standalone.empty() ) {
-		if ( cfile ) fprintf (cfile, "standalone=\"%s\" ", standalone.c_str ());
-		if ( str ) { (*str) += "standalone=\""; (*str) += standalone; (*str) += "\" "; }
-	}
-	if ( cfile ) fprintf( cfile, "?>" );
-	if ( str )	 (*str) += "?>";
-}
-
-
-void TiXmlDeclaration::CopyTo( TiXmlDeclaration* target ) const
-{
-	TiXmlNode::CopyTo( target );
-
-	target->version = version;
-	target->encoding = encoding;
-	target->standalone = standalone;
-}
-
-
-bool TiXmlDeclaration::Accept( TiXmlVisitor* visitor ) const
-{
-	return visitor->Visit( *this );
-}
-
-
-TiXmlNode* TiXmlDeclaration::Clone() const
-{	
-	TiXmlDeclaration* clone = new TiXmlDeclaration();
-
-	if ( !clone )
-		return 0;
-
-	CopyTo( clone );
-	return clone;
-}
-
-
-void TiXmlUnknown::Print( FILE* cfile, int depth ) const
-{
-	for ( int i=0; i<depth; i++ )
-		fprintf( cfile, "    " );
-	fprintf( cfile, "<%s>", value.c_str() );
-}
-
-
-void TiXmlUnknown::CopyTo( TiXmlUnknown* target ) const
-{
-	TiXmlNode::CopyTo( target );
-}
-
-
-bool TiXmlUnknown::Accept( TiXmlVisitor* visitor ) const
-{
-	return visitor->Visit( *this );
-}
-
-
-TiXmlNode* TiXmlUnknown::Clone() const
-{
-	TiXmlUnknown* clone = new TiXmlUnknown();
-
-	if ( !clone )
-		return 0;
-
-	CopyTo( clone );
-	return clone;
-}
-
-
-TiXmlAttributeSet::TiXmlAttributeSet()
-{
-	sentinel.next = &sentinel;
-	sentinel.prev = &sentinel;
-}
-
-
-TiXmlAttributeSet::~TiXmlAttributeSet()
-{
-	assert( sentinel.next == &sentinel );
-	assert( sentinel.prev == &sentinel );
-}
-
-
-void TiXmlAttributeSet::Add( TiXmlAttribute* addMe )
-{
-    #ifdef TIXML_USE_STL
-	assert( !Find( TIXML_STRING( addMe->Name() ) ) );	// Shouldn't be multiply adding to the set.
-	#else
-	assert( !Find( addMe->Name() ) );	// Shouldn't be multiply adding to the set.
-	#endif
-
-	addMe->next = &sentinel;
-	addMe->prev = sentinel.prev;
-
-	sentinel.prev->next = addMe;
-	sentinel.prev      = addMe;
-}
-
-void TiXmlAttributeSet::Remove( TiXmlAttribute* removeMe )
-{
-	TiXmlAttribute* node;
-
-	for( node = sentinel.next; node != &sentinel; node = node->next )
-	{
-		if ( node == removeMe )
-		{
-			node->prev->next = node->next;
-			node->next->prev = node->prev;
-			node->next = 0;
-			node->prev = 0;
-			return;
-		}
-	}
-	assert( 0 );		// we tried to remove a non-linked attribute.
-}
-
-
-#ifdef TIXML_USE_STL
-TiXmlAttribute* TiXmlAttributeSet::Find( const std::string& name ) const
-{
-	for( TiXmlAttribute* node = sentinel.next; node != &sentinel; node = node->next )
-	{
-		if ( node->name == name )
-			return node;
-	}
-	return 0;
-}
-
-TiXmlAttribute* TiXmlAttributeSet::FindOrCreate( const std::string& _name )
-{
-	TiXmlAttribute* attrib = Find( _name );
-	if ( !attrib ) {
-		attrib = new TiXmlAttribute();
-		Add( attrib );
-		attrib->SetName( _name );
-	}
-	return attrib;
-}
-#endif
-
-
-TiXmlAttribute* TiXmlAttributeSet::Find( const char* name ) const
-{
-	for( TiXmlAttribute* node = sentinel.next; node != &sentinel; node = node->next )
-	{
-		if ( strcmp( node->name.c_str(), name ) == 0 )
-			return node;
-	}
-	return 0;
-}
-
-
-TiXmlAttribute* TiXmlAttributeSet::FindOrCreate( const char* _name )
-{
-	TiXmlAttribute* attrib = Find( _name );
-	if ( !attrib ) {
-		attrib = new TiXmlAttribute();
-		Add( attrib );
-		attrib->SetName( _name );
-	}
-	return attrib;
-}
-
-
-#ifdef TIXML_USE_STL	
-std::istream& operator>> (std::istream & in, TiXmlNode & base)
-{
-	TIXML_STRING tag;
-	tag.reserve( 8 * 1000 );
-	base.StreamIn( &in, &tag );
-
-	base.Parse( tag.c_str(), 0, TIXML_DEFAULT_ENCODING );
-	return in;
-}
-#endif
-
-
-#ifdef TIXML_USE_STL	
-std::ostream& operator<< (std::ostream & out, const TiXmlNode & base)
-{
-	TiXmlPrinter printer;
-	printer.SetStreamPrinting();
-	base.Accept( &printer );
-	out << printer.Str();
-
-	return out;
-}
-
-
-std::string& operator<< (std::string& out, const TiXmlNode& base )
-{
-	TiXmlPrinter printer;
-	printer.SetStreamPrinting();
-	base.Accept( &printer );
-	out.append( printer.Str() );
-
-	return out;
-}
-#endif
-
-
-TiXmlHandle TiXmlHandle::FirstChild() const
-{
-	if ( node )
-	{
-		TiXmlNode* child = node->FirstChild();
-		if ( child )
-			return TiXmlHandle( child );
-	}
-	return TiXmlHandle( 0 );
-}
-
-
-TiXmlHandle TiXmlHandle::FirstChild( const char * value ) const
-{
-	if ( node )
-	{
-		TiXmlNode* child = node->FirstChild( value );
-		if ( child )
-			return TiXmlHandle( child );
-	}
-	return TiXmlHandle( 0 );
-}
-
-
-TiXmlHandle TiXmlHandle::FirstChildElement() const
-{
-	if ( node )
-	{
-		TiXmlElement* child = node->FirstChildElement();
-		if ( child )
-			return TiXmlHandle( child );
-	}
-	return TiXmlHandle( 0 );
-}
-
-
-TiXmlHandle TiXmlHandle::FirstChildElement( const char * value ) const
-{
-	if ( node )
-	{
-		TiXmlElement* child = node->FirstChildElement( value );
-		if ( child )
-			return TiXmlHandle( child );
-	}
-	return TiXmlHandle( 0 );
-}
-
-
-TiXmlHandle TiXmlHandle::Child( int count ) const
-{
-	if ( node )
-	{
-		int i;
-		TiXmlNode* child = node->FirstChild();
-		for (	i=0;
-				child && i<count;
-				child = child->NextSibling(), ++i )
-		{
-			// nothing
-		}
-		if ( child )
-			return TiXmlHandle( child );
-	}
-	return TiXmlHandle( 0 );
-}
-
-
-TiXmlHandle TiXmlHandle::Child( const char* value, int count ) const
-{
-	if ( node )
-	{
-		int i;
-		TiXmlNode* child = node->FirstChild( value );
-		for (	i=0;
-				child && i<count;
-				child = child->NextSibling( value ), ++i )
-		{
-			// nothing
-		}
-		if ( child )
-			return TiXmlHandle( child );
-	}
-	return TiXmlHandle( 0 );
-}
-
-
-TiXmlHandle TiXmlHandle::ChildElement( int count ) const
-{
-	if ( node )
-	{
-		int i;
-		TiXmlElement* child = node->FirstChildElement();
-		for (	i=0;
-				child && i<count;
-				child = child->NextSiblingElement(), ++i )
-		{
-			// nothing
-		}
-		if ( child )
-			return TiXmlHandle( child );
-	}
-	return TiXmlHandle( 0 );
-}
-
-
-TiXmlHandle TiXmlHandle::ChildElement( const char* value, int count ) const
-{
-	if ( node )
-	{
-		int i;
-		TiXmlElement* child = node->FirstChildElement( value );
-		for (	i=0;
-				child && i<count;
-				child = child->NextSiblingElement( value ), ++i )
-		{
-			// nothing
-		}
-		if ( child )
-			return TiXmlHandle( child );
-	}
-	return TiXmlHandle( 0 );
-}
-
-
-bool TiXmlPrinter::VisitEnter( const TiXmlDocument& )
-{
-	return true;
-}
-
-bool TiXmlPrinter::VisitExit( const TiXmlDocument& )
-{
-	return true;
-}
-
-bool TiXmlPrinter::VisitEnter( const TiXmlElement& element, const TiXmlAttribute* firstAttribute )
-{
-	DoIndent();
-	buffer += "<";
-	buffer += element.Value();
-
-	for( const TiXmlAttribute* attrib = firstAttribute; attrib; attrib = attrib->Next() )
-	{
-		buffer += " ";
-		attrib->Print( 0, 0, &buffer );
-	}
-
-	if ( !element.FirstChild() ) 
-	{
-		buffer += " />";
-		DoLineBreak();
-	}
-	else 
-	{
-		buffer += ">";
-		if (    element.FirstChild()->ToText()
-			  && element.LastChild() == element.FirstChild()
-			  && element.FirstChild()->ToText()->CDATA() == false )
-		{
-			simpleTextPrint = true;
-			// no DoLineBreak()!
-		}
-		else
-		{
-			DoLineBreak();
-		}
-	}
-	++depth;	
-	return true;
-}
-
-
-bool TiXmlPrinter::VisitExit( const TiXmlElement& element )
-{
-	--depth;
-	if ( !element.FirstChild() ) 
-	{
-		// nothing.
-	}
-	else 
-	{
-		if ( simpleTextPrint )
-		{
-			simpleTextPrint = false;
-		}
-		else
-		{
-			DoIndent();
-		}
-		buffer += "</";
-		buffer += element.Value();
-		buffer += ">";
-		DoLineBreak();
-	}
-	return true;
-}
-
-
-bool TiXmlPrinter::Visit( const TiXmlText& text )
-{
-	if ( text.CDATA() )
-	{
-		DoIndent();
-		buffer += "<![CDATA[";
-		buffer += text.Value();
-		buffer += "]]>";
-		DoLineBreak();
-	}
-	else if ( simpleTextPrint )
-	{
-		TIXML_STRING str;
-		TiXmlBase::EncodeString( text.ValueTStr(), &str );
-		buffer += str;
-	}
-	else
-	{
-		DoIndent();
-		TIXML_STRING str;
-		TiXmlBase::EncodeString( text.ValueTStr(), &str );
-		buffer += str;
-		DoLineBreak();
-	}
-	return true;
-}
-
-
-bool TiXmlPrinter::Visit( const TiXmlDeclaration& declaration )
-{
-	DoIndent();
-	declaration.Print( 0, 0, &buffer );
-	DoLineBreak();
-	return true;
-}
-
-
-bool TiXmlPrinter::Visit( const TiXmlComment& comment )
-{
-	DoIndent();
-	buffer += "<!--";
-	buffer += comment.Value();
-	buffer += "-->";
-	DoLineBreak();
-	return true;
-}
-
-
-bool TiXmlPrinter::Visit( const TiXmlUnknown& unknown )
-{
-	DoIndent();
-	buffer += "<";
-	buffer += unknown.Value();
-	buffer += ">";
-	DoLineBreak();
-	return true;
-}
-

+ 0 - 1802
src/tool/tool_xodrobj/TinyXML/tinyxml.h

@@ -1,1802 +0,0 @@
-/*
-www.sourceforge.net/projects/tinyxml
-Original code (2.0 and earlier )copyright (c) 2000-2006 Lee Thomason (www.grinninglizard.com)
-
-This software is provided 'as-is', without any express or implied
-warranty. In no event will the authors be held liable for any
-damages arising from the use of this software.
-
-Permission is granted to anyone to use this software for any
-purpose, including commercial applications, and to alter it and
-redistribute it freely, subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must
-not claim that you wrote the original software. If you use this
-software in a product, an acknowledgment in the product documentation
-would be appreciated but is not required.
-
-2. Altered source versions must be plainly marked as such, and
-must not be misrepresented as being the original software.
-
-3. This notice may not be removed or altered from any source
-distribution.
-*/
-#define TIXML_USE_STL
-
-
-#ifndef TINYXML_INCLUDED
-#define TINYXML_INCLUDED
-
-#ifdef _MSC_VER
-#pragma warning( push )
-#pragma warning( disable : 4530 )
-#pragma warning( disable : 4786 )
-#endif
-
-#include <ctype.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <assert.h>
-
-// Help out windows:
-#if defined( _DEBUG ) && !defined( DEBUG )
-#define DEBUG
-#endif
-
-#ifdef TIXML_USE_STL
-	#include <string>
- 	#include <iostream>
-	#include <sstream>
-	#define TIXML_STRING		std::string
-#else
-	#include "tinystr.h"
-	#define TIXML_STRING		TiXmlString
-#endif
-
-// Deprecated library function hell. Compilers want to use the
-// new safe versions. This probably doesn't fully address the problem,
-// but it gets closer. There are too many compilers for me to fully
-// test. If you get compilation troubles, undefine TIXML_SAFE
-#define TIXML_SAFE
-
-#ifdef TIXML_SAFE
-	#if defined(_MSC_VER) && (_MSC_VER >= 1400 )
-		// Microsoft visual studio, version 2005 and higher.
-		#define TIXML_SNPRINTF _snprintf_s
-		#define TIXML_SNSCANF  _snscanf_s
-		#define TIXML_SSCANF   sscanf_s
-	#elif defined(_MSC_VER) && (_MSC_VER >= 1200 )
-		// Microsoft visual studio, version 6 and higher.
-		//#pragma message( "Using _sn* functions." )
-		#define TIXML_SNPRINTF _snprintf
-		#define TIXML_SNSCANF  _snscanf
-		#define TIXML_SSCANF   sscanf
-	#elif defined(__GNUC__) && (__GNUC__ >= 3 )
-		// GCC version 3 and higher.s
-		//#warning( "Using sn* functions." )
-		#define TIXML_SNPRINTF snprintf
-		#define TIXML_SNSCANF  snscanf
-		#define TIXML_SSCANF   sscanf
-	#else
-		#define TIXML_SSCANF   sscanf
-	#endif
-#endif	
-
-class TiXmlDocument;
-class TiXmlElement;
-class TiXmlComment;
-class TiXmlUnknown;
-class TiXmlAttribute;
-class TiXmlText;
-class TiXmlDeclaration;
-class TiXmlParsingData;
-
-const int TIXML_MAJOR_VERSION = 2;
-const int TIXML_MINOR_VERSION = 6;
-const int TIXML_PATCH_VERSION = 0;
-
-/*	Internal structure for tracking location of items 
-	in the XML file.
-*/
-struct TiXmlCursor
-{
-	TiXmlCursor()		{ Clear(); }
-	void Clear()		{ row = col = -1; }
-
-	int row;	// 0 based.
-	int col;	// 0 based.
-};
-
-
-/**
-	Implements the interface to the "Visitor pattern" (see the Accept() method.)
-	If you call the Accept() method, it requires being passed a TiXmlVisitor
-	class to handle callbacks. For nodes that contain other nodes (Document, Element)
-	you will get called with a VisitEnter/VisitExit pair. Nodes that are always leaves
-	are simply called with Visit().
-
-	If you return 'true' from a Visit method, recursive parsing will continue. If you return
-	false, <b>no children of this node or its sibilings</b> will be Visited.
-
-	All flavors of Visit methods have a default implementation that returns 'true' (continue 
-	visiting). You need to only override methods that are interesting to you.
-
-	Generally Accept() is called on the TiXmlDocument, although all nodes suppert Visiting.
-
-	You should never change the document from a callback.
-
-	@sa TiXmlNode::Accept()
-*/
-class TiXmlVisitor
-{
-public:
-	virtual ~TiXmlVisitor() {}
-
-	/// Visit a document.
-	virtual bool VisitEnter( const TiXmlDocument& /*doc*/ )			{ return true; }
-	/// Visit a document.
-	virtual bool VisitExit( const TiXmlDocument& /*doc*/ )			{ return true; }
-
-	/// Visit an element.
-	virtual bool VisitEnter( const TiXmlElement& /*element*/, const TiXmlAttribute* /*firstAttribute*/ )	{ return true; }
-	/// Visit an element.
-	virtual bool VisitExit( const TiXmlElement& /*element*/ )		{ return true; }
-
-	/// Visit a declaration
-	virtual bool Visit( const TiXmlDeclaration& /*declaration*/ )	{ return true; }
-	/// Visit a text node
-	virtual bool Visit( const TiXmlText& /*text*/ )					{ return true; }
-	/// Visit a comment node
-	virtual bool Visit( const TiXmlComment& /*comment*/ )			{ return true; }
-	/// Visit an unknow node
-	virtual bool Visit( const TiXmlUnknown& /*unknown*/ )			{ return true; }
-};
-
-// Only used by Attribute::Query functions
-enum 
-{ 
-	TIXML_SUCCESS,
-	TIXML_NO_ATTRIBUTE,
-	TIXML_WRONG_TYPE
-};
-
-
-// Used by the parsing routines.
-enum TiXmlEncoding
-{
-	TIXML_ENCODING_UNKNOWN,
-	TIXML_ENCODING_UTF8,
-	TIXML_ENCODING_LEGACY
-};
-
-const TiXmlEncoding TIXML_DEFAULT_ENCODING = TIXML_ENCODING_UNKNOWN;
-
-/** TiXmlBase is a base class for every class in TinyXml.
-	It does little except to establish that TinyXml classes
-	can be printed and provide some utility functions.
-
-	In XML, the document and elements can contain
-	other elements and other types of nodes.
-
-	@verbatim
-	A Document can contain:	Element	(container or leaf)
-							Comment (leaf)
-							Unknown (leaf)
-							Declaration( leaf )
-
-	An Element can contain:	Element (container or leaf)
-							Text	(leaf)
-							Attributes (not on tree)
-							Comment (leaf)
-							Unknown (leaf)
-
-	A Decleration contains: Attributes (not on tree)
-	@endverbatim
-*/
-class TiXmlBase
-{
-	friend class TiXmlNode;
-	friend class TiXmlElement;
-	friend class TiXmlDocument;
-
-public:
-	TiXmlBase()	:	userData(0)		{}
-	virtual ~TiXmlBase()			{}
-
-	/**	All TinyXml classes can print themselves to a filestream
-		or the string class (TiXmlString in non-STL mode, std::string
-		in STL mode.) Either or both cfile and str can be null.
-		
-		This is a formatted print, and will insert 
-		tabs and newlines.
-		
-		(For an unformatted stream, use the << operator.)
-	*/
-	virtual void Print( FILE* cfile, int depth ) const = 0;
-
-	/**	The world does not agree on whether white space should be kept or
-		not. In order to make everyone happy, these global, static functions
-		are provided to set whether or not TinyXml will condense all white space
-		into a single space or not. The default is to condense. Note changing this
-		value is not thread safe.
-	*/
-	static void SetCondenseWhiteSpace( bool condense )		{ condenseWhiteSpace = condense; }
-
-	/// Return the current white space setting.
-	static bool IsWhiteSpaceCondensed()						{ return condenseWhiteSpace; }
-
-	/** Return the position, in the original source file, of this node or attribute.
-		The row and column are 1-based. (That is the first row and first column is
-		1,1). If the returns values are 0 or less, then the parser does not have
-		a row and column value.
-
-		Generally, the row and column value will be set when the TiXmlDocument::Load(),
-		TiXmlDocument::LoadFile(), or any TiXmlNode::Parse() is called. It will NOT be set
-		when the DOM was created from operator>>.
-
-		The values reflect the initial load. Once the DOM is modified programmatically
-		(by adding or changing nodes and attributes) the new values will NOT update to
-		reflect changes in the document.
-
-		There is a minor performance cost to computing the row and column. Computation
-		can be disabled if TiXmlDocument::SetTabSize() is called with 0 as the value.
-
-		@sa TiXmlDocument::SetTabSize()
-	*/
-	int Row() const			{ return location.row + 1; }
-	int Column() const		{ return location.col + 1; }	///< See Row()
-
-	void  SetUserData( void* user )			{ userData = user; }	///< Set a pointer to arbitrary user data.
-	void* GetUserData()						{ return userData; }	///< Get a pointer to arbitrary user data.
-	const void* GetUserData() const 		{ return userData; }	///< Get a pointer to arbitrary user data.
-
-	// Table that returs, for a given lead byte, the total number of bytes
-	// in the UTF-8 sequence.
-	static const int utf8ByteTable[256];
-
-	virtual const char* Parse(	const char* p, 
-								TiXmlParsingData* data, 
-								TiXmlEncoding encoding /*= TIXML_ENCODING_UNKNOWN */ ) = 0;
-
-	/** Expands entities in a string. Note this should not contian the tag's '<', '>', etc, 
-		or they will be transformed into entities!
-	*/
-	static void EncodeString( const TIXML_STRING& str, TIXML_STRING* out );
-
-	enum
-	{
-		TIXML_NO_ERROR = 0,
-		TIXML_ERROR,
-		TIXML_ERROR_OPENING_FILE,
-		TIXML_ERROR_PARSING_ELEMENT,
-		TIXML_ERROR_FAILED_TO_READ_ELEMENT_NAME,
-		TIXML_ERROR_READING_ELEMENT_VALUE,
-		TIXML_ERROR_READING_ATTRIBUTES,
-		TIXML_ERROR_PARSING_EMPTY,
-		TIXML_ERROR_READING_END_TAG,
-		TIXML_ERROR_PARSING_UNKNOWN,
-		TIXML_ERROR_PARSING_COMMENT,
-		TIXML_ERROR_PARSING_DECLARATION,
-		TIXML_ERROR_DOCUMENT_EMPTY,
-		TIXML_ERROR_EMBEDDED_NULL,
-		TIXML_ERROR_PARSING_CDATA,
-		TIXML_ERROR_DOCUMENT_TOP_ONLY,
-
-		TIXML_ERROR_STRING_COUNT
-	};
-
-protected:
-
-	static const char* SkipWhiteSpace( const char*, TiXmlEncoding encoding );
-
-	inline static bool IsWhiteSpace( char c )		
-	{ 
-		return ( isspace( (unsigned char) c ) || c == '\n' || c == '\r' ); 
-	}
-	inline static bool IsWhiteSpace( int c )
-	{
-		if ( c < 256 )
-			return IsWhiteSpace( (char) c );
-		return false;	// Again, only truly correct for English/Latin...but usually works.
-	}
-
-	#ifdef TIXML_USE_STL
-	static bool	StreamWhiteSpace( std::istream * in, TIXML_STRING * tag );
-	static bool StreamTo( std::istream * in, int character, TIXML_STRING * tag );
-	#endif
-
-	/*	Reads an XML name into the string provided. Returns
-		a pointer just past the last character of the name,
-		or 0 if the function has an error.
-	*/
-	static const char* ReadName( const char* p, TIXML_STRING* name, TiXmlEncoding encoding );
-
-	/*	Reads text. Returns a pointer past the given end tag.
-		Wickedly complex options, but it keeps the (sensitive) code in one place.
-	*/
-	static const char* ReadText(	const char* in,				// where to start
-									TIXML_STRING* text,			// the string read
-									bool ignoreWhiteSpace,		// whether to keep the white space
-									const char* endTag,			// what ends this text
-									bool ignoreCase,			// whether to ignore case in the end tag
-									TiXmlEncoding encoding );	// the current encoding
-
-	// If an entity has been found, transform it into a character.
-	static const char* GetEntity( const char* in, char* value, int* length, TiXmlEncoding encoding );
-
-	// Get a character, while interpreting entities.
-	// The length can be from 0 to 4 bytes.
-	inline static const char* GetChar( const char* p, char* _value, int* length, TiXmlEncoding encoding )
-	{
-		assert( p );
-		if ( encoding == TIXML_ENCODING_UTF8 )
-		{
-			*length = utf8ByteTable[ *((const unsigned char*)p) ];
-			assert( *length >= 0 && *length < 5 );
-		}
-		else
-		{
-			*length = 1;
-		}
-
-		if ( *length == 1 )
-		{
-			if ( *p == '&' )
-				return GetEntity( p, _value, length, encoding );
-			*_value = *p;
-			return p+1;
-		}
-		else if ( *length )
-		{
-			//strncpy( _value, p, *length );	// lots of compilers don't like this function (unsafe),
-												// and the null terminator isn't needed
-			for( int i=0; p[i] && i<*length; ++i ) {
-				_value[i] = p[i];
-			}
-			return p + (*length);
-		}
-		else
-		{
-			// Not valid text.
-			return 0;
-		}
-	}
-
-	// Return true if the next characters in the stream are any of the endTag sequences.
-	// Ignore case only works for english, and should only be relied on when comparing
-	// to English words: StringEqual( p, "version", true ) is fine.
-	static bool StringEqual(	const char* p,
-								const char* endTag,
-								bool ignoreCase,
-								TiXmlEncoding encoding );
-
-	static const char* errorString[ TIXML_ERROR_STRING_COUNT ];
-
-	TiXmlCursor location;
-
-    /// Field containing a generic user pointer
-	void*			userData;
-	
-	// None of these methods are reliable for any language except English.
-	// Good for approximation, not great for accuracy.
-	static int IsAlpha( unsigned char anyByte, TiXmlEncoding encoding );
-	static int IsAlphaNum( unsigned char anyByte, TiXmlEncoding encoding );
-	inline static int ToLower( int v, TiXmlEncoding encoding )
-	{
-		if ( encoding == TIXML_ENCODING_UTF8 )
-		{
-			if ( v < 128 ) return tolower( v );
-			return v;
-		}
-		else
-		{
-			return tolower( v );
-		}
-	}
-	static void ConvertUTF32ToUTF8( unsigned long input, char* output, int* length );
-
-private:
-	TiXmlBase( const TiXmlBase& );				// not implemented.
-	void operator=( const TiXmlBase& base );	// not allowed.
-
-	struct Entity
-	{
-		const char*     str;
-		unsigned int	strLength;
-		char		    chr;
-	};
-	enum
-	{
-		NUM_ENTITY = 5,
-		MAX_ENTITY_LENGTH = 6
-
-	};
-	static Entity entity[ NUM_ENTITY ];
-	static bool condenseWhiteSpace;
-};
-
-
-/** The parent class for everything in the Document Object Model.
-	(Except for attributes).
-	Nodes have siblings, a parent, and children. A node can be
-	in a document, or stand on its own. The type of a TiXmlNode
-	can be queried, and it can be cast to its more defined type.
-*/
-class TiXmlNode : public TiXmlBase
-{
-	friend class TiXmlDocument;
-	friend class TiXmlElement;
-
-public:
-	#ifdef TIXML_USE_STL	
-
-	    /** An input stream operator, for every class. Tolerant of newlines and
-		    formatting, but doesn't expect them.
-	    */
-	    friend std::istream& operator >> (std::istream& in, TiXmlNode& base);
-
-	    /** An output stream operator, for every class. Note that this outputs
-		    without any newlines or formatting, as opposed to Print(), which
-		    includes tabs and new lines.
-
-		    The operator<< and operator>> are not completely symmetric. Writing
-		    a node to a stream is very well defined. You'll get a nice stream
-		    of output, without any extra whitespace or newlines.
-		    
-		    But reading is not as well defined. (As it always is.) If you create
-		    a TiXmlElement (for example) and read that from an input stream,
-		    the text needs to define an element or junk will result. This is
-		    true of all input streams, but it's worth keeping in mind.
-
-		    A TiXmlDocument will read nodes until it reads a root element, and
-			all the children of that root element.
-	    */	
-	    friend std::ostream& operator<< (std::ostream& out, const TiXmlNode& base);
-
-		/// Appends the XML node or attribute to a std::string.
-		friend std::string& operator<< (std::string& out, const TiXmlNode& base );
-
-	#endif
-
-	/** The types of XML nodes supported by TinyXml. (All the
-			unsupported types are picked up by UNKNOWN.)
-	*/
-	enum NodeType
-	{
-		TINYXML_DOCUMENT,
-		TINYXML_ELEMENT,
-		TINYXML_COMMENT,
-		TINYXML_UNKNOWN,
-		TINYXML_TEXT,
-		TINYXML_DECLARATION,
-		TINYXML_TYPECOUNT
-	};
-
-	virtual ~TiXmlNode();
-
-	/** The meaning of 'value' changes for the specific type of
-		TiXmlNode.
-		@verbatim
-		Document:	filename of the xml file
-		Element:	name of the element
-		Comment:	the comment text
-		Unknown:	the tag contents
-		Text:		the text string
-		@endverbatim
-
-		The subclasses will wrap this function.
-	*/
-	const char *Value() const { return value.c_str (); }
-
-    #ifdef TIXML_USE_STL
-	/** Return Value() as a std::string. If you only use STL,
-	    this is more efficient than calling Value().
-		Only available in STL mode.
-	*/
-	const std::string& ValueStr() const { return value; }
-	#endif
-
-	const TIXML_STRING& ValueTStr() const { return value; }
-
-	/** Changes the value of the node. Defined as:
-		@verbatim
-		Document:	filename of the xml file
-		Element:	name of the element
-		Comment:	the comment text
-		Unknown:	the tag contents
-		Text:		the text string
-		@endverbatim
-	*/
-	void SetValue(const char * _value) { value = _value;}
-
-    #ifdef TIXML_USE_STL
-	/// STL std::string form.
-	void SetValue( const std::string& _value )	{ value = _value; }
-	#endif
-
-	/// Delete all the children of this node. Does not affect 'this'.
-	void Clear();
-
-	/// One step up the DOM.
-	TiXmlNode* Parent()							{ return parent; }
-	const TiXmlNode* Parent() const				{ return parent; }
-
-	const TiXmlNode* FirstChild()	const		{ return firstChild; }	///< The first child of this node. Will be null if there are no children.
-	TiXmlNode* FirstChild()						{ return firstChild; }
-	const TiXmlNode* FirstChild( const char * value ) const;			///< The first child of this node with the matching 'value'. Will be null if none found.
-	/// The first child of this node with the matching 'value'. Will be null if none found.
-	TiXmlNode* FirstChild( const char * _value ) {
-		// Call through to the const version - safe since nothing is changed. Exiting syntax: cast this to a const (always safe)
-		// call the method, cast the return back to non-const.
-		return const_cast< TiXmlNode* > ((const_cast< const TiXmlNode* >(this))->FirstChild( _value ));
-	}
-	const TiXmlNode* LastChild() const	{ return lastChild; }		/// The last child of this node. Will be null if there are no children.
-	TiXmlNode* LastChild()	{ return lastChild; }
-	
-	const TiXmlNode* LastChild( const char * value ) const;			/// The last child of this node matching 'value'. Will be null if there are no children.
-	TiXmlNode* LastChild( const char * _value ) {
-		return const_cast< TiXmlNode* > ((const_cast< const TiXmlNode* >(this))->LastChild( _value ));
-	}
-
-    #ifdef TIXML_USE_STL
-	const TiXmlNode* FirstChild( const std::string& _value ) const	{	return FirstChild (_value.c_str ());	}	///< STL std::string form.
-	TiXmlNode* FirstChild( const std::string& _value )				{	return FirstChild (_value.c_str ());	}	///< STL std::string form.
-	const TiXmlNode* LastChild( const std::string& _value ) const	{	return LastChild (_value.c_str ());	}	///< STL std::string form.
-	TiXmlNode* LastChild( const std::string& _value )				{	return LastChild (_value.c_str ());	}	///< STL std::string form.
-	#endif
-
-	/** An alternate way to walk the children of a node.
-		One way to iterate over nodes is:
-		@verbatim
-			for( child = parent->FirstChild(); child; child = child->NextSibling() )
-		@endverbatim
-
-		IterateChildren does the same thing with the syntax:
-		@verbatim
-			child = 0;
-			while( child = parent->IterateChildren( child ) )
-		@endverbatim
-
-		IterateChildren takes the previous child as input and finds
-		the next one. If the previous child is null, it returns the
-		first. IterateChildren will return null when done.
-	*/
-	const TiXmlNode* IterateChildren( const TiXmlNode* previous ) const;
-	TiXmlNode* IterateChildren( const TiXmlNode* previous ) {
-		return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->IterateChildren( previous ) );
-	}
-
-	/// This flavor of IterateChildren searches for children with a particular 'value'
-	const TiXmlNode* IterateChildren( const char * value, const TiXmlNode* previous ) const;
-	TiXmlNode* IterateChildren( const char * _value, const TiXmlNode* previous ) {
-		return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->IterateChildren( _value, previous ) );
-	}
-
-    #ifdef TIXML_USE_STL
-	const TiXmlNode* IterateChildren( const std::string& _value, const TiXmlNode* previous ) const	{	return IterateChildren (_value.c_str (), previous);	}	///< STL std::string form.
-	TiXmlNode* IterateChildren( const std::string& _value, const TiXmlNode* previous ) {	return IterateChildren (_value.c_str (), previous);	}	///< STL std::string form.
-	#endif
-
-	/** Add a new node related to this. Adds a child past the LastChild.
-		Returns a pointer to the new object or NULL if an error occured.
-	*/
-	TiXmlNode* InsertEndChild( const TiXmlNode& addThis );
-
-
-	/** Add a new node related to this. Adds a child past the LastChild.
-
-		NOTE: the node to be added is passed by pointer, and will be
-		henceforth owned (and deleted) by tinyXml. This method is efficient
-		and avoids an extra copy, but should be used with care as it
-		uses a different memory model than the other insert functions.
-
-		@sa InsertEndChild
-	*/
-	TiXmlNode* LinkEndChild( TiXmlNode* addThis );
-
-	/** Add a new node related to this. Adds a child before the specified child.
-		Returns a pointer to the new object or NULL if an error occured.
-	*/
-	TiXmlNode* InsertBeforeChild( TiXmlNode* beforeThis, const TiXmlNode& addThis );
-
-	/** Add a new node related to this. Adds a child after the specified child.
-		Returns a pointer to the new object or NULL if an error occured.
-	*/
-	TiXmlNode* InsertAfterChild(  TiXmlNode* afterThis, const TiXmlNode& addThis );
-
-	/** Replace a child of this node.
-		Returns a pointer to the new object or NULL if an error occured.
-	*/
-	TiXmlNode* ReplaceChild( TiXmlNode* replaceThis, const TiXmlNode& withThis );
-
-	/// Delete a child of this node.
-	bool RemoveChild( TiXmlNode* removeThis );
-
-	/// Navigate to a sibling node.
-	const TiXmlNode* PreviousSibling() const			{ return prev; }
-	TiXmlNode* PreviousSibling()						{ return prev; }
-
-	/// Navigate to a sibling node.
-	const TiXmlNode* PreviousSibling( const char * ) const;
-	TiXmlNode* PreviousSibling( const char *_prev ) {
-		return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->PreviousSibling( _prev ) );
-	}
-
-    #ifdef TIXML_USE_STL
-	const TiXmlNode* PreviousSibling( const std::string& _value ) const	{	return PreviousSibling (_value.c_str ());	}	///< STL std::string form.
-	TiXmlNode* PreviousSibling( const std::string& _value ) 			{	return PreviousSibling (_value.c_str ());	}	///< STL std::string form.
-	const TiXmlNode* NextSibling( const std::string& _value) const		{	return NextSibling (_value.c_str ());	}	///< STL std::string form.
-	TiXmlNode* NextSibling( const std::string& _value) 					{	return NextSibling (_value.c_str ());	}	///< STL std::string form.
-	#endif
-
-	/// Navigate to a sibling node.
-	const TiXmlNode* NextSibling() const				{ return next; }
-	TiXmlNode* NextSibling()							{ return next; }
-
-	/// Navigate to a sibling node with the given 'value'.
-	const TiXmlNode* NextSibling( const char * ) const;
-	TiXmlNode* NextSibling( const char* _next ) {
-		return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->NextSibling( _next ) );
-	}
-
-	/** Convenience function to get through elements.
-		Calls NextSibling and ToElement. Will skip all non-Element
-		nodes. Returns 0 if there is not another element.
-	*/
-	const TiXmlElement* NextSiblingElement() const;
-	TiXmlElement* NextSiblingElement() {
-		return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->NextSiblingElement() );
-	}
-
-	/** Convenience function to get through elements.
-		Calls NextSibling and ToElement. Will skip all non-Element
-		nodes. Returns 0 if there is not another element.
-	*/
-	const TiXmlElement* NextSiblingElement( const char * ) const;
-	TiXmlElement* NextSiblingElement( const char *_next ) {
-		return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->NextSiblingElement( _next ) );
-	}
-
-    #ifdef TIXML_USE_STL
-	const TiXmlElement* NextSiblingElement( const std::string& _value) const	{	return NextSiblingElement (_value.c_str ());	}	///< STL std::string form.
-	TiXmlElement* NextSiblingElement( const std::string& _value)				{	return NextSiblingElement (_value.c_str ());	}	///< STL std::string form.
-	#endif
-
-	/// Convenience function to get through elements.
-	const TiXmlElement* FirstChildElement()	const;
-	TiXmlElement* FirstChildElement() {
-		return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->FirstChildElement() );
-	}
-
-	/// Convenience function to get through elements.
-	const TiXmlElement* FirstChildElement( const char * _value ) const;
-	TiXmlElement* FirstChildElement( const char * _value ) {
-		return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->FirstChildElement( _value ) );
-	}
-
-    #ifdef TIXML_USE_STL
-	const TiXmlElement* FirstChildElement( const std::string& _value ) const	{	return FirstChildElement (_value.c_str ());	}	///< STL std::string form.
-	TiXmlElement* FirstChildElement( const std::string& _value )				{	return FirstChildElement (_value.c_str ());	}	///< STL std::string form.
-	#endif
-
-	/** Query the type (as an enumerated value, above) of this node.
-		The possible types are: DOCUMENT, ELEMENT, COMMENT,
-								UNKNOWN, TEXT, and DECLARATION.
-	*/
-	int Type() const	{ return type; }
-
-	/** Return a pointer to the Document this node lives in.
-		Returns null if not in a document.
-	*/
-	const TiXmlDocument* GetDocument() const;
-	TiXmlDocument* GetDocument() {
-		return const_cast< TiXmlDocument* >( (const_cast< const TiXmlNode* >(this))->GetDocument() );
-	}
-
-	/// Returns true if this node has no children.
-	bool NoChildren() const						{ return !firstChild; }
-
-	virtual const TiXmlDocument*    ToDocument()    const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual const TiXmlElement*     ToElement()     const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual const TiXmlComment*     ToComment()     const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual const TiXmlUnknown*     ToUnknown()     const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual const TiXmlText*        ToText()        const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual const TiXmlDeclaration* ToDeclaration() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-
-	virtual TiXmlDocument*          ToDocument()    { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual TiXmlElement*           ToElement()	    { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual TiXmlComment*           ToComment()     { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual TiXmlUnknown*           ToUnknown()	    { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual TiXmlText*	            ToText()        { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-	virtual TiXmlDeclaration*       ToDeclaration() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type.
-
-	/** Create an exact duplicate of this node and return it. The memory must be deleted
-		by the caller. 
-	*/
-	virtual TiXmlNode* Clone() const = 0;
-
-	/** Accept a hierchical visit the nodes in the TinyXML DOM. Every node in the 
-		XML tree will be conditionally visited and the host will be called back
-		via the TiXmlVisitor interface.
-
-		This is essentially a SAX interface for TinyXML. (Note however it doesn't re-parse
-		the XML for the callbacks, so the performance of TinyXML is unchanged by using this
-		interface versus any other.)
-
-		The interface has been based on ideas from:
-
-		- http://www.saxproject.org/
-		- http://c2.com/cgi/wiki?HierarchicalVisitorPattern 
-
-		Which are both good references for "visiting".
-
-		An example of using Accept():
-		@verbatim
-		TiXmlPrinter printer;
-		tinyxmlDoc.Accept( &printer );
-		const char* xmlcstr = printer.CStr();
-		@endverbatim
-	*/
-	virtual bool Accept( TiXmlVisitor* visitor ) const = 0;
-
-protected:
-	TiXmlNode( NodeType _type );
-
-	// Copy to the allocated object. Shared functionality between Clone, Copy constructor,
-	// and the assignment operator.
-	void CopyTo( TiXmlNode* target ) const;
-
-	#ifdef TIXML_USE_STL
-	    // The real work of the input operator.
-	virtual void StreamIn( std::istream* in, TIXML_STRING* tag ) = 0;
-	#endif
-
-	// Figure out what is at *p, and parse it. Returns null if it is not an xml node.
-	TiXmlNode* Identify( const char* start, TiXmlEncoding encoding );
-
-	TiXmlNode*		parent;
-	NodeType		type;
-
-	TiXmlNode*		firstChild;
-	TiXmlNode*		lastChild;
-
-	TIXML_STRING	value;
-
-	TiXmlNode*		prev;
-	TiXmlNode*		next;
-
-private:
-	TiXmlNode( const TiXmlNode& );				// not implemented.
-	void operator=( const TiXmlNode& base );	// not allowed.
-};
-
-
-/** An attribute is a name-value pair. Elements have an arbitrary
-	number of attributes, each with a unique name.
-
-	@note The attributes are not TiXmlNodes, since they are not
-		  part of the tinyXML document object model. There are other
-		  suggested ways to look at this problem.
-*/
-class TiXmlAttribute : public TiXmlBase
-{
-	friend class TiXmlAttributeSet;
-
-public:
-	/// Construct an empty attribute.
-	TiXmlAttribute() : TiXmlBase()
-	{
-		document = 0;
-		prev = next = 0;
-	}
-
-	#ifdef TIXML_USE_STL
-	/// std::string constructor.
-	TiXmlAttribute( const std::string& _name, const std::string& _value )
-	{
-		name = _name;
-		value = _value;
-		document = 0;
-		prev = next = 0;
-	}
-	#endif
-
-	/// Construct an attribute with a name and value.
-	TiXmlAttribute( const char * _name, const char * _value )
-	{
-		name = _name;
-		value = _value;
-		document = 0;
-		prev = next = 0;
-	}
-
-	const char*		Name()  const		{ return name.c_str(); }		///< Return the name of this attribute.
-	const char*		Value() const		{ return value.c_str(); }		///< Return the value of this attribute.
-	#ifdef TIXML_USE_STL
-	const std::string& ValueStr() const	{ return value; }				///< Return the value of this attribute.
-	#endif
-	int				IntValue() const;									///< Return the value of this attribute, converted to an integer.
-	double			DoubleValue() const;								///< Return the value of this attribute, converted to a double.
-
-	// Get the tinyxml string representation
-	const TIXML_STRING& NameTStr() const { return name; }
-
-	/** QueryIntValue examines the value string. It is an alternative to the
-		IntValue() method with richer error checking.
-		If the value is an integer, it is stored in 'value' and 
-		the call returns TIXML_SUCCESS. If it is not
-		an integer, it returns TIXML_WRONG_TYPE.
-
-		A specialized but useful call. Note that for success it returns 0,
-		which is the opposite of almost all other TinyXml calls.
-	*/
-	int QueryIntValue( int* _value ) const;
-	/// QueryDoubleValue examines the value string. See QueryIntValue().
-	int QueryDoubleValue( double* _value ) const;
-
-	void SetName( const char* _name )	{ name = _name; }				///< Set the name of this attribute.
-	void SetValue( const char* _value )	{ value = _value; }				///< Set the value.
-
-	void SetIntValue( int _value );										///< Set the value from an integer.
-	void SetDoubleValue( double _value );								///< Set the value from a double.
-
-    #ifdef TIXML_USE_STL
-	/// STL std::string form.
-	void SetName( const std::string& _name )	{ name = _name; }	
-	/// STL std::string form.	
-	void SetValue( const std::string& _value )	{ value = _value; }
-	#endif
-
-	/// Get the next sibling attribute in the DOM. Returns null at end.
-	const TiXmlAttribute* Next() const;
-	TiXmlAttribute* Next() {
-		return const_cast< TiXmlAttribute* >( (const_cast< const TiXmlAttribute* >(this))->Next() ); 
-	}
-
-	/// Get the previous sibling attribute in the DOM. Returns null at beginning.
-	const TiXmlAttribute* Previous() const;
-	TiXmlAttribute* Previous() {
-		return const_cast< TiXmlAttribute* >( (const_cast< const TiXmlAttribute* >(this))->Previous() ); 
-	}
-
-	bool operator==( const TiXmlAttribute& rhs ) const { return rhs.name == name; }
-	bool operator<( const TiXmlAttribute& rhs )	 const { return name < rhs.name; }
-	bool operator>( const TiXmlAttribute& rhs )  const { return name > rhs.name; }
-
-	/*	Attribute parsing starts: first letter of the name
-						 returns: the next char after the value end quote
-	*/
-	virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding );
-
-	// Prints this Attribute to a FILE stream.
-	virtual void Print( FILE* cfile, int depth ) const {
-		Print( cfile, depth, 0 );
-	}
-	void Print( FILE* cfile, int depth, TIXML_STRING* str ) const;
-
-	// [internal use]
-	// Set the document pointer so the attribute can report errors.
-	void SetDocument( TiXmlDocument* doc )	{ document = doc; }
-
-private:
-	TiXmlAttribute( const TiXmlAttribute& );				// not implemented.
-	void operator=( const TiXmlAttribute& base );	// not allowed.
-
-	TiXmlDocument*	document;	// A pointer back to a document, for error reporting.
-	TIXML_STRING name;
-	TIXML_STRING value;
-	TiXmlAttribute*	prev;
-	TiXmlAttribute*	next;
-};
-
-
-/*	A class used to manage a group of attributes.
-	It is only used internally, both by the ELEMENT and the DECLARATION.
-	
-	The set can be changed transparent to the Element and Declaration
-	classes that use it, but NOT transparent to the Attribute
-	which has to implement a next() and previous() method. Which makes
-	it a bit problematic and prevents the use of STL.
-
-	This version is implemented with circular lists because:
-		- I like circular lists
-		- it demonstrates some independence from the (typical) doubly linked list.
-*/
-class TiXmlAttributeSet
-{
-public:
-	TiXmlAttributeSet();
-	~TiXmlAttributeSet();
-
-	void Add( TiXmlAttribute* attribute );
-	void Remove( TiXmlAttribute* attribute );
-
-	const TiXmlAttribute* First()	const	{ return ( sentinel.next == &sentinel ) ? 0 : sentinel.next; }
-	TiXmlAttribute* First()					{ return ( sentinel.next == &sentinel ) ? 0 : sentinel.next; }
-	const TiXmlAttribute* Last() const		{ return ( sentinel.prev == &sentinel ) ? 0 : sentinel.prev; }
-	TiXmlAttribute* Last()					{ return ( sentinel.prev == &sentinel ) ? 0 : sentinel.prev; }
-
-	TiXmlAttribute*	Find( const char* _name ) const;
-	TiXmlAttribute* FindOrCreate( const char* _name );
-
-#	ifdef TIXML_USE_STL
-	TiXmlAttribute*	Find( const std::string& _name ) const;
-	TiXmlAttribute* FindOrCreate( const std::string& _name );
-#	endif
-
-
-private:
-	//*ME:	Because of hidden/disabled copy-construktor in TiXmlAttribute (sentinel-element),
-	//*ME:	this class must be also use a hidden/disabled copy-constructor !!!
-	TiXmlAttributeSet( const TiXmlAttributeSet& );	// not allowed
-	void operator=( const TiXmlAttributeSet& );	// not allowed (as TiXmlAttribute)
-
-	TiXmlAttribute sentinel;
-};
-
-
-/** The element is a container class. It has a value, the element name,
-	and can contain other elements, text, comments, and unknowns.
-	Elements also contain an arbitrary number of attributes.
-*/
-class TiXmlElement : public TiXmlNode
-{
-public:
-	/// Construct an element.
-	TiXmlElement (const char * in_value);
-
-	#ifdef TIXML_USE_STL
-	/// std::string constructor.
-	TiXmlElement( const std::string& _value );
-	#endif
-
-	TiXmlElement( const TiXmlElement& );
-
-	void operator=( const TiXmlElement& base );
-
-	virtual ~TiXmlElement();
-
-	/** Given an attribute name, Attribute() returns the value
-		for the attribute of that name, or null if none exists.
-	*/
-	const char* Attribute( const char* name ) const;
-
-	/** Given an attribute name, Attribute() returns the value
-		for the attribute of that name, or null if none exists.
-		If the attribute exists and can be converted to an integer,
-		the integer value will be put in the return 'i', if 'i'
-		is non-null.
-	*/
-	const char* Attribute( const char* name, int* i ) const;
-
-	/** Given an attribute name, Attribute() returns the value
-		for the attribute of that name, or null if none exists.
-		If the attribute exists and can be converted to an double,
-		the double value will be put in the return 'd', if 'd'
-		is non-null.
-	*/
-	const char* Attribute( const char* name, double* d ) const;
-
-	/** QueryIntAttribute examines the attribute - it is an alternative to the
-		Attribute() method with richer error checking.
-		If the attribute is an integer, it is stored in 'value' and 
-		the call returns TIXML_SUCCESS. If it is not
-		an integer, it returns TIXML_WRONG_TYPE. If the attribute
-		does not exist, then TIXML_NO_ATTRIBUTE is returned.
-	*/	
-	int QueryIntAttribute( const char* name, int* _value ) const;
-	/// QueryDoubleAttribute examines the attribute - see QueryIntAttribute().
-	int QueryDoubleAttribute( const char* name, double* _value ) const;
-	/// QueryFloatAttribute examines the attribute - see QueryIntAttribute().
-	int QueryFloatAttribute( const char* name, float* _value ) const {
-		double d;
-		int result = QueryDoubleAttribute( name, &d );
-		if ( result == TIXML_SUCCESS ) {
-			*_value = (float)d;
-		}
-		return result;
-	}
-
-    #ifdef TIXML_USE_STL
-	/// QueryStringAttribute examines the attribute - see QueryIntAttribute().
-	int QueryStringAttribute( const char* name, std::string* _value ) const {
-		const char* cstr = Attribute( name );
-		if ( cstr ) {
-			*_value = std::string( cstr );
-			return TIXML_SUCCESS;
-		}
-		return TIXML_NO_ATTRIBUTE;
-	}
-
-	/** Template form of the attribute query which will try to read the
-		attribute into the specified type. Very easy, very powerful, but
-		be careful to make sure to call this with the correct type.
-		
-		NOTE: This method doesn't work correctly for 'string' types that contain spaces.
-
-		@return TIXML_SUCCESS, TIXML_WRONG_TYPE, or TIXML_NO_ATTRIBUTE
-	*/
-	template< typename T > int QueryValueAttribute( const std::string& name, T* outValue ) const
-	{
-		const TiXmlAttribute* node = attributeSet.Find( name );
-		if ( !node )
-			return TIXML_NO_ATTRIBUTE;
-
-		std::stringstream sstream( node->ValueStr() );
-		sstream >> *outValue;
-		if ( !sstream.fail() )
-			return TIXML_SUCCESS;
-		return TIXML_WRONG_TYPE;
-	}
-
-	int QueryValueAttribute( const std::string& name, std::string* outValue ) const
-	{
-		const TiXmlAttribute* node = attributeSet.Find( name );
-		if ( !node )
-			return TIXML_NO_ATTRIBUTE;
-		*outValue = node->ValueStr();
-		return TIXML_SUCCESS;
-	}
-	#endif
-
-	/** Sets an attribute of name to a given value. The attribute
-		will be created if it does not exist, or changed if it does.
-	*/
-	void SetAttribute( const char* name, const char * _value );
-
-    #ifdef TIXML_USE_STL
-	const std::string* Attribute( const std::string& name ) const;
-	const std::string* Attribute( const std::string& name, int* i ) const;
-	const std::string* Attribute( const std::string& name, double* d ) const;
-	int QueryIntAttribute( const std::string& name, int* _value ) const;
-	int QueryDoubleAttribute( const std::string& name, double* _value ) const;
-
-	/// STL std::string form.
-	void SetAttribute( const std::string& name, const std::string& _value );
-	///< STL std::string form.
-	void SetAttribute( const std::string& name, int _value );
-	///< STL std::string form.
-	void SetDoubleAttribute( const std::string& name, double value );
-	#endif
-
-	/** Sets an attribute of name to a given value. The attribute
-		will be created if it does not exist, or changed if it does.
-	*/
-	void SetAttribute( const char * name, int value );
-
-	/** Sets an attribute of name to a given value. The attribute
-		will be created if it does not exist, or changed if it does.
-	*/
-	void SetDoubleAttribute( const char * name, double value );
-
-	/** Deletes an attribute with the given name.
-	*/
-	void RemoveAttribute( const char * name );
-    #ifdef TIXML_USE_STL
-	void RemoveAttribute( const std::string& name )	{	RemoveAttribute (name.c_str ());	}	///< STL std::string form.
-	#endif
-
-	const TiXmlAttribute* FirstAttribute() const	{ return attributeSet.First(); }		///< Access the first attribute in this element.
-	TiXmlAttribute* FirstAttribute() 				{ return attributeSet.First(); }
-	const TiXmlAttribute* LastAttribute()	const 	{ return attributeSet.Last(); }		///< Access the last attribute in this element.
-	TiXmlAttribute* LastAttribute()					{ return attributeSet.Last(); }
-
-	/** Convenience function for easy access to the text inside an element. Although easy
-		and concise, GetText() is limited compared to getting the TiXmlText child
-		and accessing it directly.
-	
-		If the first child of 'this' is a TiXmlText, the GetText()
-		returns the character string of the Text node, else null is returned.
-
-		This is a convenient method for getting the text of simple contained text:
-		@verbatim
-		<foo>This is text</foo>
-		const char* str = fooElement->GetText();
-		@endverbatim
-
-		'str' will be a pointer to "This is text". 
-		
-		Note that this function can be misleading. If the element foo was created from
-		this XML:
-		@verbatim
-		<foo><b>This is text</b></foo> 
-		@endverbatim
-
-		then the value of str would be null. The first child node isn't a text node, it is
-		another element. From this XML:
-		@verbatim
-		<foo>This is <b>text</b></foo> 
-		@endverbatim
-		GetText() will return "This is ".
-
-		WARNING: GetText() accesses a child node - don't become confused with the 
-				 similarly named TiXmlHandle::Text() and TiXmlNode::ToText() which are 
-				 safe type casts on the referenced node.
-	*/
-	const char* GetText() const;
-
-	/// Creates a new Element and returns it - the returned element is a copy.
-	virtual TiXmlNode* Clone() const;
-	// Print the Element to a FILE stream.
-	virtual void Print( FILE* cfile, int depth ) const;
-
-	/*	Attribtue parsing starts: next char past '<'
-						 returns: next char past '>'
-	*/
-	virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding );
-
-	virtual const TiXmlElement*     ToElement()     const { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-	virtual TiXmlElement*           ToElement()	          { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-
-	/** Walk the XML tree visiting this node and all of its children. 
-	*/
-	virtual bool Accept( TiXmlVisitor* visitor ) const;
-
-protected:
-
-	void CopyTo( TiXmlElement* target ) const;
-	void ClearThis();	// like clear, but initializes 'this' object as well
-
-	// Used to be public [internal use]
-	#ifdef TIXML_USE_STL
-	virtual void StreamIn( std::istream * in, TIXML_STRING * tag );
-	#endif
-	/*	[internal use]
-		Reads the "value" of the element -- another element, or text.
-		This should terminate with the current end tag.
-	*/
-	const char* ReadValue( const char* in, TiXmlParsingData* prevData, TiXmlEncoding encoding );
-
-private:
-	TiXmlAttributeSet attributeSet;
-};
-
-
-/**	An XML comment.
-*/
-class TiXmlComment : public TiXmlNode
-{
-public:
-	/// Constructs an empty comment.
-	TiXmlComment() : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) {}
-	/// Construct a comment from text.
-	TiXmlComment( const char* _value ) : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) {
-		SetValue( _value );
-	}
-	TiXmlComment( const TiXmlComment& );
-	void operator=( const TiXmlComment& base );
-
-	virtual ~TiXmlComment()	{}
-
-	/// Returns a copy of this Comment.
-	virtual TiXmlNode* Clone() const;
-	// Write this Comment to a FILE stream.
-	virtual void Print( FILE* cfile, int depth ) const;
-
-	/*	Attribtue parsing starts: at the ! of the !--
-						 returns: next char past '>'
-	*/
-	virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding );
-
-	virtual const TiXmlComment*  ToComment() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-	virtual TiXmlComment*  ToComment() { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-
-	/** Walk the XML tree visiting this node and all of its children. 
-	*/
-	virtual bool Accept( TiXmlVisitor* visitor ) const;
-
-protected:
-	void CopyTo( TiXmlComment* target ) const;
-
-	// used to be public
-	#ifdef TIXML_USE_STL
-	virtual void StreamIn( std::istream * in, TIXML_STRING * tag );
-	#endif
-//	virtual void StreamOut( TIXML_OSTREAM * out ) const;
-
-private:
-
-};
-
-
-/** XML text. A text node can have 2 ways to output the next. "normal" output 
-	and CDATA. It will default to the mode it was parsed from the XML file and
-	you generally want to leave it alone, but you can change the output mode with 
-	SetCDATA() and query it with CDATA().
-*/
-class TiXmlText : public TiXmlNode
-{
-	friend class TiXmlElement;
-public:
-	/** Constructor for text element. By default, it is treated as 
-		normal, encoded text. If you want it be output as a CDATA text
-		element, set the parameter _cdata to 'true'
-	*/
-	TiXmlText (const char * initValue ) : TiXmlNode (TiXmlNode::TINYXML_TEXT)
-	{
-		SetValue( initValue );
-		cdata = false;
-	}
-	virtual ~TiXmlText() {}
-
-	#ifdef TIXML_USE_STL
-	/// Constructor.
-	TiXmlText( const std::string& initValue ) : TiXmlNode (TiXmlNode::TINYXML_TEXT)
-	{
-		SetValue( initValue );
-		cdata = false;
-	}
-	#endif
-
-	TiXmlText( const TiXmlText& copy ) : TiXmlNode( TiXmlNode::TINYXML_TEXT )	{ copy.CopyTo( this ); }
-	void operator=( const TiXmlText& base )							 	{ base.CopyTo( this ); }
-
-	// Write this text object to a FILE stream.
-	virtual void Print( FILE* cfile, int depth ) const;
-
-	/// Queries whether this represents text using a CDATA section.
-	bool CDATA() const				{ return cdata; }
-	/// Turns on or off a CDATA representation of text.
-	void SetCDATA( bool _cdata )	{ cdata = _cdata; }
-
-	virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding );
-
-	virtual const TiXmlText* ToText() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-	virtual TiXmlText*       ToText()       { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-
-	/** Walk the XML tree visiting this node and all of its children. 
-	*/
-	virtual bool Accept( TiXmlVisitor* content ) const;
-
-protected :
-	///  [internal use] Creates a new Element and returns it.
-	virtual TiXmlNode* Clone() const;
-	void CopyTo( TiXmlText* target ) const;
-
-	bool Blank() const;	// returns true if all white space and new lines
-	// [internal use]
-	#ifdef TIXML_USE_STL
-	virtual void StreamIn( std::istream * in, TIXML_STRING * tag );
-	#endif
-
-private:
-	bool cdata;			// true if this should be input and output as a CDATA style text element
-};
-
-
-/** In correct XML the declaration is the first entry in the file.
-	@verbatim
-		<?xml version="1.0" standalone="yes"?>
-	@endverbatim
-
-	TinyXml will happily read or write files without a declaration,
-	however. There are 3 possible attributes to the declaration:
-	version, encoding, and standalone.
-
-	Note: In this version of the code, the attributes are
-	handled as special cases, not generic attributes, simply
-	because there can only be at most 3 and they are always the same.
-*/
-class TiXmlDeclaration : public TiXmlNode
-{
-public:
-	/// Construct an empty declaration.
-	TiXmlDeclaration()   : TiXmlNode( TiXmlNode::TINYXML_DECLARATION ) {}
-
-#ifdef TIXML_USE_STL
-	/// Constructor.
-	TiXmlDeclaration(	const std::string& _version,
-						const std::string& _encoding,
-						const std::string& _standalone );
-#endif
-
-	/// Construct.
-	TiXmlDeclaration(	const char* _version,
-						const char* _encoding,
-						const char* _standalone );
-
-	TiXmlDeclaration( const TiXmlDeclaration& copy );
-	void operator=( const TiXmlDeclaration& copy );
-
-	virtual ~TiXmlDeclaration()	{}
-
-	/// Version. Will return an empty string if none was found.
-	const char *Version() const			{ return version.c_str (); }
-	/// Encoding. Will return an empty string if none was found.
-	const char *Encoding() const		{ return encoding.c_str (); }
-	/// Is this a standalone document?
-	const char *Standalone() const		{ return standalone.c_str (); }
-
-	/// Creates a copy of this Declaration and returns it.
-	virtual TiXmlNode* Clone() const;
-	// Print this declaration to a FILE stream.
-	virtual void Print( FILE* cfile, int depth, TIXML_STRING* str ) const;
-	virtual void Print( FILE* cfile, int depth ) const {
-		Print( cfile, depth, 0 );
-	}
-
-	virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding );
-
-	virtual const TiXmlDeclaration* ToDeclaration() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-	virtual TiXmlDeclaration*       ToDeclaration()       { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-
-	/** Walk the XML tree visiting this node and all of its children. 
-	*/
-	virtual bool Accept( TiXmlVisitor* visitor ) const;
-
-protected:
-	void CopyTo( TiXmlDeclaration* target ) const;
-	// used to be public
-	#ifdef TIXML_USE_STL
-	virtual void StreamIn( std::istream * in, TIXML_STRING * tag );
-	#endif
-
-private:
-
-	TIXML_STRING version;
-	TIXML_STRING encoding;
-	TIXML_STRING standalone;
-};
-
-
-/** Any tag that tinyXml doesn't recognize is saved as an
-	unknown. It is a tag of text, but should not be modified.
-	It will be written back to the XML, unchanged, when the file
-	is saved.
-
-	DTD tags get thrown into TiXmlUnknowns.
-*/
-class TiXmlUnknown : public TiXmlNode
-{
-public:
-	TiXmlUnknown() : TiXmlNode( TiXmlNode::TINYXML_UNKNOWN )	{}
-	virtual ~TiXmlUnknown() {}
-
-	TiXmlUnknown( const TiXmlUnknown& copy ) : TiXmlNode( TiXmlNode::TINYXML_UNKNOWN )		{ copy.CopyTo( this ); }
-	void operator=( const TiXmlUnknown& copy )										{ copy.CopyTo( this ); }
-
-	/// Creates a copy of this Unknown and returns it.
-	virtual TiXmlNode* Clone() const;
-	// Print this Unknown to a FILE stream.
-	virtual void Print( FILE* cfile, int depth ) const;
-
-	virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding );
-
-	virtual const TiXmlUnknown*     ToUnknown()     const { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-	virtual TiXmlUnknown*           ToUnknown()	    { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-
-	/** Walk the XML tree visiting this node and all of its children. 
-	*/
-	virtual bool Accept( TiXmlVisitor* content ) const;
-
-protected:
-	void CopyTo( TiXmlUnknown* target ) const;
-
-	#ifdef TIXML_USE_STL
-	virtual void StreamIn( std::istream * in, TIXML_STRING * tag );
-	#endif
-
-private:
-
-};
-
-
-/** Always the top level node. A document binds together all the
-	XML pieces. It can be saved, loaded, and printed to the screen.
-	The 'value' of a document node is the xml file name.
-*/
-class TiXmlDocument : public TiXmlNode
-{
-public:
-	/// Create an empty document, that has no name.
-	TiXmlDocument();
-	/// Create a document with a name. The name of the document is also the filename of the xml.
-	TiXmlDocument( const char * documentName );
-
-	#ifdef TIXML_USE_STL
-	/// Constructor.
-	TiXmlDocument( const std::string& documentName );
-	#endif
-
-	TiXmlDocument( const TiXmlDocument& copy );
-	void operator=( const TiXmlDocument& copy );
-
-	virtual ~TiXmlDocument() {}
-
-	/** Load a file using the current document value.
-		Returns true if successful. Will delete any existing
-		document data before loading.
-	*/
-	bool LoadFile( TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING );
-	/// Save a file using the current document value. Returns true if successful.
-	bool SaveFile() const;
-	/// Load a file using the given filename. Returns true if successful.
-	bool LoadFile( const char * filename, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING );
-	/// Save a file using the given filename. Returns true if successful.
-	bool SaveFile( const char * filename ) const;
-	/** Load a file using the given FILE*. Returns true if successful. Note that this method
-		doesn't stream - the entire object pointed at by the FILE*
-		will be interpreted as an XML file. TinyXML doesn't stream in XML from the current
-		file location. Streaming may be added in the future.
-	*/
-	bool LoadFile( FILE*, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING );
-	/// Save a file using the given FILE*. Returns true if successful.
-	bool SaveFile( FILE* ) const;
-
-	#ifdef TIXML_USE_STL
-	bool LoadFile( const std::string& filename, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING )			///< STL std::string version.
-	{
-		return LoadFile( filename.c_str(), encoding );
-	}
-	bool SaveFile( const std::string& filename ) const		///< STL std::string version.
-	{
-		return SaveFile( filename.c_str() );
-	}
-	#endif
-
-	/** Parse the given null terminated block of xml data. Passing in an encoding to this
-		method (either TIXML_ENCODING_LEGACY or TIXML_ENCODING_UTF8 will force TinyXml
-		to use that encoding, regardless of what TinyXml might otherwise try to detect.
-	*/
-	virtual const char* Parse( const char* p, TiXmlParsingData* data = 0, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING );
-
-	/** Get the root element -- the only top level element -- of the document.
-		In well formed XML, there should only be one. TinyXml is tolerant of
-		multiple elements at the document level.
-	*/
-	const TiXmlElement* RootElement() const		{ return FirstChildElement(); }
-	TiXmlElement* RootElement()					{ return FirstChildElement(); }
-
-	/** If an error occurs, Error will be set to true. Also,
-		- The ErrorId() will contain the integer identifier of the error (not generally useful)
-		- The ErrorDesc() method will return the name of the error. (very useful)
-		- The ErrorRow() and ErrorCol() will return the location of the error (if known)
-	*/	
-	bool Error() const						{ return error; }
-
-	/// Contains a textual (english) description of the error if one occurs.
-	const char * ErrorDesc() const	{ return errorDesc.c_str (); }
-
-	/** Generally, you probably want the error string ( ErrorDesc() ). But if you
-		prefer the ErrorId, this function will fetch it.
-	*/
-	int ErrorId()	const				{ return errorId; }
-
-	/** Returns the location (if known) of the error. The first column is column 1, 
-		and the first row is row 1. A value of 0 means the row and column wasn't applicable
-		(memory errors, for example, have no row/column) or the parser lost the error. (An
-		error in the error reporting, in that case.)
-
-		@sa SetTabSize, Row, Column
-	*/
-	int ErrorRow() const	{ return errorLocation.row+1; }
-	int ErrorCol() const	{ return errorLocation.col+1; }	///< The column where the error occured. See ErrorRow()
-
-	/** SetTabSize() allows the error reporting functions (ErrorRow() and ErrorCol())
-		to report the correct values for row and column. It does not change the output
-		or input in any way.
-		
-		By calling this method, with a tab size
-		greater than 0, the row and column of each node and attribute is stored
-		when the file is loaded. Very useful for tracking the DOM back in to
-		the source file.
-
-		The tab size is required for calculating the location of nodes. If not
-		set, the default of 4 is used. The tabsize is set per document. Setting
-		the tabsize to 0 disables row/column tracking.
-
-		Note that row and column tracking is not supported when using operator>>.
-
-		The tab size needs to be enabled before the parse or load. Correct usage:
-		@verbatim
-		TiXmlDocument doc;
-		doc.SetTabSize( 8 );
-		doc.Load( "myfile.xml" );
-		@endverbatim
-
-		@sa Row, Column
-	*/
-	void SetTabSize( int _tabsize )		{ tabsize = _tabsize; }
-
-	int TabSize() const	{ return tabsize; }
-
-	/** If you have handled the error, it can be reset with this call. The error
-		state is automatically cleared if you Parse a new XML block.
-	*/
-	void ClearError()						{	error = false; 
-												errorId = 0; 
-												errorDesc = ""; 
-												errorLocation.row = errorLocation.col = 0; 
-												//errorLocation.last = 0; 
-											}
-
-	/** Write the document to standard out using formatted printing ("pretty print"). */
-	void Print() const						{ Print( stdout, 0 ); }
-
-	/* Write the document to a string using formatted printing ("pretty print"). This
-		will allocate a character array (new char[]) and return it as a pointer. The
-		calling code pust call delete[] on the return char* to avoid a memory leak.
-	*/
-	//char* PrintToMemory() const; 
-
-	/// Print this Document to a FILE stream.
-	virtual void Print( FILE* cfile, int depth = 0 ) const;
-	// [internal use]
-	void SetError( int err, const char* errorLocation, TiXmlParsingData* prevData, TiXmlEncoding encoding );
-
-	virtual const TiXmlDocument*    ToDocument()    const { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-	virtual TiXmlDocument*          ToDocument()          { return this; } ///< Cast to a more defined type. Will return null not of the requested type.
-
-	/** Walk the XML tree visiting this node and all of its children. 
-	*/
-	virtual bool Accept( TiXmlVisitor* content ) const;
-
-protected :
-	// [internal use]
-	virtual TiXmlNode* Clone() const;
-	#ifdef TIXML_USE_STL
-	virtual void StreamIn( std::istream * in, TIXML_STRING * tag );
-	#endif
-
-private:
-	void CopyTo( TiXmlDocument* target ) const;
-
-	bool error;
-	int  errorId;
-	TIXML_STRING errorDesc;
-	int tabsize;
-	TiXmlCursor errorLocation;
-	bool useMicrosoftBOM;		// the UTF-8 BOM were found when read. Note this, and try to write.
-};
-
-
-/**
-	A TiXmlHandle is a class that wraps a node pointer with null checks; this is
-	an incredibly useful thing. Note that TiXmlHandle is not part of the TinyXml
-	DOM structure. It is a separate utility class.
-
-	Take an example:
-	@verbatim
-	<Document>
-		<Element attributeA = "valueA">
-			<Child attributeB = "value1" />
-			<Child attributeB = "value2" />
-		</Element>
-	<Document>
-	@endverbatim
-
-	Assuming you want the value of "attributeB" in the 2nd "Child" element, it's very 
-	easy to write a *lot* of code that looks like:
-
-	@verbatim
-	TiXmlElement* root = document.FirstChildElement( "Document" );
-	if ( root )
-	{
-		TiXmlElement* element = root->FirstChildElement( "Element" );
-		if ( element )
-		{
-			TiXmlElement* child = element->FirstChildElement( "Child" );
-			if ( child )
-			{
-				TiXmlElement* child2 = child->NextSiblingElement( "Child" );
-				if ( child2 )
-				{
-					// Finally do something useful.
-	@endverbatim
-
-	And that doesn't even cover "else" cases. TiXmlHandle addresses the verbosity
-	of such code. A TiXmlHandle checks for null	pointers so it is perfectly safe 
-	and correct to use:
-
-	@verbatim
-	TiXmlHandle docHandle( &document );
-	TiXmlElement* child2 = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).Child( "Child", 1 ).ToElement();
-	if ( child2 )
-	{
-		// do something useful
-	@endverbatim
-
-	Which is MUCH more concise and useful.
-
-	It is also safe to copy handles - internally they are nothing more than node pointers.
-	@verbatim
-	TiXmlHandle handleCopy = handle;
-	@endverbatim
-
-	What they should not be used for is iteration:
-
-	@verbatim
-	int i=0; 
-	while ( true )
-	{
-		TiXmlElement* child = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).Child( "Child", i ).ToElement();
-		if ( !child )
-			break;
-		// do something
-		++i;
-	}
-	@endverbatim
-
-	It seems reasonable, but it is in fact two embedded while loops. The Child method is 
-	a linear walk to find the element, so this code would iterate much more than it needs 
-	to. Instead, prefer:
-
-	@verbatim
-	TiXmlElement* child = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).FirstChild( "Child" ).ToElement();
-
-	for( child; child; child=child->NextSiblingElement() )
-	{
-		// do something
-	}
-	@endverbatim
-*/
-class TiXmlHandle
-{
-public:
-	/// Create a handle from any node (at any depth of the tree.) This can be a null pointer.
-	TiXmlHandle( TiXmlNode* _node )					{ this->node = _node; }
-	/// Copy constructor
-	TiXmlHandle( const TiXmlHandle& ref )			{ this->node = ref.node; }
-	TiXmlHandle operator=( const TiXmlHandle& ref ) { this->node = ref.node; return *this; }
-
-	/// Return a handle to the first child node.
-	TiXmlHandle FirstChild() const;
-	/// Return a handle to the first child node with the given name.
-	TiXmlHandle FirstChild( const char * value ) const;
-	/// Return a handle to the first child element.
-	TiXmlHandle FirstChildElement() const;
-	/// Return a handle to the first child element with the given name.
-	TiXmlHandle FirstChildElement( const char * value ) const;
-
-	/** Return a handle to the "index" child with the given name. 
-		The first child is 0, the second 1, etc.
-	*/
-	TiXmlHandle Child( const char* value, int index ) const;
-	/** Return a handle to the "index" child. 
-		The first child is 0, the second 1, etc.
-	*/
-	TiXmlHandle Child( int index ) const;
-	/** Return a handle to the "index" child element with the given name. 
-		The first child element is 0, the second 1, etc. Note that only TiXmlElements
-		are indexed: other types are not counted.
-	*/
-	TiXmlHandle ChildElement( const char* value, int index ) const;
-	/** Return a handle to the "index" child element. 
-		The first child element is 0, the second 1, etc. Note that only TiXmlElements
-		are indexed: other types are not counted.
-	*/
-	TiXmlHandle ChildElement( int index ) const;
-
-	#ifdef TIXML_USE_STL
-	TiXmlHandle FirstChild( const std::string& _value ) const				{ return FirstChild( _value.c_str() ); }
-	TiXmlHandle FirstChildElement( const std::string& _value ) const		{ return FirstChildElement( _value.c_str() ); }
-
-	TiXmlHandle Child( const std::string& _value, int index ) const			{ return Child( _value.c_str(), index ); }
-	TiXmlHandle ChildElement( const std::string& _value, int index ) const	{ return ChildElement( _value.c_str(), index ); }
-	#endif
-
-	/** Return the handle as a TiXmlNode. This may return null.
-	*/
-	TiXmlNode* ToNode() const			{ return node; } 
-	/** Return the handle as a TiXmlElement. This may return null.
-	*/
-	TiXmlElement* ToElement() const		{ return ( ( node && node->ToElement() ) ? node->ToElement() : 0 ); }
-	/**	Return the handle as a TiXmlText. This may return null.
-	*/
-	TiXmlText* ToText() const			{ return ( ( node && node->ToText() ) ? node->ToText() : 0 ); }
-	/** Return the handle as a TiXmlUnknown. This may return null.
-	*/
-	TiXmlUnknown* ToUnknown() const		{ return ( ( node && node->ToUnknown() ) ? node->ToUnknown() : 0 ); }
-
-	/** @deprecated use ToNode. 
-		Return the handle as a TiXmlNode. This may return null.
-	*/
-	TiXmlNode* Node() const			{ return ToNode(); } 
-	/** @deprecated use ToElement. 
-		Return the handle as a TiXmlElement. This may return null.
-	*/
-	TiXmlElement* Element() const	{ return ToElement(); }
-	/**	@deprecated use ToText()
-		Return the handle as a TiXmlText. This may return null.
-	*/
-	TiXmlText* Text() const			{ return ToText(); }
-	/** @deprecated use ToUnknown()
-		Return the handle as a TiXmlUnknown. This may return null.
-	*/
-	TiXmlUnknown* Unknown() const	{ return ToUnknown(); }
-
-private:
-	TiXmlNode* node;
-};
-
-
-/** Print to memory functionality. The TiXmlPrinter is useful when you need to:
-
-	-# Print to memory (especially in non-STL mode)
-	-# Control formatting (line endings, etc.)
-
-	When constructed, the TiXmlPrinter is in its default "pretty printing" mode.
-	Before calling Accept() you can call methods to control the printing
-	of the XML document. After TiXmlNode::Accept() is called, the printed document can
-	be accessed via the CStr(), Str(), and Size() methods.
-
-	TiXmlPrinter uses the Visitor API.
-	@verbatim
-	TiXmlPrinter printer;
-	printer.SetIndent( "\t" );
-
-	doc.Accept( &printer );
-	fprintf( stdout, "%s", printer.CStr() );
-	@endverbatim
-*/
-class TiXmlPrinter : public TiXmlVisitor
-{
-public:
-	TiXmlPrinter() : depth( 0 ), simpleTextPrint( false ),
-					 buffer(), indent( "    " ), lineBreak( "\n" ) {}
-
-	virtual bool VisitEnter( const TiXmlDocument& doc );
-	virtual bool VisitExit( const TiXmlDocument& doc );
-
-	virtual bool VisitEnter( const TiXmlElement& element, const TiXmlAttribute* firstAttribute );
-	virtual bool VisitExit( const TiXmlElement& element );
-
-	virtual bool Visit( const TiXmlDeclaration& declaration );
-	virtual bool Visit( const TiXmlText& text );
-	virtual bool Visit( const TiXmlComment& comment );
-	virtual bool Visit( const TiXmlUnknown& unknown );
-
-	/** Set the indent characters for printing. By default 4 spaces
-		but tab (\t) is also useful, or null/empty string for no indentation.
-	*/
-	void SetIndent( const char* _indent )			{ indent = _indent ? _indent : "" ; }
-	/// Query the indention string.
-	const char* Indent()							{ return indent.c_str(); }
-	/** Set the line breaking string. By default set to newline (\n). 
-		Some operating systems prefer other characters, or can be
-		set to the null/empty string for no indenation.
-	*/
-	void SetLineBreak( const char* _lineBreak )		{ lineBreak = _lineBreak ? _lineBreak : ""; }
-	/// Query the current line breaking string.
-	const char* LineBreak()							{ return lineBreak.c_str(); }
-
-	/** Switch over to "stream printing" which is the most dense formatting without 
-		linebreaks. Common when the XML is needed for network transmission.
-	*/
-	void SetStreamPrinting()						{ indent = "";
-													  lineBreak = "";
-													}	
-	/// Return the result.
-	const char* CStr()								{ return buffer.c_str(); }
-	/// Return the length of the result string.
-	size_t Size()									{ return buffer.size(); }
-
-	#ifdef TIXML_USE_STL
-	/// Return the result.
-	const std::string& Str()						{ return buffer; }
-	#endif
-
-private:
-	void DoIndent()	{
-		for( int i=0; i<depth; ++i )
-			buffer += indent;
-	}
-	void DoLineBreak() {
-		buffer += lineBreak;
-	}
-
-	int depth;
-	bool simpleTextPrint;
-	TIXML_STRING buffer;
-	TIXML_STRING indent;
-	TIXML_STRING lineBreak;
-};
-
-
-#ifdef _MSC_VER
-#pragma warning( pop )
-#endif
-
-#endif
-

+ 0 - 52
src/tool/tool_xodrobj/TinyXML/tinyxmlerror.cpp

@@ -1,52 +0,0 @@
-/*
-www.sourceforge.net/projects/tinyxml
-Original code (2.0 and earlier )copyright (c) 2000-2006 Lee Thomason (www.grinninglizard.com)
-
-This software is provided 'as-is', without any express or implied 
-warranty. In no event will the authors be held liable for any 
-damages arising from the use of this software.
-
-Permission is granted to anyone to use this software for any 
-purpose, including commercial applications, and to alter it and 
-redistribute it freely, subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must
-not claim that you wrote the original software. If you use this
-software in a product, an acknowledgment in the product documentation
-would be appreciated but is not required.
-
-2. Altered source versions must be plainly marked as such, and
-must not be misrepresented as being the original software.
-
-3. This notice may not be removed or altered from any source
-distribution.
-*/
-
-#include "tinyxml.h"
-
-// The goal of the seperate error file is to make the first
-// step towards localization. tinyxml (currently) only supports
-// english error messages, but the could now be translated.
-//
-// It also cleans up the code a bit.
-//
-
-const char* TiXmlBase::errorString[ TIXML_ERROR_STRING_COUNT ] =
-{
-	"No error",
-	"Error",
-	"Failed to open file",
-	"Error parsing Element.",
-	"Failed to read Element name",
-	"Error reading Element value.",
-	"Error reading Attributes.",
-	"Error: empty tag.",
-	"Error reading end tag.",
-	"Error parsing Unknown.",
-	"Error parsing Comment.",
-	"Error parsing Declaration.",
-	"Error document empty.",
-	"Error null (0) or unexpected EOF found in input stream.",
-	"Error parsing CDATA.",
-	"Error when TiXmlDocument added to document, because TiXmlDocument can only be at the root.",
-};

+ 0 - 1635
src/tool/tool_xodrobj/TinyXML/tinyxmlparser.cpp

@@ -1,1635 +0,0 @@
-/*
-www.sourceforge.net/projects/tinyxml
-Original code (2.0 and earlier )copyright (c) 2000-2002 Lee Thomason (www.grinninglizard.com)
-
-This software is provided 'as-is', without any express or implied 
-warranty. In no event will the authors be held liable for any 
-damages arising from the use of this software.
-
-Permission is granted to anyone to use this software for any 
-purpose, including commercial applications, and to alter it and 
-redistribute it freely, subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must 
-not claim that you wrote the original software. If you use this
-software in a product, an acknowledgment in the product documentation
-would be appreciated but is not required.
-
-2. Altered source versions must be plainly marked as such, and 
-must not be misrepresented as being the original software.
-
-3. This notice may not be removed or altered from any source 
-distribution.
-*/
-
-#include <ctype.h>
-#include <stddef.h>
-
-#include "tinyxml.h"
-
-//#define DEBUG_PARSER
-#if defined( DEBUG_PARSER )
-#	if defined( DEBUG ) && defined( _MSC_VER )
-#		include <windows.h>
-#		define TIXML_LOG OutputDebugString
-#	else
-#		define TIXML_LOG printf
-#	endif
-#endif
-
-// Note tha "PutString" hardcodes the same list. This
-// is less flexible than it appears. Changing the entries
-// or order will break putstring.	
-TiXmlBase::Entity TiXmlBase::entity[ NUM_ENTITY ] = 
-{
-	{ "&amp;",  5, '&' },
-	{ "&lt;",   4, '<' },
-	{ "&gt;",   4, '>' },
-	{ "&quot;", 6, '\"' },
-	{ "&apos;", 6, '\'' }
-};
-
-// Bunch of unicode info at:
-//		http://www.unicode.org/faq/utf_bom.html
-// Including the basic of this table, which determines the #bytes in the
-// sequence from the lead byte. 1 placed for invalid sequences --
-// although the result will be junk, pass it through as much as possible.
-// Beware of the non-characters in UTF-8:	
-//				ef bb bf (Microsoft "lead bytes")
-//				ef bf be
-//				ef bf bf 
-
-const unsigned char TIXML_UTF_LEAD_0 = 0xefU;
-const unsigned char TIXML_UTF_LEAD_1 = 0xbbU;
-const unsigned char TIXML_UTF_LEAD_2 = 0xbfU;
-
-const int TiXmlBase::utf8ByteTable[256] = 
-{
-	//	0	1	2	3	4	5	6	7	8	9	a	b	c	d	e	f
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x00
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x10
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x20
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x30
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x40
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x50
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x60
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x70	End of ASCII range
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x80 0x80 to 0xc1 invalid
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0x90 
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0xa0 
-		1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	// 0xb0 
-		1,	1,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	// 0xc0 0xc2 to 0xdf 2 byte
-		2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	2,	// 0xd0
-		3,	3,	3,	3,	3,	3,	3,	3,	3,	3,	3,	3,	3,	3,	3,	3,	// 0xe0 0xe0 to 0xef 3 byte
-		4,	4,	4,	4,	4,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1,	1	// 0xf0 0xf0 to 0xf4 4 byte, 0xf5 and higher invalid
-};
-
-
-void TiXmlBase::ConvertUTF32ToUTF8( unsigned long input, char* output, int* length )
-{
-	const unsigned long BYTE_MASK = 0xBF;
-	const unsigned long BYTE_MARK = 0x80;
-	const unsigned long FIRST_BYTE_MARK[7] = { 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC };
-
-	if (input < 0x80) 
-		*length = 1;
-	else if ( input < 0x800 )
-		*length = 2;
-	else if ( input < 0x10000 )
-		*length = 3;
-	else if ( input < 0x200000 )
-		*length = 4;
-	else
-		{ *length = 0; return; }	// This code won't covert this correctly anyway.
-
-	output += *length;
-
-	// Scary scary fall throughs.
-	switch (*length) 
-	{
-		case 4:
-			--output; 
-			*output = (char)((input | BYTE_MARK) & BYTE_MASK); 
-			input >>= 6;
-		case 3:
-			--output; 
-			*output = (char)((input | BYTE_MARK) & BYTE_MASK); 
-			input >>= 6;
-		case 2:
-			--output; 
-			*output = (char)((input | BYTE_MARK) & BYTE_MASK); 
-			input >>= 6;
-		case 1:
-			--output; 
-			*output = (char)(input | FIRST_BYTE_MARK[*length]);
-	}
-}
-
-
-/*static*/ int TiXmlBase::IsAlpha( unsigned char anyByte, TiXmlEncoding /*encoding*/ )
-{
-	// This will only work for low-ascii, everything else is assumed to be a valid
-	// letter. I'm not sure this is the best approach, but it is quite tricky trying
-	// to figure out alhabetical vs. not across encoding. So take a very 
-	// conservative approach.
-
-//	if ( encoding == TIXML_ENCODING_UTF8 )
-//	{
-		if ( anyByte < 127 )
-			return isalpha( anyByte );
-		else
-			return 1;	// What else to do? The unicode set is huge...get the english ones right.
-//	}
-//	else
-//	{
-//		return isalpha( anyByte );
-//	}
-}
-
-
-/*static*/ int TiXmlBase::IsAlphaNum( unsigned char anyByte, TiXmlEncoding /*encoding*/ )
-{
-	// This will only work for low-ascii, everything else is assumed to be a valid
-	// letter. I'm not sure this is the best approach, but it is quite tricky trying
-	// to figure out alhabetical vs. not across encoding. So take a very 
-	// conservative approach.
-
-//	if ( encoding == TIXML_ENCODING_UTF8 )
-//	{
-		if ( anyByte < 127 )
-			return isalnum( anyByte );
-		else
-			return 1;	// What else to do? The unicode set is huge...get the english ones right.
-//	}
-//	else
-//	{
-//		return isalnum( anyByte );
-//	}
-}
-
-
-class TiXmlParsingData
-{
-	friend class TiXmlDocument;
-  public:
-	void Stamp( const char* now, TiXmlEncoding encoding );
-
-	const TiXmlCursor& Cursor()	{ return cursor; }
-
-  private:
-	// Only used by the document!
-	TiXmlParsingData( const char* start, int _tabsize, int row, int col )
-	{
-		assert( start );
-		stamp = start;
-		tabsize = _tabsize;
-		cursor.row = row;
-		cursor.col = col;
-	}
-
-	TiXmlCursor		cursor;
-	const char*		stamp;
-	int				tabsize;
-};
-
-
-void TiXmlParsingData::Stamp( const char* now, TiXmlEncoding encoding )
-{
-	assert( now );
-
-	// Do nothing if the tabsize is 0.
-	if ( tabsize < 1 )
-	{
-		return;
-	}
-
-	// Get the current row, column.
-	int row = cursor.row;
-	int col = cursor.col;
-	const char* p = stamp;
-	assert( p );
-
-	while ( p < now )
-	{
-		// Treat p as unsigned, so we have a happy compiler.
-		const unsigned char* pU = (const unsigned char*)p;
-
-		// Code contributed by Fletcher Dunn: (modified by lee)
-		switch (*pU) {
-			case 0:
-				// We *should* never get here, but in case we do, don't
-				// advance past the terminating null character, ever
-				return;
-
-			case '\r':
-				// bump down to the next line
-				++row;
-				col = 0;				
-				// Eat the character
-				++p;
-
-				// Check for \r\n sequence, and treat this as a single character
-				if (*p == '\n') {
-					++p;
-				}
-				break;
-
-			case '\n':
-				// bump down to the next line
-				++row;
-				col = 0;
-
-				// Eat the character
-				++p;
-
-				// Check for \n\r sequence, and treat this as a single
-				// character.  (Yes, this bizarre thing does occur still
-				// on some arcane platforms...)
-				if (*p == '\r') {
-					++p;
-				}
-				break;
-
-			case '\t':
-				// Eat the character
-				++p;
-
-				// Skip to next tab stop
-				col = (col / tabsize + 1) * tabsize;
-				break;
-
-			case TIXML_UTF_LEAD_0:
-				if ( encoding == TIXML_ENCODING_UTF8 )
-				{
-					if ( *(p+1) && *(p+2) )
-					{
-						// In these cases, don't advance the column. These are
-						// 0-width spaces.
-						if ( *(pU+1)==TIXML_UTF_LEAD_1 && *(pU+2)==TIXML_UTF_LEAD_2 )
-							p += 3;	
-						else if ( *(pU+1)==0xbfU && *(pU+2)==0xbeU )
-							p += 3;	
-						else if ( *(pU+1)==0xbfU && *(pU+2)==0xbfU )
-							p += 3;	
-						else
-							{ p +=3; ++col; }	// A normal character.
-					}
-				}
-				else
-				{
-					++p;
-					++col;
-				}
-				break;
-
-			default:
-				if ( encoding == TIXML_ENCODING_UTF8 )
-				{
-					// Eat the 1 to 4 byte utf8 character.
-					int step = TiXmlBase::utf8ByteTable[*((const unsigned char*)p)];
-					if ( step == 0 )
-						step = 1;		// Error case from bad encoding, but handle gracefully.
-					p += step;
-
-					// Just advance one column, of course.
-					++col;
-				}
-				else
-				{
-					++p;
-					++col;
-				}
-				break;
-		}
-	}
-	cursor.row = row;
-	cursor.col = col;
-	assert( cursor.row >= -1 );
-	assert( cursor.col >= -1 );
-	stamp = p;
-	assert( stamp );
-}
-
-
-const char* TiXmlBase::SkipWhiteSpace( const char* p, TiXmlEncoding encoding )
-{
-	if ( !p || !*p )
-	{
-		return 0;
-	}
-	if ( encoding == TIXML_ENCODING_UTF8 )
-	{
-		while ( *p )
-		{
-			const unsigned char* pU = (const unsigned char*)p;
-			
-			// Skip the stupid Microsoft UTF-8 Byte order marks
-			if (	*(pU+0)==TIXML_UTF_LEAD_0
-				 && *(pU+1)==TIXML_UTF_LEAD_1 
-				 && *(pU+2)==TIXML_UTF_LEAD_2 )
-			{
-				p += 3;
-				continue;
-			}
-			else if(*(pU+0)==TIXML_UTF_LEAD_0
-				 && *(pU+1)==0xbfU
-				 && *(pU+2)==0xbeU )
-			{
-				p += 3;
-				continue;
-			}
-			else if(*(pU+0)==TIXML_UTF_LEAD_0
-				 && *(pU+1)==0xbfU
-				 && *(pU+2)==0xbfU )
-			{
-				p += 3;
-				continue;
-			}
-
-			if ( IsWhiteSpace( *p ) )		// Still using old rules for white space.
-				++p;
-			else
-				break;
-		}
-	}
-	else
-	{
-		while ( *p && IsWhiteSpace( *p ) )
-			++p;
-	}
-
-	return p;
-}
-
-#ifdef TIXML_USE_STL
-/*static*/ bool TiXmlBase::StreamWhiteSpace( std::istream * in, TIXML_STRING * tag )
-{
-	for( ;; )
-	{
-		if ( !in->good() ) return false;
-
-		int c = in->peek();
-		// At this scope, we can't get to a document. So fail silently.
-		if ( !IsWhiteSpace( c ) || c <= 0 )
-			return true;
-
-		*tag += (char) in->get();
-	}
-}
-
-/*static*/ bool TiXmlBase::StreamTo( std::istream * in, int character, TIXML_STRING * tag )
-{
-	//assert( character > 0 && character < 128 );	// else it won't work in utf-8
-	while ( in->good() )
-	{
-		int c = in->peek();
-		if ( c == character )
-			return true;
-		if ( c <= 0 )		// Silent failure: can't get document at this scope
-			return false;
-
-		in->get();
-		*tag += (char) c;
-	}
-	return false;
-}
-#endif
-
-// One of TinyXML's more performance demanding functions. Try to keep the memory overhead down. The
-// "assign" optimization removes over 10% of the execution time.
-//
-const char* TiXmlBase::ReadName( const char* p, TIXML_STRING * name, TiXmlEncoding encoding )
-{
-	// Oddly, not supported on some comilers,
-	//name->clear();
-	// So use this:
-	*name = "";
-	assert( p );
-
-	// Names start with letters or underscores.
-	// Of course, in unicode, tinyxml has no idea what a letter *is*. The
-	// algorithm is generous.
-	//
-	// After that, they can be letters, underscores, numbers,
-	// hyphens, or colons. (Colons are valid ony for namespaces,
-	// but tinyxml can't tell namespaces from names.)
-	if (    p && *p 
-		 && ( IsAlpha( (unsigned char) *p, encoding ) || *p == '_' ) )
-	{
-		const char* start = p;
-		while(		p && *p
-				&&	(		IsAlphaNum( (unsigned char ) *p, encoding ) 
-						 || *p == '_'
-						 || *p == '-'
-						 || *p == '.'
-						 || *p == ':' ) )
-		{
-			//(*name) += *p; // expensive
-			++p;
-		}
-		if ( p-start > 0 ) {
-			name->assign( start, p-start );
-		}
-		return p;
-	}
-	return 0;
-}
-
-const char* TiXmlBase::GetEntity( const char* p, char* value, int* length, TiXmlEncoding encoding )
-{
-	// Presume an entity, and pull it out.
-    TIXML_STRING ent;
-	int i;
-	*length = 0;
-
-	if ( *(p+1) && *(p+1) == '#' && *(p+2) )
-	{
-		unsigned long ucs = 0;
-		ptrdiff_t delta = 0;
-		unsigned mult = 1;
-
-		if ( *(p+2) == 'x' )
-		{
-			// Hexadecimal.
-			if ( !*(p+3) ) return 0;
-
-			const char* q = p+3;
-			q = strchr( q, ';' );
-
-			if ( !q || !*q ) return 0;
-
-			delta = q-p;
-			--q;
-
-			while ( *q != 'x' )
-			{
-				if ( *q >= '0' && *q <= '9' )
-					ucs += mult * (*q - '0');
-				else if ( *q >= 'a' && *q <= 'f' )
-					ucs += mult * (*q - 'a' + 10);
-				else if ( *q >= 'A' && *q <= 'F' )
-					ucs += mult * (*q - 'A' + 10 );
-				else 
-					return 0;
-				mult *= 16;
-				--q;
-			}
-		}
-		else
-		{
-			// Decimal.
-			if ( !*(p+2) ) return 0;
-
-			const char* q = p+2;
-			q = strchr( q, ';' );
-
-			if ( !q || !*q ) return 0;
-
-			delta = q-p;
-			--q;
-
-			while ( *q != '#' )
-			{
-				if ( *q >= '0' && *q <= '9' )
-					ucs += mult * (*q - '0');
-				else 
-					return 0;
-				mult *= 10;
-				--q;
-			}
-		}
-		if ( encoding == TIXML_ENCODING_UTF8 )
-		{
-			// convert the UCS to UTF-8
-			ConvertUTF32ToUTF8( ucs, value, length );
-		}
-		else
-		{
-			*value = (char)ucs;
-			*length = 1;
-		}
-		return p + delta + 1;
-	}
-
-	// Now try to match it.
-	for( i=0; i<NUM_ENTITY; ++i )
-	{
-		if ( strncmp( entity[i].str, p, entity[i].strLength ) == 0 )
-		{
-			assert( strlen( entity[i].str ) == entity[i].strLength );
-			*value = entity[i].chr;
-			*length = 1;
-			return ( p + entity[i].strLength );
-		}
-	}
-
-	// So it wasn't an entity, its unrecognized, or something like that.
-	*value = *p;	// Don't put back the last one, since we return it!
-	//*length = 1;	// Leave unrecognized entities - this doesn't really work.
-					// Just writes strange XML.
-	return p+1;
-}
-
-
-bool TiXmlBase::StringEqual( const char* p,
-							 const char* tag,
-							 bool ignoreCase,
-							 TiXmlEncoding encoding )
-{
-	assert( p );
-	assert( tag );
-	if ( !p || !*p )
-	{
-		assert( 0 );
-		return false;
-	}
-
-	const char* q = p;
-
-	if ( ignoreCase )
-	{
-		while ( *q && *tag && ToLower( *q, encoding ) == ToLower( *tag, encoding ) )
-		{
-			++q;
-			++tag;
-		}
-
-		if ( *tag == 0 )
-			return true;
-	}
-	else
-	{
-		while ( *q && *tag && *q == *tag )
-		{
-			++q;
-			++tag;
-		}
-
-		if ( *tag == 0 )		// Have we found the end of the tag, and everything equal?
-			return true;
-	}
-	return false;
-}
-
-const char* TiXmlBase::ReadText(	const char* p, 
-									TIXML_STRING * text, 
-									bool trimWhiteSpace, 
-									const char* endTag, 
-									bool caseInsensitive,
-									TiXmlEncoding encoding )
-{
-    *text = "";
-	if (    !trimWhiteSpace			// certain tags always keep whitespace
-		 || !condenseWhiteSpace )	// if true, whitespace is always kept
-	{
-		// Keep all the white space.
-		while (	   p && *p
-				&& !StringEqual( p, endTag, caseInsensitive, encoding )
-			  )
-		{
-			int len;
-			char cArr[4] = { 0, 0, 0, 0 };
-			p = GetChar( p, cArr, &len, encoding );
-			text->append( cArr, len );
-		}
-	}
-	else
-	{
-		bool whitespace = false;
-
-		// Remove leading white space:
-		p = SkipWhiteSpace( p, encoding );
-		while (	   p && *p
-				&& !StringEqual( p, endTag, caseInsensitive, encoding ) )
-		{
-			if ( *p == '\r' || *p == '\n' )
-			{
-				whitespace = true;
-				++p;
-			}
-			else if ( IsWhiteSpace( *p ) )
-			{
-				whitespace = true;
-				++p;
-			}
-			else
-			{
-				// If we've found whitespace, add it before the
-				// new character. Any whitespace just becomes a space.
-				if ( whitespace )
-				{
-					(*text) += ' ';
-					whitespace = false;
-				}
-				int len;
-				char cArr[4] = { 0, 0, 0, 0 };
-				p = GetChar( p, cArr, &len, encoding );
-				if ( len == 1 )
-					(*text) += cArr[0];	// more efficient
-				else
-					text->append( cArr, len );
-			}
-		}
-	}
-	if ( p && *p ) 
-		p += strlen( endTag );
-	return p;
-}
-
-#ifdef TIXML_USE_STL
-
-void TiXmlDocument::StreamIn( std::istream * in, TIXML_STRING * tag )
-{
-	// The basic issue with a document is that we don't know what we're
-	// streaming. Read something presumed to be a tag (and hope), then
-	// identify it, and call the appropriate stream method on the tag.
-	//
-	// This "pre-streaming" will never read the closing ">" so the
-	// sub-tag can orient itself.
-
-	if ( !StreamTo( in, '<', tag ) ) 
-	{
-		SetError( TIXML_ERROR_PARSING_EMPTY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return;
-	}
-
-	while ( in->good() )
-	{
-		int tagIndex = (int) tag->length();
-		while ( in->good() && in->peek() != '>' )
-		{
-			int c = in->get();
-			if ( c <= 0 )
-			{
-				SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN );
-				break;
-			}
-			(*tag) += (char) c;
-		}
-
-		if ( in->good() )
-		{
-			// We now have something we presume to be a node of 
-			// some sort. Identify it, and call the node to
-			// continue streaming.
-			TiXmlNode* node = Identify( tag->c_str() + tagIndex, TIXML_DEFAULT_ENCODING );
-
-			if ( node )
-			{
-				node->StreamIn( in, tag );
-				bool isElement = node->ToElement() != 0;
-				delete node;
-				node = 0;
-
-				// If this is the root element, we're done. Parsing will be
-				// done by the >> operator.
-				if ( isElement )
-				{
-					return;
-				}
-			}
-			else
-			{
-				SetError( TIXML_ERROR, 0, 0, TIXML_ENCODING_UNKNOWN );
-				return;
-			}
-		}
-	}
-	// We should have returned sooner.
-	SetError( TIXML_ERROR, 0, 0, TIXML_ENCODING_UNKNOWN );
-}
-
-#endif
-
-const char* TiXmlDocument::Parse( const char* p, TiXmlParsingData* prevData, TiXmlEncoding encoding )
-{
-	ClearError();
-
-	// Parse away, at the document level. Since a document
-	// contains nothing but other tags, most of what happens
-	// here is skipping white space.
-	if ( !p || !*p )
-	{
-		SetError( TIXML_ERROR_DOCUMENT_EMPTY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return 0;
-	}
-
-	// Note that, for a document, this needs to come
-	// before the while space skip, so that parsing
-	// starts from the pointer we are given.
-	location.Clear();
-	if ( prevData )
-	{
-		location.row = prevData->cursor.row;
-		location.col = prevData->cursor.col;
-	}
-	else
-	{
-		location.row = 0;
-		location.col = 0;
-	}
-	TiXmlParsingData data( p, TabSize(), location.row, location.col );
-	location = data.Cursor();
-
-	if ( encoding == TIXML_ENCODING_UNKNOWN )
-	{
-		// Check for the Microsoft UTF-8 lead bytes.
-		const unsigned char* pU = (const unsigned char*)p;
-		if (	*(pU+0) && *(pU+0) == TIXML_UTF_LEAD_0
-			 && *(pU+1) && *(pU+1) == TIXML_UTF_LEAD_1
-			 && *(pU+2) && *(pU+2) == TIXML_UTF_LEAD_2 )
-		{
-			encoding = TIXML_ENCODING_UTF8;
-			useMicrosoftBOM = true;
-		}
-	}
-
-    p = SkipWhiteSpace( p, encoding );
-	if ( !p )
-	{
-		SetError( TIXML_ERROR_DOCUMENT_EMPTY, 0, 0, TIXML_ENCODING_UNKNOWN );
-		return 0;
-	}
-
-	while ( p && *p )
-	{
-		TiXmlNode* node = Identify( p, encoding );
-		if ( node )
-		{
-			p = node->Parse( p, &data, encoding );
-			LinkEndChild( node );
-		}
-		else
-		{
-			break;
-		}
-
-		// Did we get encoding info?
-		if (    encoding == TIXML_ENCODING_UNKNOWN
-			 && node->ToDeclaration() )
-		{
-			TiXmlDeclaration* dec = node->ToDeclaration();
-			const char* enc = dec->Encoding();
-			assert( enc );
-
-			if ( *enc == 0 )
-				encoding = TIXML_ENCODING_UTF8;
-			else if ( StringEqual( enc, "UTF-8", true, TIXML_ENCODING_UNKNOWN ) )
-				encoding = TIXML_ENCODING_UTF8;
-			else if ( StringEqual( enc, "UTF8", true, TIXML_ENCODING_UNKNOWN ) )
-				encoding = TIXML_ENCODING_UTF8;	// incorrect, but be nice
-			else 
-				encoding = TIXML_ENCODING_LEGACY;
-		}
-
-		p = SkipWhiteSpace( p, encoding );
-	}
-
-	// Was this empty?
-	if ( !firstChild ) {
-		SetError( TIXML_ERROR_DOCUMENT_EMPTY, 0, 0, encoding );
-		return 0;
-	}
-
-	// All is well.
-	return p;
-}
-
-void TiXmlDocument::SetError( int err, const char* pError, TiXmlParsingData* data, TiXmlEncoding encoding )
-{	
-	// The first error in a chain is more accurate - don't set again!
-	if ( error )
-		return;
-
-	assert( err > 0 && err < TIXML_ERROR_STRING_COUNT );
-	error   = true;
-	errorId = err;
-	errorDesc = errorString[ errorId ];
-
-	errorLocation.Clear();
-	if ( pError && data )
-	{
-		data->Stamp( pError, encoding );
-		errorLocation = data->Cursor();
-	}
-}
-
-
-TiXmlNode* TiXmlNode::Identify( const char* p, TiXmlEncoding encoding )
-{
-	TiXmlNode* returnNode = 0;
-
-	p = SkipWhiteSpace( p, encoding );
-	if( !p || !*p || *p != '<' )
-	{
-		return 0;
-	}
-
-	p = SkipWhiteSpace( p, encoding );
-
-	if ( !p || !*p )
-	{
-		return 0;
-	}
-
-	// What is this thing? 
-	// - Elements start with a letter or underscore, but xml is reserved.
-	// - Comments: <!--
-	// - Decleration: <?xml
-	// - Everthing else is unknown to tinyxml.
-	//
-
-	const char* xmlHeader = { "<?xml" };
-	const char* commentHeader = { "<!--" };
-	const char* dtdHeader = { "<!" };
-	const char* cdataHeader = { "<![CDATA[" };
-
-	if ( StringEqual( p, xmlHeader, true, encoding ) )
-	{
-		#ifdef DEBUG_PARSER
-			TIXML_LOG( "XML parsing Declaration\n" );
-		#endif
-		returnNode = new TiXmlDeclaration();
-	}
-	else if ( StringEqual( p, commentHeader, false, encoding ) )
-	{
-		#ifdef DEBUG_PARSER
-			TIXML_LOG( "XML parsing Comment\n" );
-		#endif
-		returnNode = new TiXmlComment();
-	}
-	else if ( StringEqual( p, cdataHeader, false, encoding ) )
-	{
-		#ifdef DEBUG_PARSER
-			TIXML_LOG( "XML parsing CDATA\n" );
-		#endif
-		TiXmlText* text = new TiXmlText( "" );
-		text->SetCDATA( true );
-		returnNode = text;
-	}
-	else if ( StringEqual( p, dtdHeader, false, encoding ) )
-	{
-		#ifdef DEBUG_PARSER
-			TIXML_LOG( "XML parsing Unknown(1)\n" );
-		#endif
-		returnNode = new TiXmlUnknown();
-	}
-	else if (    IsAlpha( *(p+1), encoding )
-			  || *(p+1) == '_' )
-	{
-		#ifdef DEBUG_PARSER
-			TIXML_LOG( "XML parsing Element\n" );
-		#endif
-		returnNode = new TiXmlElement( "" );
-	}
-	else
-	{
-		#ifdef DEBUG_PARSER
-			TIXML_LOG( "XML parsing Unknown(2)\n" );
-		#endif
-		returnNode = new TiXmlUnknown();
-	}
-
-	if ( returnNode )
-	{
-		// Set the parent, so it can report errors
-		returnNode->parent = this;
-	}
-	return returnNode;
-}
-
-#ifdef TIXML_USE_STL
-
-void TiXmlElement::StreamIn (std::istream * in, TIXML_STRING * tag)
-{
-	// We're called with some amount of pre-parsing. That is, some of "this"
-	// element is in "tag". Go ahead and stream to the closing ">"
-	while( in->good() )
-	{
-		int c = in->get();
-		if ( c <= 0 )
-		{
-			TiXmlDocument* document = GetDocument();
-			if ( document )
-				document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN );
-			return;
-		}
-		(*tag) += (char) c ;
-		
-		if ( c == '>' )
-			break;
-	}
-
-	if ( tag->length() < 3 ) return;
-
-	// Okay...if we are a "/>" tag, then we're done. We've read a complete tag.
-	// If not, identify and stream.
-
-	if (    tag->at( tag->length() - 1 ) == '>' 
-		 && tag->at( tag->length() - 2 ) == '/' )
-	{
-		// All good!
-		return;
-	}
-	else if ( tag->at( tag->length() - 1 ) == '>' )
-	{
-		// There is more. Could be:
-		//		text
-		//		cdata text (which looks like another node)
-		//		closing tag
-		//		another node.
-		for ( ;; )
-		{
-			StreamWhiteSpace( in, tag );
-
-			// Do we have text?
-			if ( in->good() && in->peek() != '<' ) 
-			{
-				// Yep, text.
-				TiXmlText text( "" );
-				text.StreamIn( in, tag );
-
-				// What follows text is a closing tag or another node.
-				// Go around again and figure it out.
-				continue;
-			}
-
-			// We now have either a closing tag...or another node.
-			// We should be at a "<", regardless.
-			if ( !in->good() ) return;
-			assert( in->peek() == '<' );
-			int tagIndex = (int) tag->length();
-
-			bool closingTag = false;
-			bool firstCharFound = false;
-
-			for( ;; )
-			{
-				if ( !in->good() )
-					return;
-
-				int c = in->peek();
-				if ( c <= 0 )
-				{
-					TiXmlDocument* document = GetDocument();
-					if ( document )
-						document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN );
-					return;
-				}
-				
-				if ( c == '>' )
-					break;
-
-				*tag += (char) c;
-				in->get();
-
-				// Early out if we find the CDATA id.
-				if ( c == '[' && tag->size() >= 9 )
-				{
-					size_t len = tag->size();
-					const char* start = tag->c_str() + len - 9;
-					if ( strcmp( start, "<![CDATA[" ) == 0 ) {
-						assert( !closingTag );
-						break;
-					}
-				}
-
-				if ( !firstCharFound && c != '<' && !IsWhiteSpace( c ) )
-				{
-					firstCharFound = true;
-					if ( c == '/' )
-						closingTag = true;
-				}
-			}
-			// If it was a closing tag, then read in the closing '>' to clean up the input stream.
-			// If it was not, the streaming will be done by the tag.
-			if ( closingTag )
-			{
-				if ( !in->good() )
-					return;
-
-				int c = in->get();
-				if ( c <= 0 )
-				{
-					TiXmlDocument* document = GetDocument();
-					if ( document )
-						document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN );
-					return;
-				}
-				assert( c == '>' );
-				*tag += (char) c;
-
-				// We are done, once we've found our closing tag.
-				return;
-			}
-			else
-			{
-				// If not a closing tag, id it, and stream.
-				const char* tagloc = tag->c_str() + tagIndex;
-				TiXmlNode* node = Identify( tagloc, TIXML_DEFAULT_ENCODING );
-				if ( !node )
-					return;
-				node->StreamIn( in, tag );
-				delete node;
-				node = 0;
-
-				// No return: go around from the beginning: text, closing tag, or node.
-			}
-		}
-	}
-}
-#endif
-
-const char* TiXmlElement::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding )
-{
-	p = SkipWhiteSpace( p, encoding );
-	TiXmlDocument* document = GetDocument();
-
-	if ( !p || !*p )
-	{
-		if ( document ) document->SetError( TIXML_ERROR_PARSING_ELEMENT, 0, 0, encoding );
-		return 0;
-	}
-
-	if ( data )
-	{
-		data->Stamp( p, encoding );
-		location = data->Cursor();
-	}
-
-	if ( *p != '<' )
-	{
-		if ( document ) document->SetError( TIXML_ERROR_PARSING_ELEMENT, p, data, encoding );
-		return 0;
-	}
-
-	p = SkipWhiteSpace( p+1, encoding );
-
-	// Read the name.
-	const char* pErr = p;
-
-    p = ReadName( p, &value, encoding );
-	if ( !p || !*p )
-	{
-		if ( document )	document->SetError( TIXML_ERROR_FAILED_TO_READ_ELEMENT_NAME, pErr, data, encoding );
-		return 0;
-	}
-
-    TIXML_STRING endTag ("</");
-	endTag += value;
-
-	// Check for and read attributes. Also look for an empty
-	// tag or an end tag.
-	while ( p && *p )
-	{
-		pErr = p;
-		p = SkipWhiteSpace( p, encoding );
-		if ( !p || !*p )
-		{
-			if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, pErr, data, encoding );
-			return 0;
-		}
-		if ( *p == '/' )
-		{
-			++p;
-			// Empty tag.
-			if ( *p  != '>' )
-			{
-				if ( document ) document->SetError( TIXML_ERROR_PARSING_EMPTY, p, data, encoding );		
-				return 0;
-			}
-			return (p+1);
-		}
-		else if ( *p == '>' )
-		{
-			// Done with attributes (if there were any.)
-			// Read the value -- which can include other
-			// elements -- read the end tag, and return.
-			++p;
-			p = ReadValue( p, data, encoding );		// Note this is an Element method, and will set the error if one happens.
-			if ( !p || !*p ) {
-				// We were looking for the end tag, but found nothing.
-				// Fix for [ 1663758 ] Failure to report error on bad XML
-				if ( document ) document->SetError( TIXML_ERROR_READING_END_TAG, p, data, encoding );
-				return 0;
-			}
-
-			// We should find the end tag now
-			// note that:
-			// </foo > and
-			// </foo> 
-			// are both valid end tags.
-			if ( StringEqual( p, endTag.c_str(), false, encoding ) )
-			{
-				p += endTag.length();
-				p = SkipWhiteSpace( p, encoding );
-				if ( p && *p && *p == '>' ) {
-					++p;
-					return p;
-				}
-				if ( document ) document->SetError( TIXML_ERROR_READING_END_TAG, p, data, encoding );
-				return 0;
-			}
-			else
-			{
-				if ( document ) document->SetError( TIXML_ERROR_READING_END_TAG, p, data, encoding );
-				return 0;
-			}
-		}
-		else
-		{
-			// Try to read an attribute:
-			TiXmlAttribute* attrib = new TiXmlAttribute();
-			if ( !attrib )
-			{
-				return 0;
-			}
-
-			attrib->SetDocument( document );
-			pErr = p;
-			p = attrib->Parse( p, data, encoding );
-
-			if ( !p || !*p )
-			{
-				if ( document ) document->SetError( TIXML_ERROR_PARSING_ELEMENT, pErr, data, encoding );
-				delete attrib;
-				return 0;
-			}
-
-			// Handle the strange case of double attributes:
-			#ifdef TIXML_USE_STL
-			TiXmlAttribute* node = attributeSet.Find( attrib->NameTStr() );
-			#else
-			TiXmlAttribute* node = attributeSet.Find( attrib->Name() );
-			#endif
-			if ( node )
-			{
-				if ( document ) document->SetError( TIXML_ERROR_PARSING_ELEMENT, pErr, data, encoding );
-				delete attrib;
-				return 0;
-			}
-
-			attributeSet.Add( attrib );
-		}
-	}
-	return p;
-}
-
-
-const char* TiXmlElement::ReadValue( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding )
-{
-	TiXmlDocument* document = GetDocument();
-
-	// Read in text and elements in any order.
-	const char* pWithWhiteSpace = p;
-	p = SkipWhiteSpace( p, encoding );
-
-	while ( p && *p )
-	{
-		if ( *p != '<' )
-		{
-			// Take what we have, make a text element.
-			TiXmlText* textNode = new TiXmlText( "" );
-
-			if ( !textNode )
-			{
-			    return 0;
-			}
-
-			if ( TiXmlBase::IsWhiteSpaceCondensed() )
-			{
-				p = textNode->Parse( p, data, encoding );
-			}
-			else
-			{
-				// Special case: we want to keep the white space
-				// so that leading spaces aren't removed.
-				p = textNode->Parse( pWithWhiteSpace, data, encoding );
-			}
-
-			if ( !textNode->Blank() )
-				LinkEndChild( textNode );
-			else
-				delete textNode;
-		} 
-		else 
-		{
-			// We hit a '<'
-			// Have we hit a new element or an end tag? This could also be
-			// a TiXmlText in the "CDATA" style.
-			if ( StringEqual( p, "</", false, encoding ) )
-			{
-				return p;
-			}
-			else
-			{
-				TiXmlNode* node = Identify( p, encoding );
-				if ( node )
-				{
-					p = node->Parse( p, data, encoding );
-					LinkEndChild( node );
-				}				
-				else
-				{
-					return 0;
-				}
-			}
-		}
-		pWithWhiteSpace = p;
-		p = SkipWhiteSpace( p, encoding );
-	}
-
-	if ( !p )
-	{
-		if ( document ) document->SetError( TIXML_ERROR_READING_ELEMENT_VALUE, 0, 0, encoding );
-	}	
-	return p;
-}
-
-
-#ifdef TIXML_USE_STL
-void TiXmlUnknown::StreamIn( std::istream * in, TIXML_STRING * tag )
-{
-	while ( in->good() )
-	{
-		int c = in->get();	
-		if ( c <= 0 )
-		{
-			TiXmlDocument* document = GetDocument();
-			if ( document )
-				document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN );
-			return;
-		}
-		(*tag) += (char) c;
-
-		if ( c == '>' )
-		{
-			// All is well.
-			return;		
-		}
-	}
-}
-#endif
-
-
-const char* TiXmlUnknown::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding )
-{
-	TiXmlDocument* document = GetDocument();
-	p = SkipWhiteSpace( p, encoding );
-
-	if ( data )
-	{
-		data->Stamp( p, encoding );
-		location = data->Cursor();
-	}
-	if ( !p || !*p || *p != '<' )
-	{
-		if ( document ) document->SetError( TIXML_ERROR_PARSING_UNKNOWN, p, data, encoding );
-		return 0;
-	}
-	++p;
-    value = "";
-
-	while ( p && *p && *p != '>' )
-	{
-		value += *p;
-		++p;
-	}
-
-	if ( !p )
-	{
-		if ( document )	document->SetError( TIXML_ERROR_PARSING_UNKNOWN, 0, 0, encoding );
-	}
-	if ( *p == '>' )
-		return p+1;
-	return p;
-}
-
-#ifdef TIXML_USE_STL
-void TiXmlComment::StreamIn( std::istream * in, TIXML_STRING * tag )
-{
-	while ( in->good() )
-	{
-		int c = in->get();	
-		if ( c <= 0 )
-		{
-			TiXmlDocument* document = GetDocument();
-			if ( document )
-				document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN );
-			return;
-		}
-
-		(*tag) += (char) c;
-
-		if ( c == '>' 
-			 && tag->at( tag->length() - 2 ) == '-'
-			 && tag->at( tag->length() - 3 ) == '-' )
-		{
-			// All is well.
-			return;		
-		}
-	}
-}
-#endif
-
-
-const char* TiXmlComment::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding )
-{
-	TiXmlDocument* document = GetDocument();
-	value = "";
-
-	p = SkipWhiteSpace( p, encoding );
-
-	if ( data )
-	{
-		data->Stamp( p, encoding );
-		location = data->Cursor();
-	}
-	const char* startTag = "<!--";
-	const char* endTag   = "-->";
-
-	if ( !StringEqual( p, startTag, false, encoding ) )
-	{
-		document->SetError( TIXML_ERROR_PARSING_COMMENT, p, data, encoding );
-		return 0;
-	}
-	p += strlen( startTag );
-
-	// [ 1475201 ] TinyXML parses entities in comments
-	// Oops - ReadText doesn't work, because we don't want to parse the entities.
-	// p = ReadText( p, &value, false, endTag, false, encoding );
-	//
-	// from the XML spec:
-	/*
-	 [Definition: Comments may appear anywhere in a document outside other markup; in addition, 
-	              they may appear within the document type declaration at places allowed by the grammar. 
-				  They are not part of the document's character data; an XML processor MAY, but need not, 
-				  make it possible for an application to retrieve the text of comments. For compatibility, 
-				  the string "--" (double-hyphen) MUST NOT occur within comments.] Parameter entity 
-				  references MUST NOT be recognized within comments.
-
-				  An example of a comment:
-
-				  <!-- declarations for <head> & <body> -->
-	*/
-
-    value = "";
-	// Keep all the white space.
-	while (	p && *p && !StringEqual( p, endTag, false, encoding ) )
-	{
-		value.append( p, 1 );
-		++p;
-	}
-	if ( p && *p ) 
-		p += strlen( endTag );
-
-	return p;
-}
-
-
-const char* TiXmlAttribute::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding )
-{
-	p = SkipWhiteSpace( p, encoding );
-	if ( !p || !*p ) return 0;
-
-	if ( data )
-	{
-		data->Stamp( p, encoding );
-		location = data->Cursor();
-	}
-	// Read the name, the '=' and the value.
-	const char* pErr = p;
-	p = ReadName( p, &name, encoding );
-	if ( !p || !*p )
-	{
-		if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, pErr, data, encoding );
-		return 0;
-	}
-	p = SkipWhiteSpace( p, encoding );
-	if ( !p || !*p || *p != '=' )
-	{
-		if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, p, data, encoding );
-		return 0;
-	}
-
-	++p;	// skip '='
-	p = SkipWhiteSpace( p, encoding );
-	if ( !p || !*p )
-	{
-		if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, p, data, encoding );
-		return 0;
-	}
-	
-	const char* end;
-	const char SINGLE_QUOTE = '\'';
-	const char DOUBLE_QUOTE = '\"';
-
-	if ( *p == SINGLE_QUOTE )
-	{
-		++p;
-		end = "\'";		// single quote in string
-		p = ReadText( p, &value, false, end, false, encoding );
-	}
-	else if ( *p == DOUBLE_QUOTE )
-	{
-		++p;
-		end = "\"";		// double quote in string
-		p = ReadText( p, &value, false, end, false, encoding );
-	}
-	else
-	{
-		// All attribute values should be in single or double quotes.
-		// But this is such a common error that the parser will try
-		// its best, even without them.
-		value = "";
-		while (    p && *p											// existence
-				&& !IsWhiteSpace( *p )								// whitespace
-				&& *p != '/' && *p != '>' )							// tag end
-		{
-			if ( *p == SINGLE_QUOTE || *p == DOUBLE_QUOTE ) {
-				// [ 1451649 ] Attribute values with trailing quotes not handled correctly
-				// We did not have an opening quote but seem to have a 
-				// closing one. Give up and throw an error.
-				if ( document ) document->SetError( TIXML_ERROR_READING_ATTRIBUTES, p, data, encoding );
-				return 0;
-			}
-			value += *p;
-			++p;
-		}
-	}
-	return p;
-}
-
-#ifdef TIXML_USE_STL
-void TiXmlText::StreamIn( std::istream * in, TIXML_STRING * tag )
-{
-	while ( in->good() )
-	{
-		int c = in->peek();	
-		if ( !cdata && (c == '<' ) ) 
-		{
-			return;
-		}
-		if ( c <= 0 )
-		{
-			TiXmlDocument* document = GetDocument();
-			if ( document )
-				document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN );
-			return;
-		}
-
-		(*tag) += (char) c;
-		in->get();	// "commits" the peek made above
-
-		if ( cdata && c == '>' && tag->size() >= 3 ) {
-			size_t len = tag->size();
-			if ( (*tag)[len-2] == ']' && (*tag)[len-3] == ']' ) {
-				// terminator of cdata.
-				return;
-			}
-		}    
-	}
-}
-#endif
-
-const char* TiXmlText::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding )
-{
-	value = "";
-	TiXmlDocument* document = GetDocument();
-
-	if ( data )
-	{
-		data->Stamp( p, encoding );
-		location = data->Cursor();
-	}
-
-	const char* const startTag = "<![CDATA[";
-	const char* const endTag   = "]]>";
-
-	if ( cdata || StringEqual( p, startTag, false, encoding ) )
-	{
-		cdata = true;
-
-		if ( !StringEqual( p, startTag, false, encoding ) )
-		{
-			document->SetError( TIXML_ERROR_PARSING_CDATA, p, data, encoding );
-			return 0;
-		}
-		p += strlen( startTag );
-
-		// Keep all the white space, ignore the encoding, etc.
-		while (	   p && *p
-				&& !StringEqual( p, endTag, false, encoding )
-			  )
-		{
-			value += *p;
-			++p;
-		}
-
-		TIXML_STRING dummy; 
-		p = ReadText( p, &dummy, false, endTag, false, encoding );
-		return p;
-	}
-	else
-	{
-		bool ignoreWhite = true;
-
-		const char* end = "<";
-		p = ReadText( p, &value, ignoreWhite, end, false, encoding );
-		if ( p )
-			return p-1;	// don't truncate the '<'
-		return 0;
-	}
-}
-
-#ifdef TIXML_USE_STL
-void TiXmlDeclaration::StreamIn( std::istream * in, TIXML_STRING * tag )
-{
-	while ( in->good() )
-	{
-		int c = in->get();
-		if ( c <= 0 )
-		{
-			TiXmlDocument* document = GetDocument();
-			if ( document )
-				document->SetError( TIXML_ERROR_EMBEDDED_NULL, 0, 0, TIXML_ENCODING_UNKNOWN );
-			return;
-		}
-		(*tag) += (char) c;
-
-		if ( c == '>' )
-		{
-			// All is well.
-			return;
-		}
-	}
-}
-#endif
-
-const char* TiXmlDeclaration::Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding _encoding )
-{
-	p = SkipWhiteSpace( p, _encoding );
-	// Find the beginning, find the end, and look for
-	// the stuff in-between.
-	TiXmlDocument* document = GetDocument();
-	if ( !p || !*p || !StringEqual( p, "<?xml", true, _encoding ) )
-	{
-		if ( document ) document->SetError( TIXML_ERROR_PARSING_DECLARATION, 0, 0, _encoding );
-		return 0;
-	}
-	if ( data )
-	{
-		data->Stamp( p, _encoding );
-		location = data->Cursor();
-	}
-	p += 5;
-
-	version = "";
-	encoding = "";
-	standalone = "";
-
-	while ( p && *p )
-	{
-		if ( *p == '>' )
-		{
-			++p;
-			return p;
-		}
-
-		p = SkipWhiteSpace( p, _encoding );
-		if ( StringEqual( p, "version", true, _encoding ) )
-		{
-			TiXmlAttribute attrib;
-			p = attrib.Parse( p, data, _encoding );		
-			version = attrib.Value();
-		}
-		else if ( StringEqual( p, "encoding", true, _encoding ) )
-		{
-			TiXmlAttribute attrib;
-			p = attrib.Parse( p, data, _encoding );		
-			encoding = attrib.Value();
-		}
-		else if ( StringEqual( p, "standalone", true, _encoding ) )
-		{
-			TiXmlAttribute attrib;
-			p = attrib.Parse( p, data, _encoding );		
-			standalone = attrib.Value();
-		}
-		else
-		{
-			// Read over whatever it is.
-			while( p && *p && *p != '>' && !IsWhiteSpace( *p ) )
-				++p;
-		}
-	}
-	return 0;
-}
-
-bool TiXmlText::Blank() const
-{
-	for ( unsigned i=0; i<value.length(); i++ )
-		if ( !IsWhiteSpace( value[i] ) )
-			return false;
-	return true;
-}
-

+ 91 - 7
src/tool/tool_xodrobj/mainwindow.cpp

@@ -69,12 +69,16 @@ static bool LoadXODR(std::string strpath,OpenDrive & mxodr)
     xp.ReadFile(strpath);
 }
 
-static int getmnfac(OpenDrive & mxodr)
+static int getmnfac(OpenDrive & mxodr,double & fmovex,double & fmovey)
 {
     int nrtn = 1;
 
     int i;
-    double xmax = 10;double ymax = 10;
+    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<mxodr.GetRoadCount();i++)
     {
         int j;
@@ -90,14 +94,32 @@ static int getmnfac(OpenDrive & mxodr)
             x = pg->GetX();
             y = pg->GetY();
 
-            if(fabs(x)>xmax)xmax = fabs(x);
-            if(fabs(y)>ymax)ymax = fabs(y);
+            if(x>fxmax)fxmax = x;
+            if(x<fxmin)fxmin = x;
+            if(y>fymax)fymax = y;
+            if(y<fymin)fymin = y;
 
         }
     }
 
-    int nfacx = (VIEW_WIDTH/2)/(xmax*1.2);
-    int nfacy = (VIEW_HEIGHT/2)/(ymax*1.2);
+    fmovex = 0;
+    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;
+    }
+
+    int nfacx = (VIEW_WIDTH/2)/(fxmax*1.2);
+    int nfacy = (VIEW_HEIGHT/2)/(fymax*1.2);
+    if(nfacx<1)nfacx = 1;
+    if(nfacy<1)nfacy = 1;
+
+
 
     if(nfacx < nfacy)nrtn = nfacx;
     else nrtn = nfacy;
@@ -124,7 +146,12 @@ MainWindow::MainWindow(QWidget *parent) :
     strmapth = strmapth + "/map/map.xodr";
 
     LoadXODR(strmapth,mxodr);
-    mnfac = getmnfac(mxodr);
+
+    double fmovex,fmovey;
+    mnfac = getmnfac(mxodr,fmovex,fmovey);
+
+    mfViewMoveX = mfViewMoveX - fmovex;
+    mfViewMoveY = mfViewMoveY - fmovey;
 
     mnMoveX = VIEW_WIDTH/2;
     mnMoveY = VIEW_HEIGHT/2;
@@ -261,6 +288,7 @@ void MainWindow::ExecPainter()
                 GeometryArc * parc;
                 GeometryParamPoly3 * ppp3;
                 GeometrySpiral *pSpiral;
+                GeometryPoly3 *ppoly;
                 double rel_x,rel_y,rel_hdg;
                 pg = pgeob->GetGeometryAt(0);
 
@@ -269,6 +297,8 @@ void MainWindow::ExecPainter()
 
                 switch (pg->GetGeomType()) {
                 case 0:
+                    x = x + mfViewMoveX;
+                    y = y + mfViewMoveY;
                     painter->drawLine(QPoint(x*mnfac,y*mnfac*(-1)),
                                       QPoint((x + pg->GetLength() * cos(pg->GetHdg()))*mnfac,(y + pg->GetLength() * sin(pg->GetHdg()))*mnfac*(-1)));
                     break;
@@ -291,6 +321,8 @@ void MainWindow::ExecPainter()
 
                            x = rel_x;
                            y = rel_y;
+                           x = x + mfViewMoveX;
+                           y = y + mfViewMoveY;
                            painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
 
                        }
@@ -337,10 +369,55 @@ void MainWindow::ExecPainter()
                             x_draw = x_center + R *cos(hdgnow  + M_PI/2.0);
                             y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
                         }
+                        x_draw = x_draw + mfViewMoveX;
+                        y_draw = y_draw + mfViewMoveY;
                         painter->drawPoint(x_draw * mnfac ,y_draw * mnfac *(-1));
                     }
                     }
                     break;
+                case 3:
+                    {
+                    painter->setPen(Qt::red);
+                    ppoly = (GeometryPoly3 *)pg;
+                    x = pg->GetX();
+                    y = pg->GetY();
+                    double A,B,C,D;
+                    A = ppoly->GetA();
+                    B = ppoly->GetB();
+                    C = ppoly->GetC();
+                    D = ppoly->GetD();
+                    const double steplim = 0.1;
+                    double du = steplim;
+                    double u = 0;
+                    double v = 0;
+                    double oldx,oldy;
+                    oldx = x;
+                    oldy = y;
+                    double xstart,ystart;
+                    xstart = x;
+                    ystart = y;
+                    double hdgstart = ppoly->GetHdg();
+                    double flen = 0;
+                    while(flen < ppoly->GetLength())
+                    {
+                        double fdis = 0;
+                        v = A + B*u + C*u*u + D*u*u*u;
+                        x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
+                        y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
+                        fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
+                        oldx = x;
+                        oldy = y;
+                        if(fdis>(steplim*2.0))du = du/2.0;
+                        flen = flen + fdis;
+                        u = u + du;
+                        std::cout<<" x: "<<x<<" y:"<<y<<std::endl;
+                        x = x + mfViewMoveX;
+                        y = y + mfViewMoveY;
+                        painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
+                    }
+                    painter->setPen(Qt::blue);
+                    }
+                    break;
                 case 4:
                     {
                     ppp3 = (GeometryParamPoly3 * )pg;
@@ -356,6 +433,8 @@ void MainWindow::ExecPainter()
                         ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
                         x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
                         y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
+                        x = x + mfViewMoveX;
+                        y = y + mfViewMoveY;
                         painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
                         s = s+ sstep;
                     }
@@ -454,6 +533,9 @@ void MainWindow::ExecPainter()
             GaussProjCal(m_navigation_data.at(i)->gps_lng,m_navigation_data.at(i)->gps_lat,&x,&y);
             x = x-x0;
             y= y-y0;
+
+            x = x + mfViewMoveX;
+            y = y + mfViewMoveY;
             painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
         }
         mMutexNavi.unlock();
@@ -1175,6 +1257,8 @@ void MainWindow::onClickXY(double x, double y)
     sely = mClickY * (-1);
     selx = selx/((double )mnfac);
     sely = sely/((double)mnfac);
+    selx = selx - mfViewMoveX;
+    sely = sely - mfViewMoveY;
     mpLE_SelX->setText(QString::number(selx,'f',3));
     mpLE_SelY->setText(QString::number(sely,'f',3));
 

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

@@ -182,6 +182,9 @@ private:
 
     void * mpasrc,*mpadst,*mpatrace;
 
+    double mfViewMoveX = 0;
+    double mfViewMoveY = 0;
+
 
 
     QMutex mMutexNavi;

+ 10 - 24
src/tool/tool_xodrobj/tool_xodrobj.pro

@@ -30,19 +30,6 @@ SOURCES += \
     xodr.cpp \
     myview.cpp \
     linedata.cpp \
-    OpenDrive/Junction.cpp \
-    OpenDrive/Lane.cpp \
-    OpenDrive/ObjectSignal.cpp \
-    OpenDrive/OpenDrive.cpp \
-    OpenDrive/OpenDriveXmlParser.cpp \
-    OpenDrive/OpenDriveXmlWriter.cpp \
-    OpenDrive/OtherStructures.cpp \
-    OpenDrive/Road.cpp \
-    OpenDrive/RoadGeometry.cpp \
-    TinyXML/tinystr.cpp \
-    TinyXML/tinyxml.cpp \
-    TinyXML/tinyxmlerror.cpp \
-    TinyXML/tinyxmlparser.cpp \
     fresnl.cpp \
     polevl.c \
     const.cpp \
@@ -58,17 +45,6 @@ HEADERS += \
     boost.h \
     gps_type.h \
     linedata.h \
-    OpenDrive/Junction.h \
-    OpenDrive/Lane.h \
-    OpenDrive/ObjectSignal.h \
-    OpenDrive/OpenDrive.h \
-    OpenDrive/OpenDriveXmlParser.h \
-    OpenDrive/OpenDriveXmlWriter.h \
-    OpenDrive/OtherStructures.h \
-    OpenDrive/Road.h \
-    OpenDrive/RoadGeometry.h \
-    TinyXML/tinystr.h \
-    TinyXML/tinyxml.h \
     gnss_coordinate_convert.h \
     ../../include/msgtype/gps.pb.h \
     ../../include/msgtype/gpsimu.pb.h \
@@ -89,6 +65,16 @@ FORMS += \
     error( "Couldn't find the ivboost.pri file!" )
 }
 
+!include(../../common/common/xodr/OpenDrive/OpenDrive.pri ) {
+    error( "Couldn't find the OpenDrive.pri file!" )
+}
+
+!include(../../common/common/xodr/TinyXML/TinyXML.pri ) {
+    error( "Couldn't find the TinyXML.pri file!" )
+}
+
+INCLUDEPATH += $$PWD/../map_lanetoxodr
+
 
 DISTFILES += \
     geodata.proto

+ 73 - 0
src/tool/view_ivchart/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 81 - 0
src/tool/view_ivchart/dialogselect.cpp

@@ -0,0 +1,81 @@
+#include "dialogselect.h"
+#include "ui_dialogselect.h"
+
+#include <QGroupBox>
+#include <QScrollArea>
+
+DialogSelect::DialogSelect(std::vector<std::string> xvectorlist, std::vector<std::string> &xvectorused,QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::DialogSelect)
+{
+    ui->setupUi(this);
+
+    mpvectorused = &xvectorused;
+
+    QGroupBox * pGroup = new QGroupBox();
+    pGroup->setGeometry(50,100,560,3000);
+
+    QScrollArea * pScroll = new QScrollArea(this);
+    pScroll->setWidget(pGroup);
+
+    pScroll->setGeometry(30,100,600,300);
+
+    int ntotalwidth = 560;
+    int ncheckwidth = 80;
+    int ncheckheight = 23;
+    int nhospace = 100;
+    int nvespace = 30;
+
+    unsigned int i;
+    int ipos = 0;
+    int jpos = 0;
+    for(i=0;i<xvectorlist.size();i++)
+    {
+        QCheckBox * pcheck = new QCheckBox(pGroup);
+        pcheck->setGeometry(30+ipos*nhospace,30+jpos*nvespace,ncheckwidth,ncheckheight);
+        pcheck->setText(xvectorlist[i].data());
+
+        mvectorcheck.push_back(pcheck);
+        unsigned int j;
+        bool bused = false;
+        for(j=0;j<xvectorused.size();j++)
+        {
+            if(xvectorused[j] == xvectorlist[i])
+            {
+                bused = true;
+                break;
+            }
+        }
+        pcheck->setChecked(bused);
+        ipos++;
+        if(ipos>=((ntotalwidth -30)/nhospace))
+        {
+            ipos = 0;
+            jpos++;
+        }
+    }
+
+    setWindowTitle("Select Chart Item");
+
+
+}
+
+DialogSelect::~DialogSelect()
+{
+    delete ui;
+}
+
+void DialogSelect::on_pushButton_Select_clicked()
+{
+    mpvectorused->clear();
+    unsigned int i;
+    for(i=0;i<mvectorcheck.size();i++)
+    {
+        if(mvectorcheck[i]->isChecked())
+        {
+            mpvectorused->push_back(mvectorcheck[i]->text().toStdString());
+        }
+    }
+
+    this->accept();
+}

+ 32 - 0
src/tool/view_ivchart/dialogselect.h

@@ -0,0 +1,32 @@
+#ifndef DIALOGSELECT_H
+#define DIALOGSELECT_H
+
+#include <QDialog>
+
+#include <string>
+#include <vector>
+#include <QCheckBox>
+
+namespace Ui {
+class DialogSelect;
+}
+
+class DialogSelect : public QDialog
+{
+    Q_OBJECT
+
+public:
+    explicit DialogSelect(std::vector<std::string> xvectorlist, std::vector<std::string> &xvectorused,QWidget *parent = nullptr);
+    ~DialogSelect();
+
+private slots:
+    void on_pushButton_Select_clicked();
+
+private:
+    Ui::DialogSelect *ui;
+
+    std::vector<QCheckBox *> mvectorcheck;
+    std::vector<std::string> * mpvectorused;
+};
+
+#endif // DIALOGSELECT_H

+ 32 - 0
src/tool/view_ivchart/dialogselect.ui

@@ -0,0 +1,32 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>DialogSelect</class>
+ <widget class="QDialog" name="DialogSelect">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>660</width>
+    <height>430</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <widget class="QPushButton" name="pushButton_Select">
+   <property name="geometry">
+    <rect>
+     <x>40</x>
+     <y>20</y>
+     <width>89</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Select</string>
+   </property>
+  </widget>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 132 - 0
src/tool/view_ivchart/ivchartproc.cpp

@@ -0,0 +1,132 @@
+#include "ivchartproc.h"
+
+#include "functional"
+
+ivchartproc::ivchartproc()
+{
+    bool bconnect = QDBusConnection::sessionBus().connect(QString(),"/catarc/adc",  "adciv.interface", "ivchart",this,SLOT(onChartMsg(QByteArray)));
+//    qDebug("connect is %d",bconnect);
+}
+
+void ivchartproc::run()
+{
+    const int nkeep = 300000;
+    while(mbrun&&(!QThread::isInterruptionRequested()))
+    {
+        std::vector<iv::ivchart::ivchartarray> xvectorivarray;
+        mMutexArray.lock();
+        xvectorivarray = mvectorarray;
+        mvectorarray.clear();
+        mMutexArray.unlock();
+
+        int i;
+        int nsize = xvectorivarray.size();
+        for(i=0;i<nsize;i++)
+        {
+            unsigned int k;
+            for(k=0;k<xvectorivarray[i].xivchartunit_size();k++)
+            {
+                bool bhave = false;
+                int j;
+                std::hash<std::string > h;
+                size_t hash_unit = h(xvectorivarray[i].xivchartunit(k).strvarname());
+                mMutex.lock();
+
+                int ncucount = mvectorCU.size();
+                for(j=0;j<ncucount;j++)
+                {
+                    if(hash_unit == mvectorCU[j].hash_name)
+                    {
+                        mvectorCU[j].mvectorchartunit.push_back(xvectorivarray[i].xivchartunit(k));
+                        bhave = true;
+                        break;
+                    }
+                }
+                if(bhave == false)
+                {
+                    ChartUnit xcu;
+                    xcu.strname = xvectorivarray[i].xivchartunit(k).strvarname();
+                    xcu.mvectorchartunit.push_back(xvectorivarray[i].xivchartunit(k));
+                    xcu.hash_name = hash_unit;
+                    mvectorCU.push_back(xcu);
+                }
+
+                mMutex.unlock();
+            }
+        }
+
+        qint64 nnow = QDateTime::currentMSecsSinceEpoch();
+
+        int ncusize = mvectorCU.size();
+
+        mMutex.lock();
+        for(i=0;i<ncusize;i++)
+        {
+            int j;
+            int nsizechart = mvectorCU[i].mvectorchartunit.size();
+            for(j=0;j<nsizechart;j++)
+            {
+                if(mvectorCU[i].mvectorchartunit[j].timex()>(nnow - nkeep))
+                {
+                    break;
+                }
+            }
+        }
+        mMutex.unlock();
+
+        if(xvectorivarray.size()  == 0)
+        {
+            msleep(1);
+        }
+
+    }
+}
+
+
+void ivchartproc::onChartMsg(QByteArray value)
+{
+
+    qDebug("chart msg size is %d",value.size());
+    iv::ivchart::ivchartarray xivarray;
+    if(xivarray.ParseFromArray(value.data(),value.size()))
+    {
+        mMutexArray.lock();
+        if(mvectorarray.size()<10000)
+            mvectorarray.push_back(xivarray);
+        mMutexArray.unlock();
+    }
+    else
+    {
+        qDebug("ivchartproc::onChartMsg parse error.");
+    }
+}
+
+std::vector<std::string> ivchartproc::GetChartNameList()
+{
+    std::vector<std::string> xvectorname;
+    mMutex.lock();
+    unsigned int i;
+    for(i=0;i<mvectorCU.size();i++)
+    {
+        xvectorname.push_back(mvectorCU[i].strname);
+    }
+    mMutex.unlock();
+    return xvectorname;
+}
+
+std::vector<iv::ivchart::ivchartunit> ivchartproc::GetChartUnit(std::string strname)
+{
+    std::vector<iv::ivchart::ivchartunit> xvectorcu;
+    mMutex.lock();
+    unsigned int i;
+    for(i=0;i<mvectorCU.size();i++)
+    {
+        if(strname == mvectorCU[i].strname)
+        {
+            xvectorcu= mvectorCU[i].mvectorchartunit;
+            break;
+        }
+    }
+    mMutex.unlock();
+    return xvectorcu;
+}

+ 43 - 0
src/tool/view_ivchart/ivchartproc.h

@@ -0,0 +1,43 @@
+#ifndef IVCHARTPROC_H
+#define IVCHARTPROC_H
+
+#include <QThread>
+
+#include <QMutex>
+
+#include <QDateTime>
+#include <QtDBus/qdbusmessage.h>
+#include <QtDBus/QDBusConnection>
+
+#include "ivchart.pb.h"
+
+class ChartUnit
+{
+public:
+    std::string strname;
+    size_t hash_name;
+    std::vector<iv::ivchart::ivchartunit> mvectorchartunit;
+};
+
+class ivchartproc : public QThread
+{
+    Q_OBJECT
+public:
+    ivchartproc();
+
+private slots:
+    void onChartMsg(QByteArray value);
+private:
+    void run();
+    std::vector<ChartUnit> mvectorCU;
+    QMutex mMutex;
+    std::vector<iv::ivchart::ivchartarray> mvectorarray;
+    QMutex mMutexArray;
+    bool mbrun = true;
+
+public:
+    std::vector<std::string > GetChartNameList();
+    std::vector<iv::ivchart::ivchartunit> GetChartUnit(std::string strname);
+};
+
+#endif // IVCHARTPROC_H

+ 11 - 0
src/tool/view_ivchart/main.cpp

@@ -0,0 +1,11 @@
+#include "mainwindow.h"
+
+#include <QApplication>
+
+int main(int argc, char *argv[])
+{
+    QApplication a(argc, argv);
+    MainWindow w;
+    w.show();
+    return a.exec();
+}

+ 168 - 0
src/tool/view_ivchart/mainwindow.cpp

@@ -0,0 +1,168 @@
+#include "mainwindow.h"
+#include "ui_mainwindow.h"
+#include <functional>
+#include <iostream>
+
+MainWindow::MainWindow(QWidget *parent)
+    : QMainWindow(parent)
+    , ui(new Ui::MainWindow)
+{
+    ui->setupUi(this);
+
+    std::hash<std::string> h;
+    size_t n = h("Just fucking google it");
+    std::cout << n << std::endl;
+
+    m_chart = new QChart();
+    m_chart->setTheme(QChart::ChartThemeLight);//设置白色主题
+    m_chart->setDropShadowEnabled(true);//背景阴影    m_chart->setAutoFillBackground(true);  //设置背景自动填充
+//    m_chart->addSeries(&mlineseries);//添加系列到QChart上
+
+
+    m_chart->setTitleBrush(QBrush(QColor(0,0,255)));//设置标题Brush
+    m_chart->setTitleFont(QFont("微软雅黑"));//设置标题字体
+    m_chart->setTitle("曲线图");
+
+
+
+
+
+
+    QChartView *chartView = new QChartView(m_chart,ui->centralwidget);
+    chartView->setRenderHint(QPainter::Antialiasing);
+
+
+   chartView->setGeometry(10,10,1300,600);
+   mchartview = chartView;
+
+   mpivchartproc  = new ivchartproc();
+   mpivchartproc->start();
+
+   QTimer * timer;
+   timer = new QTimer();
+   connect(timer,SIGNAL(timeout()),this,SLOT(onTimer()));
+   timer->start(100);
+
+   setWindowTitle("ADC IV Chart View");
+}
+
+MainWindow::~MainWindow()
+{
+    delete ui;
+}
+
+
+void MainWindow::resizeEvent(QResizeEvent *event)
+{
+    qDebug("resize");
+    QSize sizemain = ui->centralwidget->size();
+    qDebug("size x = %d y=%d",sizemain.width(),sizemain.height());
+    mchartview->setGeometry(0,0,sizemain.width(),sizemain.height());
+
+}
+
+
+void MainWindow::on_actionSelect_Data_triggered()
+{
+    std::vector<std::string> xvectorlist = mpivchartproc->GetChartNameList();
+    std::vector<std::string> xvectorused = mvectorused;
+    DialogSelect dialogselect(xvectorlist,xvectorused);
+    int nrtn = dialogselect.exec();
+
+    if(nrtn == QDialog::Accepted)
+    {
+        mvectorused = xvectorused;
+    }
+    else
+    {
+        return;
+    }
+
+    unsigned int i;
+    for(i=0;i<mvectorCUShow.size();i++)
+    {
+        unsigned int j;
+        bool bhave = false;
+        for(j=0;j<mvectorused.size();j++)
+        {
+            if(mvectorCUShow[i].mstrname == mvectorused[j])
+            {
+                bhave = true;
+                break;
+            }
+        }
+        if(bhave == false)
+        {
+            delete mvectorCUShow[i].mlineseries;
+            mvectorCUShow.erase(mvectorCUShow.begin()+i);
+        }
+
+    }
+    for(i=0;i<mvectorused.size();i++)
+    {
+        bool bhave = false;
+        unsigned int j;
+        for(j=0;j<mvectorCUShow.size();j++)
+        {
+            if(mvectorused[i] == mvectorCUShow[j].mstrname)
+            {
+                bhave = true;
+                break;
+            }
+        }
+        if(bhave == false)
+        {
+            CUShow xcu;
+            xcu.mstrname = mvectorused[i];
+            mvectorCUShow.push_back(xcu);
+
+            mvectorCUShow[mvectorCUShow.size()-1].mlineseries = new QLineSeries();
+            QLineSeries * plineseries = mvectorCUShow[mvectorCUShow.size()-1].mlineseries;
+
+            plineseries->setColor(QColor(255,0,0));
+
+            plineseries->setName(xcu.mstrname.data());
+
+            plineseries->setVisible(true);
+            plineseries->setPointLabelsFormat("(@xPoint,@yPoint)");
+            plineseries->setPointLabelsVisible(false);
+
+
+            m_chart->addSeries(plineseries);//添加系列到QChart上
+
+            //创建X轴和Y轴
+            QValueAxis *axisX = new QValueAxis;
+            axisX->setRange(-3000,0);    //默认则坐标为动态计算大小的
+            axisX->setLabelFormat("%dms");
+            QValueAxis *axisY = new QValueAxis;
+            axisY->setRange(-1,1);    //默认则坐标为动态计算大小的
+            axisY->setTitleText("value值");
+
+            axisY->setLinePenColor(QColor(0,255,0));
+
+            m_chart->setAxisX(axisX,plineseries);
+            m_chart->setAxisY(axisY,plineseries);
+        }
+    }
+
+}
+
+void MainWindow::onTimer()
+{
+    unsigned int i;
+    for(i=0;i<mvectorCUShow.size();i++)
+    {
+        std::vector<iv::ivchart::ivchartunit> xvectorcu = mpivchartproc->GetChartUnit(mvectorCUShow[i].mstrname);
+        unsigned int j;
+        qint64 nnow = QDateTime::currentMSecsSinceEpoch();
+        QList<QPointF> xListPoint;
+        for(j=0;j<xvectorcu.size();j++)
+        {
+
+            xListPoint.push_back(QPointF(xvectorcu[j].timex() - nnow,xvectorcu[j].fvalue()));
+ //           qDebug("%f %f ",xListPoint[0].x(),xListPoint[0].y());
+        }
+
+        mvectorCUShow[i].mlineseries->replace(xListPoint);
+    }
+}

+ 51 - 0
src/tool/view_ivchart/mainwindow.h

@@ -0,0 +1,51 @@
+#ifndef MAINWINDOW_H
+#define MAINWINDOW_H
+
+#include <QMainWindow>
+
+#include <QtCharts>
+#include <QLineSeries>
+
+#include "ivchartproc.h"
+#include "dialogselect.h"
+
+QT_BEGIN_NAMESPACE
+namespace Ui { class MainWindow; }
+QT_END_NAMESPACE
+
+struct CUShow
+{
+public:
+    std::string mstrname;
+    QLineSeries * mlineseries;
+};
+
+class MainWindow : public QMainWindow
+{
+    Q_OBJECT
+
+public:
+    MainWindow(QWidget *parent = nullptr);
+    ~MainWindow();
+
+private slots:
+    void onTimer();
+
+private:
+    Ui::MainWindow *ui;
+
+    QChart * m_chart;
+    QChartView * mchartview;
+
+    ivchartproc * mpivchartproc;
+
+    std::vector<std::string> mvectorused;
+
+    std::vector<CUShow> mvectorCUShow;
+public:
+     void resizeEvent(QResizeEvent *event);
+
+private slots:
+     void on_actionSelect_Data_triggered();
+};
+#endif // MAINWINDOW_H

+ 43 - 0
src/tool/view_ivchart/mainwindow.ui

@@ -0,0 +1,43 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>MainWindow</class>
+ <widget class="QMainWindow" name="MainWindow">
+  <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="menuFunc">
+    <property name="title">
+     <string>Func</string>
+    </property>
+    <addaction name="actionSelect_Data"/>
+   </widget>
+   <addaction name="menuFunc"/>
+  </widget>
+  <widget class="QStatusBar" name="statusbar"/>
+  <action name="actionSelect_Data">
+   <property name="text">
+    <string>Select Data</string>
+   </property>
+  </action>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 45 - 0
src/tool/view_ivchart/view_ivchart.pro

@@ -0,0 +1,45 @@
+QT       += core gui charts dbus
+
+greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
+
+CONFIG += c++11
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked 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
+
+# You can also make your code fail to compile if it uses 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 += \
+    ../../include/msgtype/ivchart.pb.cc \
+    dialogselect.cpp \
+    ivchartproc.cpp \
+    main.cpp \
+    mainwindow.cpp
+
+HEADERS += \
+    ../../include/msgtype/ivchart.pb.h \
+    dialogselect.h \
+    ivchartproc.h \
+    mainwindow.h
+
+FORMS += \
+    dialogselect.ui \
+    mainwindow.ui
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+INCLUDEPATH += $$PWD/../../include/msgtype
+
+unix: LIBS += -lprotobuf
+
+win32: LIBS += $$PWD\..\..\..\thirdpartylib\protobuf\lib\libprotobuf.a
+win32: INCLUDEPATH+= $$PWD\..\..\..\thirdpartylib\protobuf\src

+ 5 - 1
src/ui/ADCIntelligentShow_grpc/adcintelligentshow.cpp

@@ -8,6 +8,8 @@
 #include "pos_def.h"
 extern std::vector<iv::pos_def> gvectorpos;
 
+extern std::string gstrdefaultlane;
+
 ADCIntelligentShow * gAShow;
 
 
@@ -256,6 +258,8 @@ ADCIntelligentShow::ADCIntelligentShow(QWidget *parent) :
 
     mpapad = iv::modulecomm::RegisterSend("pad",1000,1);
 
+    mndefaultlane = atoi(gstrdefaultlane.data());
+
 
 #endif
 
@@ -1064,7 +1068,7 @@ void ADCIntelligentShow::on_pushButton_go_clicked()
     xodrobj xo;
     xo.flon = gvectorpos[mnStationIndex].mflon;
     xo.flat = gvectorpos[mnStationIndex].mflat;
-    xo.lane = 3;
+    xo.lane = mndefaultlane;
 
 #ifndef Android
     iv::modulecomm::ModuleSendMsg(mpadst,(char *)&xo,sizeof(xodrobj));

+ 1 - 0
src/ui/ADCIntelligentShow_grpc/adcintelligentshow.h

@@ -255,6 +255,7 @@ private:
 
     void *mpadst;
     int mnStationIndex = 0;
+    int mndefaultlane = 1;
     ////////////////////////////////////////////////////
 
 };

+ 2 - 0
src/ui/ADCIntelligentShow_grpc/main.cpp

@@ -25,6 +25,7 @@ std::string gstrmode = "false";
 std::string gstrserverip = "192.168.1.102";
 std::string gstrserverport = "30051";
 std::string gstrqueryinterval = "10";
+std::string gstrdefaultlane = "1";
 
 #include "pos_def.h"
 
@@ -144,6 +145,7 @@ int main(int argc, char *argv[])
    gstrserverip = xp.GetParam("serverip","192.168.1.102");
    gstrserverport = xp.GetParam("serverport","30051");
    gstrqueryinterval = xp.GetParam("queryinterval","10");
+   gstrdefaultlane = xp.GetParam("defaultlane","1");
 
    grpcclientthread xrpcthread;
 

+ 2 - 0
src/v2x/v2xTcpClient/Readme.md

@@ -0,0 +1,2 @@
+# 简介
+应用部云平台,针对天津职业大学开发的客户端。使用TCP/IP 协议传输。

+ 25 - 0
src/v2x/v2xTcpClientWL/Readme.md

@@ -0,0 +1,25 @@
+# 简介
+网连云平台,针对智能大会期间开发的客户端。使用TCP/IP 协议传输。
+具体协议参考doc/智能网连数据采集规范.pdf
+协议范例:
+```
+2323 03fe 4c5a595441474257354b31303439323831 31363136353733333731323533 000000000000000000 01 00 00d6
+01020020目标物数据
+010104e204e200780078007800780078010104e204e200780078007800780078
+02020010位置数据
+06c68be302130d2606d8e9b4026dcd96
+03020058决策数据
+0410100010021010002001001000100010001000100002201000100210100020010010001000100010001000
+04020020整车性能数据
+0010000800020000001000100010001000200008000200000010001000100010
+05010018整车状态数据
+010101010101010101010001010101000101001000100101
+0701000c道路信息数据
+005a00100101780101010100
+08010004自然环境数
+0101001c
+09010003
+010101
+0a01000b
+0101010101010101010101
+```

+ 51 - 0
src/v2x/v2xTcpClientWL/boost.h

@@ -0,0 +1,51 @@
+#pragma once
+
+#ifndef _IV_BOOST_H_
+#define _IV_BOOST_H_
+
+#if defined __GNUC__
+#  pragma GCC system_header 
+#endif
+#ifndef __CUDACC__
+//https://bugreports.qt-project.org/browse/QTBUG-22829
+#ifndef Q_MOC_RUN
+#include <boost/version.hpp>
+#include <boost/numeric/conversion/cast.hpp>
+#include <boost/thread/mutex.hpp>
+#include <boost/thread/condition.hpp>
+#include <boost/thread.hpp>
+#include <boost/thread/thread.hpp>
+#include <boost/filesystem.hpp>
+#include <boost/bind.hpp>
+#include <boost/cstdint.hpp>
+#include <boost/function.hpp>
+#include <boost/tuple/tuple.hpp>
+#include <boost/shared_ptr.hpp>
+#include <boost/weak_ptr.hpp>
+#include <boost/mpl/fold.hpp>
+#include <boost/mpl/inherit.hpp>
+#include <boost/mpl/inherit_linearly.hpp>
+#include <boost/mpl/joint_view.hpp>
+#include <boost/mpl/transform.hpp>
+#include <boost/mpl/vector.hpp>
+#include <boost/algorithm/string.hpp>
+#ifndef Q_MOC_RUN
+#include <boost/date_time/posix_time/posix_time.hpp>
+#endif
+#if BOOST_VERSION >= 104700
+#include <boost/chrono.hpp>
+#endif
+#include <boost/tokenizer.hpp>
+#include <boost/foreach.hpp>
+#include <boost/shared_array.hpp>
+#include <boost/interprocess/sync/file_lock.hpp>
+#if BOOST_VERSION >= 104900
+#include <boost/interprocess/permissions.hpp>
+#endif
+#include <boost/iostreams/device/mapped_file.hpp>
+#define BOOST_PARAMETER_MAX_ARITY 7
+#include <boost/signals2.hpp>
+#include <boost/signals2/slot.hpp>
+#endif
+#endif
+#endif    // _IV_BOOST_H_

+ 203 - 0
src/v2x/v2xTcpClientWL/data_type.h

@@ -0,0 +1,203 @@
+#ifndef DATA_TYPE_H
+#define DATA_TYPE_H
+/// cameral status, 2019-10-18
+#include <vector>
+#include <stdint.h>
+#include <iostream>
+
+typedef uint8_t u8;
+typedef uint16_t u16;
+typedef uint32_t u32;
+
+enum DownID { StopCommand = 1, AutoPilotControl, StationCommand };
+//1目标物数据
+struct ObsTypeData
+{
+    u8 msgSig = 1;
+    u8 msgRate = 1;
+    u8 msgSize = 16; //0x20
+    u8 obsType = 0xFF;
+    u8 obsSt = 0xFF;
+    u8 hDisH = 0xFF;
+    u8 hDisL = 0;
+    u8 vDisH = 0xFF;
+    u8 vDisL = 0;
+    u8 hSpeedH = 0xFF;
+    u8 hSpeedL = 0;
+    u8 vSpeedH = 0xFF;
+    u8 vSpeedL = 0;
+    u8 obsLengthH = 0xFF;
+    u8 obsLengthL = 0xFF;
+    u8 obsHightH = 0xFF;
+    u8 obsHightL = 0;
+    u8 obsWigthH = 0xFF;
+    u8 obsWigthL = 0xFF;
+};
+//2位置数据 @
+struct LocationData
+{
+    u8 msgSig = 2;
+    u8 msgRate = 1;
+
+    u8 msgSize = 8; //0x8
+    u8 lonH1 = 0;
+    u8 lonH0 = 0;
+    u8 lonL1 = 0;
+    u8 lonL0 = 0;
+    u8 latH1 = 0;
+    u8 latH0 = 0;
+    u8 latL1 = 0;
+    u8 latL0 = 0;
+};
+//3决策数据 @
+struct DecisionData
+{
+    u8 msgSig = 3;
+    u8 msgRate = 1;
+    u8 msgSize = 22;
+    u8 gear = 0;
+    u8 accPad = 0xFF;
+    u8 brakePad = 0xFF;
+    u8 epsAngleH = 0xFF; //@
+    u8 epsAngleL = 0; //@
+    u8 gearReq = 0;
+    u8 hAccAdReqH = 0;
+    u8 hAccAdReqL = 0;
+    u8 vAccAdReqH = 0;
+    u8 vAccAdReqL = 0;
+    u8 epsAngleAdReqH1 = 0;
+    u8 epsAngleAdReqH0 = 0;
+    u8 epsAngleAdReqL1 = 0;
+    u8 epsAngleAdReqL0 = 0;
+    u8 epsPowerAdReqH = 0;
+    u8 epsPowerAdReqL = 0;
+    u8 vPowerAdReqH = 0;
+    u8 vPowerAdReqL = 0;
+    u8 lightAdReqH = 0;
+    u8 lightAdReqL = 0;
+    u8 wiperAdReqH = 0;
+    u8 wiperAdReqL = 0;
+    u8 controllOver = 0;
+};
+//4整车性能数据
+struct VehiclePerfData
+{
+    u8 msgSig = 4;
+    u8 msgRate = 1;
+    u8 msgSize = 16;
+    u8 speedH = 0xFF; //@
+    u8 speedL = 0xFF; //@
+    u8 hAccH = 0; //@
+    u8 hAccL = 0; //@
+    u8 vAccH = 0; //@
+    u8 vAccL = 20; //@
+    u8 headingH1 = 0;//@
+    u8 headingH0 = 0;//@
+    u8 headingL1 = 0;//@
+    u8 headingL0 = 0;//@
+    u8 yawSpeedH = 0;
+    u8 yawSpeedL = 0;
+    u8 rollSpeedH = 0;
+    u8 rollSpeedL = 0;
+    u8 pitchSpeedH = 0;
+    u8 pitchSpeedL = 0;
+};
+
+//5整车状态数据
+struct VehicleStData
+{
+    u8 msgSig = 5;
+    u8 msgRate = 1;
+    u8 msgSize = 24;
+    u8 powerSt = 0xFF;
+    u8 ctrlMode = 0xFF; //@
+    u8 driMode = 0xFF;
+    u8 chargeMode = 0xFF;
+    u8 gearSt = 0;
+    u8 brakeSt = 0xFF;
+    u8 lightSt = 0xFF;
+    u8 batterySt = 0xFF;
+    u8 oilMassSt = 0xFF;
+    u8 batteryLvSt = 0xFF;
+    u8 meilageH1 = 0xE3;//@
+    u8 meilageH0 = 0xFF;//@
+    u8 meilageL1 = 0;//@
+    u8 meilageL0 = 0;//@
+    u8 wiperSt = 0xFF;
+    u8 netSt = 0xFF;
+    u8 signalSt = 0xFF;
+    u8 upSpeedH = 0xF0;
+    u8 upSpeedL = 0;
+    u8 downSpeedH = 0xE0;
+    u8 downSpeedL = 0;
+    u8 AFS = 0x02;
+    u8 ESC = 0x3;
+};
+
+////6路测设施数据
+//struct1
+//{
+//    u8 msgSig = 6;
+//    u8 msgRate = 1;
+//    u8 msgSize = ;
+//};
+////7道路信息数据
+//struct
+//{
+//    u8 msgSig = 7;
+//    u8 msgRate = 1;
+//    u8 msgSize = ;
+//};
+////8自然环境数据
+//struct
+//{
+//    u8 msgSig = 8;
+//    u8 msgRate = 1;
+//    u8 msgSize = ;
+//};
+////9人员数据
+//struct
+//{
+//    u8 msgSig = 9;
+//    u8 msgRate = 1;
+//    u8 msgSize = ;
+//};
+//10部件数据
+struct ComponsData
+{
+    u8 msgSig = 0x0A;
+    u8 msgRate = 1;
+    u8 msgSize = 11;
+    u8 SRSSt = 0xFF;
+    u8 GNSSST = 0xFF;
+    u8 IMUSt = 0xFF;
+    u8 ADSysSt = 0x01;//@
+    u8 mapSt = 0xFF;
+    u8 OBUSt = 0xFF;
+    u8 cameraSt = 0xFF;
+    u8 lidarSt = 0xFF;
+    u8 ultraSt = 0xFF;
+    u8 radarSt = 0xFF;
+    u8 nightVision = 0xFF;
+};
+
+//数据包
+struct UpdatePack
+{
+    u8 head1 = 0x23;
+    u8 head2 = 0x23;
+    u8 cmdSig = 0x03;
+    u8 askSig = 0xfe;
+//    std::string carVIN= "A1S2D3F4G5H6J7126;
+    u8 carVIN[17] ;
+//    std::string timeStamp;
+    u8 timeStamp[13] = {0};
+//    std::string msgId = "000000000";
+    u8 msgID[9] = {0};
+    u8 encryType = 0x01;
+    u8 dataRate = 0;
+    u8 dataSizeL = 0;
+    u8 dataSizeH = 0;
+};
+
+#endif // DATA_TYPE_H

+ 61 - 0
src/v2x/v2xTcpClientWL/decition_type.h

@@ -0,0 +1,61 @@
+#pragma once
+#ifndef _IV_DECITION_DECITION_TYPE_
+#define _IV_DECITION_DECITION_TYPE_
+#include "boost.h"
+namespace iv {
+namespace decition {
+struct DecitionBasic {
+    float speed;				//车速
+    float wheel_angle;			//转向角度
+    float brake;				//刹车
+    float accelerator;			//油门
+    float torque;               //力矩
+    bool leftlamp;				//左转向灯
+    bool rightlamp;				//右转向灯
+
+    int  engine;
+    int  grade;
+    int  mode;
+    int handBrake;
+    bool speak;
+    bool door;
+    bool bright;
+    int dangWei;
+
+    float angSpeed;
+    int brakeType :1;
+    char brakeEnable;  //add by fjk
+    bool left;         //add by fjk
+    bool right;        //add by fjk
+
+    bool angleEnable;
+    bool speedEnable;
+    bool dangweiEnable;
+    int  driveMode;
+
+    int directLight;
+    int brakeLight;
+    int backLight;
+    int topLight;
+
+    int farLight;
+    int nearLight;
+
+
+
+    bool   air_enable ;                  //空调使能
+    bool   air_on;
+    float   air_temp ;                  //空调温度
+    float   air_mode ;                  //空调模式
+    float   wind_level ;                  //空调风力
+    float   roof_light ;                  //顶灯
+    float   home_light ;                  //日光灯
+    float   air_worktime ;                  //空调工作时间
+    float   air_offtime ;                  //空调关闭时间
+
+};
+typedef boost::shared_ptr<DecitionBasic> Decition;	//决策
+}
+}
+#endif // !_IV_DECITION_DECITION_TYPE_
+

+ 154 - 0
src/v2x/v2xTcpClientWL/gnss_coordinate_convert.cpp

@@ -0,0 +1,154 @@
+#include <gnss_coordinate_convert.h>
+
+void gps2xy(double J4, double K4, double *x, double *y)
+{
+    int L4 = (int)((K4 - 1.5) / 3) + 1;
+    double M4 = K4 - (L4 * 3);
+    double N4 = sin(J4 * 3.1415926536 / 180);
+    double O4 = cos(J4 * 3.1415926536 / 180);
+    double P4 = tan(J4 * 3.1415926536 / 180);
+    double Q4 = 111134.8611 * J4 - N4 * O4 * (32005.7799 + 133.9238 * N4 * N4 + 0.6973 * N4 * N4 * N4 * N4 + 0.0039 * N4 * N4 * N4 * N4 * N4 * N4);
+    double R4 = sqrt(0.006738525414683) * O4;
+    double S4 = sqrt(1 + R4 * R4);
+    double T4 = 6399698.901783 / S4;
+    double U4 = (T4 / S4) / S4;
+    double V4 = O4 * M4 * 3.1415926536 / 180;
+    double W4 = 0.5 + (5 - P4 * P4 + 9 * R4 * R4 + 4 * R4 * R4 * R4 * R4) * V4 * V4 / 24;
+    double X4 = V4 * V4 * V4 * V4 / 720 * (61 + (P4 * P4 - 58) * P4 * P4);
+    double Y4 = 1 + V4 * V4 * (1 - P4 * P4 + R4 * R4) / 6;
+    double Z4 = V4 * V4 * V4 * V4 * (5 - 18 * P4 * P4 * P4 * P4 * P4 * P4 + 14 * R4 * R4 - 58 * R4 * R4 * P4 * P4) / 120;
+
+    *y = Q4 + T4 * P4 * V4 * V4 * (W4 + X4);
+    *x = 500000 + T4 * V4 * (Y4 + Z4);
+}
+
+
+
+//高斯投影由经纬度(Unit:DD)反算大地坐标(含带号,Unit:Metres)
+void GaussProjCal(double longitude, double latitude, double *X, double *Y)
+{
+    int ProjNo = 0; int ZoneWide; ////带宽
+    double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
+    double a, f, e2, ee, NN, T, C, A, M, iPI;
+    iPI = 0.0174532925199433; ////3.1415926535898/180.0;
+    ZoneWide = 6; ////6度带宽
+    a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
+                                    ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
+    ProjNo = (int)(longitude / ZoneWide);
+    longitude0 = ProjNo * ZoneWide + ZoneWide / 2;
+    longitude0 = longitude0 * iPI;
+    latitude0 = 0;
+    longitude1 = longitude * iPI; //经度转换为弧度
+    latitude1 = latitude * iPI; //纬度转换为弧度
+    e2 = 2 * f - f * f;
+    ee = e2 * (1.0 - e2);
+    NN = a / sqrt(1.0 - e2 * sin(latitude1)*sin(latitude1));
+    T = tan(latitude1)*tan(latitude1);
+    C = ee * cos(latitude1)*cos(latitude1);
+    A = (longitude1 - longitude0)*cos(latitude1);
+    M = a * ((1 - e2 / 4 - 3 * e2*e2 / 64 - 5 * e2*e2*e2 / 256)*latitude1 - (3 * e2 / 8 + 3 * e2*e2 / 32 + 45 * e2*e2
+        *e2 / 1024)*sin(2 * latitude1)
+        + (15 * e2*e2 / 256 + 45 * e2*e2*e2 / 1024)*sin(4 * latitude1) - (35 * e2*e2*e2 / 3072)*sin(6 * latitude1));
+    xval = NN * (A + (1 - T + C)*A*A*A / 6 + (5 - 18 * T + T * T + 72 * C - 58 * ee)*A*A*A*A*A / 120);
+    yval = M + NN * tan(latitude1)*(A*A / 2 + (5 - T + 9 * C + 4 * C*C)*A*A*A*A / 24
+        + (61 - 58 * T + T * T + 600 * C - 330 * ee)*A*A*A*A*A*A / 720);
+    X0 = 1000000L * (ProjNo + 1) + 500000L;
+    Y0 = 0;
+    xval = xval + X0; yval = yval + Y0;
+    *X = xval;
+    *Y = yval;
+}
+
+
+/*
+//=======================zhaobo0904
+#define PI  3.14159265358979
+void GaussProjCal(double lon, double lat, double *X, double *Y)
+{
+    // 1975 年国际椭球体长半轴 a, 第一离心率 e2, 第二离心率 ep2
+    double a = 6378140.0;
+    double e2 = 0.006694384999588;
+    double ep2 = e2/(1-e2);
+
+    // 原点所在经度
+    double lon_origin = 6.0*int(lon/6) + 3.0;
+    lon_origin *= PI / 180.0;
+
+    double k0 = 0.9996;
+
+    // 角度转弧度
+    double lat1 = lat * PI / 180.0;
+    double lon1 = lon * PI / 180.0;
+
+
+    // 经线在该点处的曲率半径,
+    double N = a / sqrt(1 - e2*sin(lat1)*sin(lat1));
+
+
+    // 赤道到该点的经线长度近似值 M, 使用泰勒展开逐项积分然后取前四项.
+    // 这个近似值是将 N 作为纬度 \phi 的函数展开为泰勒计数, 然后在区间 [0, lat1] 上积分得到的.
+    // 首先计算前四项的系数 a1~a4.
+    double a1 = 1 - e2/4 - (3*e2*e2)/64 - (5*e2*e2*e2)/256;
+    double a2 = (3*e2)/8 + (3*e2*e2)/32 + (45*e2*e2*e2)/1024;
+    double a3 = (15*e2*e2)/256 + (45*e2*e2*e2)/1024;
+    double a4 = (35*e2*e2*e2)/3072;
+    double M = a * (a1*lat1 - a2*sin(2*lat1) + a3*sin(4*lat1) - a4*sin(6*lat1));
+
+    // 辅助量
+    double T = tan(lat1)*tan(lat1);
+    double C = ep2*cos(lat1)*cos(lat1);
+    double A = (lon1 - lon_origin)*cos(lat1);
+
+    *X = 500000.0 + k0 * N * (A + (1 - T + C)*(A*A*A)/6 + (5 - 18*T + T*T + 72*C - 58*ep2)*(A*A*A*A*A)/120);
+    *Y = M + N * tan(lat1) * ((A*A)/2 +
+                              (5 - T + 9*C + 4*C*C)*(A*A*A*A)/24 +
+                              (61 - 58*T + T*T + 600*C - 330*ep2)*(A*A*A*A*A*A)/720);
+
+
+    *Y *= k0;
+    return;
+}
+//==========================================================
+
+*/
+
+
+//高斯投影由大地坐标(Unit:Metres)反算经纬度(Unit:DD)
+void GaussProjInvCal(double X, double Y, double *longitude, double *latitude)
+{
+    int ProjNo; int ZoneWide; ////带宽
+    double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
+    double e1, e2, f, a, ee, NN, T, C, M, D, R, u, fai, iPI;
+    iPI = 0.0174532925199433; ////3.1415926535898/180.0;
+    a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
+    ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
+    ZoneWide = 6; ////6度带宽
+    ProjNo = (int)(X / 1000000L); //查找带号
+    longitude0 = (ProjNo - 1) * ZoneWide + ZoneWide / 2;
+    longitude0 = longitude0 * iPI; //中央经线
+    X0 = ProjNo * 1000000L + 500000L;
+    Y0 = 0;
+    xval = X - X0; yval = Y - Y0; //带内大地坐标
+    e2 = 2 * f - f * f;
+    e1 = (1.0 - sqrt(1 - e2)) / (1.0 + sqrt(1 - e2));
+    ee = e2 / (1 - e2);
+    M = yval;
+    u = M / (a*(1 - e2 / 4 - 3 * e2*e2 / 64 - 5 * e2*e2*e2 / 256));
+    fai = u + (3 * e1 / 2 - 27 * e1*e1*e1 / 32)*sin(2 * u) + (21 * e1*e1 / 16 - 55 * e1*e1*e1*e1 / 32)*sin(
+                4 * u)
+            + (151 * e1*e1*e1 / 96)*sin(6 * u) + (1097 * e1*e1*e1*e1 / 512)*sin(8 * u);
+    C = ee * cos(fai)*cos(fai);
+    T = tan(fai)*tan(fai);
+    NN = a / sqrt(1.0 - e2 * sin(fai)*sin(fai));
+    R = a * (1 - e2) / sqrt((1 - e2 * sin(fai)*sin(fai))*(1 - e2 * sin(fai)*sin(fai))*(1 - e2 * sin
+                                                                                       (fai)*sin(fai)));
+    D = xval / NN;
+    //计算经度(Longitude) 纬度(Latitude)
+    longitude1 = longitude0 + (D - (1 + 2 * T + C)*D*D*D / 6 + (5 - 2 * C + 28 * T - 3 * C*C + 8 * ee + 24 * T*T)*D
+                               *D*D*D*D / 120) / cos(fai);
+    latitude1 = fai - (NN*tan(fai) / R)*(D*D / 2 - (5 + 3 * T + 10 * C - 4 * C*C - 9 * ee)*D*D*D*D / 24
+                                         + (61 + 90 * T + 298 * C + 45 * T*T - 256 * ee - 3 * C*C)*D*D*D*D*D*D / 720);
+    //转换为度 DD
+    *longitude = longitude1 / iPI;
+    *latitude = latitude1 / iPI;
+}

이 변경점에서 너무 많은 파일들이 변경되어 몇몇 파일들은 표시되지 않았습니다.