Browse Source

add common/comm/xodr folder for opendrive structure.

yuchuli 4 years ago
parent
commit
2996680746
26 changed files with 894 additions and 34 deletions
  1. 0 0
      src/common/common/xodr/OpenDrive/Junction.cpp
  2. 0 0
      src/common/common/xodr/OpenDrive/Junction.h
  3. 0 0
      src/common/common/xodr/OpenDrive/Lane.cpp
  4. 0 0
      src/common/common/xodr/OpenDrive/Lane.h
  5. 514 0
      src/common/common/xodr/OpenDrive/ObjectSignal.cpp
  6. 163 0
      src/common/common/xodr/OpenDrive/ObjectSignal.h
  7. 6 0
      src/common/common/xodr/OpenDrive/OpenDrive.cpp
  8. 3 0
      src/common/common/xodr/OpenDrive/OpenDrive.h
  9. 116 2
      src/common/common/xodr/OpenDrive/OpenDriveXmlParser.cpp
  10. 3 0
      src/common/common/xodr/OpenDrive/OpenDriveXmlParser.h
  11. 75 0
      src/common/common/xodr/OpenDrive/OpenDriveXmlWriter.cpp
  12. 3 0
      src/common/common/xodr/OpenDrive/OpenDriveXmlWriter.h
  13. 0 0
      src/common/common/xodr/OpenDrive/OtherStructures.cpp
  14. 0 0
      src/common/common/xodr/OpenDrive/OtherStructures.h
  15. 8 2
      src/common/common/xodr/OpenDrive/Road.cpp
  16. 2 1
      src/common/common/xodr/OpenDrive/Road.h
  17. 0 0
      src/common/common/xodr/OpenDrive/RoadGeometry.cpp
  18. 1 1
      src/common/common/xodr/OpenDrive/RoadGeometry.h
  19. 0 0
      src/common/common/xodr/TinyXML/tinystr.cpp
  20. 0 0
      src/common/common/xodr/TinyXML/tinystr.h
  21. 0 0
      src/common/common/xodr/TinyXML/tinyxml.cpp
  22. 0 0
      src/common/common/xodr/TinyXML/tinyxml.h
  23. 0 0
      src/common/common/xodr/TinyXML/tinyxmlerror.cpp
  24. 0 0
      src/common/common/xodr/TinyXML/tinyxmlparser.cpp
  25. 0 0
      src/driver/driver_map_xodrload/OpenDrive/ObjectSignal.cpp
  26. 0 28
      src/driver/driver_map_xodrload/OpenDrive/ObjectSignal.h

+ 0 - 0
src/driver/driver_map_xodrload/OpenDrive/Junction.cpp → src/common/common/xodr/OpenDrive/Junction.cpp


+ 0 - 0
src/driver/driver_map_xodrload/OpenDrive/Junction.h → src/common/common/xodr/OpenDrive/Junction.h


+ 0 - 0
src/driver/driver_map_xodrload/OpenDrive/Lane.cpp → src/common/common/xodr/OpenDrive/Lane.cpp


+ 0 - 0
src/driver/driver_map_xodrload/OpenDrive/Lane.h → src/common/common/xodr/OpenDrive/Lane.h


+ 514 - 0
src/common/common/xodr/OpenDrive/ObjectSignal.cpp

@@ -0,0 +1,514 @@
+#include "ObjectSignal.h"
+
+#include <iostream>
+
+signal_positionRoad::signal_positionRoad(double s, double t, double zOffset, double hOffset, double pitch, double roll)
+{
+    ms = s;
+    mt = t;
+    mzOffset = zOffset;
+    mhOffset = hOffset;
+    mpitch = pitch;
+    mroll = roll;
+}
+
+double signal_positionRoad::Gets()
+{
+    return ms;
+}
+
+double signal_positionRoad::Gett()
+{
+    return mt;
+}
+
+double signal_positionRoad::GetzOffset()
+{
+    return mzOffset;
+}
+
+double signal_positionRoad::GethOffset()
+{
+    return mhOffset;
+}
+
+double signal_positionRoad::Getpitch()
+{
+    return mpitch;
+}
+
+double signal_positionRoad::Getroll()
+{
+    return mroll;
+}
+
+void signal_positionRoad::Sets(double s)
+{
+    ms = s;
+}
+
+void signal_positionRoad::Sett(double t)
+{
+    mt = t;
+}
+
+void signal_positionRoad::SetzOffset(double zOffset)
+{
+    mzOffset = zOffset;
+}
+
+void signal_positionRoad::SethOffset(double hOffset)
+{
+    mhOffset = hOffset;
+}
+
+void signal_positionRoad::Setpitch(double pitch)
+{
+    mpitch = pitch;
+}
+
+void signal_positionRoad::Setroll(double roll)
+{
+    mroll = roll;
+}
+
+signal_positionInertial::signal_positionInertial(double x, double y,double z, double hdg, double pitch, double roll)
+{
+    mx = x;
+    my = y;
+    mz = z;
+    mhdg = hdg;
+    mpitch = pitch;
+    mroll = roll;
+}
+
+double signal_positionInertial::Getx()
+{
+    return mx;
+}
+
+double signal_positionInertial::Gety()
+{
+    return my;
+}
+
+double signal_positionInertial::Getz()
+{
+    return mz;
+}
+
+double signal_positionInertial::Gethdg()
+{
+    return mhdg;
+}
+
+double signal_positionInertial::Getpitch()
+{
+    return mpitch;
+}
+
+double signal_positionInertial::Getroll()
+{
+    return mroll;
+}
+
+void signal_positionInertial::Setx(double x)
+{
+    mx = x;
+}
+
+void signal_positionInertial::Sety(double y)
+{
+    my = y;
+}
+
+void signal_positionInertial::Setz(double z)
+{
+    mz = z;
+}
+
+void signal_positionInertial::Sethdg(double hdg)
+{
+    mhdg = hdg;
+}
+
+void signal_positionInertial::Setpitch(double pitch)
+{
+    mpitch = pitch;
+}
+
+void signal_positionInertial::Setroll(double roll)
+{
+    mroll = roll;
+}
+
+
+signal_laneValidity::signal_laneValidity(int fromLane,int toLane)
+{
+    mfromLane = fromLane;
+    mtoLane = toLane;
+}
+
+int signal_laneValidity::GetfromLane()
+{
+    return mfromLane;
+}
+
+int signal_laneValidity::GettoLane()
+{
+    return mtoLane;
+}
+
+void signal_laneValidity::SetfromLane(int fromLane)
+{
+    mfromLane = fromLane;
+}
+
+void signal_laneValidity::SettoLane(int toLane)
+{
+    mtoLane = toLane;
+}
+
+
+Signal::Signal(double s, double t, std::string id, std::string name, bool dynamic,string orientation,
+               double zOffset, string type, std::string country, std::string countryRevision,
+               string subtype, double hOffset, double pitch, double roll, double height, double width)
+{
+    ms = s;
+    mt = t;
+    mid = id;
+    mname = name;
+    mdynamic = dynamic;
+    morientation = orientation;
+    mzOffset = zOffset;
+    mtype = type;
+    mcountry = country;
+    mcountryRevision = countryRevision;
+    msubtype = subtype;
+    mhOffset = hOffset;
+    mpitch = pitch;
+    mroll = roll;
+    mheight = height;
+    mwidth = width;
+    mpsignal_laneValidity = 0;
+    mpsignal_positionInertial = 0;
+    mpsignal_positionRoad = new signal_positionRoad(s,t,zOffset,hOffset,pitch,roll);
+}
+
+Signal::Signal()
+{
+    mpsignal_positionInertial = 0;
+    mpsignal_positionRoad = 0;
+    mpsignal_laneValidity = 0;
+
+}
+Signal::~Signal()
+{
+    if(mpsignal_laneValidity != 0)delete mpsignal_laneValidity;
+    if(mpsignal_positionInertial != 0)delete mpsignal_positionInertial;
+    if(mpsignal_positionRoad != 0)delete mpsignal_positionRoad;
+}
+
+Signal& Signal::operator=(const Signal& x)
+{
+    if (this != &x)
+    {
+        this->ms = x.ms;
+        this->mt = x.mt;
+        this->mid = x.mid;
+        this->mname = x.mname;
+        this->mdynamic = x.mdynamic;
+        this->morientation = x.morientation;
+        this->mzOffset = x.mzOffset;
+        this->mtype = x.mtype;
+        this->mcountry = x.mcountry;
+        this->mcountryRevision = x.mcountryRevision;
+        this->msubtype = x.msubtype;
+        this->mhOffset = x.mhOffset;
+        this->mpitch = x.mpitch;
+        this->mroll = x.mroll;
+        this->mheight = x.mheight;
+        this->mwidth = x.mwidth;
+        this->mpsignal_positionInertial = 0;
+        if(x.mpsignal_positionInertial != 0)
+        {
+            this->mpsignal_positionInertial = new signal_positionInertial(x.mpsignal_positionInertial->Getx(),
+                                                                      x.mpsignal_positionInertial->Gety(),
+                                                                      x.mpsignal_positionInertial->Getz(),
+                                                                      x.mpsignal_positionInertial->Gethdg(),
+                                                                      x.mpsignal_positionInertial->Getpitch(),
+                                                                      x.mpsignal_positionInertial->Getroll());
+        }
+        this->mpsignal_laneValidity = 0;
+        if(x.mpsignal_laneValidity != 0)
+        {
+            this->mpsignal_laneValidity = new signal_laneValidity(x.mpsignal_laneValidity->GetfromLane(),
+                                                              x.mpsignal_laneValidity->GettoLane());
+        }
+        this->mpsignal_positionRoad = new signal_positionRoad(ms,mt,mzOffset,mhOffset,mpitch,mroll);
+    }
+    return *this;
+}
+
+Signal::Signal(const Signal &x)
+{
+    ms = x.ms;
+    mt = x.mt;
+    mid = x.mid;
+    mname = x.mname;
+    mdynamic = x.mdynamic;
+    morientation = x.morientation;
+    mzOffset = x.mzOffset;
+    mtype = x.mtype;
+    mcountry = x.mcountry;
+    mcountryRevision = x.mcountryRevision;
+    msubtype = x.msubtype;
+    mhOffset = x.mhOffset;
+    mpitch = x.mpitch;
+    mroll = x.mroll;
+    mheight = x.mheight;
+    mwidth = x.mwidth;
+    this->mpsignal_positionInertial = 0;
+    if(x.mpsignal_positionInertial != 0)
+    {
+        this->mpsignal_positionInertial = new signal_positionInertial(x.mpsignal_positionInertial->Getx(),
+                                                                  x.mpsignal_positionInertial->Gety(),
+                                                                  x.mpsignal_positionInertial->Getz(),
+                                                                  x.mpsignal_positionInertial->Gethdg(),
+                                                                  x.mpsignal_positionInertial->Getpitch(),
+                                                                  x.mpsignal_positionInertial->Getroll());
+    }
+    this->mpsignal_laneValidity = 0;
+    if(x.mpsignal_laneValidity != 0)
+    {
+        this->mpsignal_laneValidity = new signal_laneValidity(x.mpsignal_laneValidity->GetfromLane(),
+                                                          x.mpsignal_laneValidity->GettoLane());
+    }
+    mpsignal_positionRoad = new signal_positionRoad(ms,mt,mzOffset,mhOffset,mpitch,mroll);
+}
+
+double Signal::Gets()
+{
+    return ms;
+}
+
+double Signal::Gett()
+{
+    return mt;
+}
+
+string Signal::Getid()
+{
+    return mid;
+}
+
+string Signal::Getname()
+{
+    return mname;
+}
+
+bool Signal::Getdynamic()
+{
+    return mdynamic;
+}
+
+string Signal::Getorientation()
+{
+    return morientation;
+}
+
+double Signal::GetzOffset()
+{
+    return mzOffset;
+}
+
+string Signal::Gettype()
+{
+    return mtype;
+}
+
+string Signal::Getcountry()
+{
+    return mcountry;
+}
+
+string Signal::GetcountryRevision()
+{
+    return mcountryRevision;
+}
+
+string Signal::Getsubtype()
+{
+    return msubtype;
+}
+
+double Signal::GethOffset()
+{
+    return mhOffset;
+}
+
+double Signal::Getpitch()
+{
+    return mpitch;
+}
+
+double Signal::Getroll()
+{
+    return mroll;
+}
+
+double Signal::Getheight()
+{
+    return mheight;
+}
+
+double Signal::Getwidth()
+{
+    return mwidth;
+}
+
+signal_positionRoad * Signal::GetpositionRoad()
+{
+    return mpsignal_positionRoad;
+}
+
+signal_positionInertial * Signal::GetpositionInertial()
+{
+    return mpsignal_positionInertial;
+}
+
+void Signal::Sets(double s)
+{
+    ms = s;
+}
+
+void Signal::Sett(double t)
+{
+    mt = t;
+}
+
+void Signal::Setid(std::string id)
+{
+    mid = id;
+}
+
+void Signal::Setname(std::string name)
+{
+    mname = name;
+}
+
+void Signal::Setdynamic(bool dynamic)
+{
+    mdynamic = dynamic;
+}
+
+void Signal::Setorientation(std::string orientation)
+{
+    morientation = orientation;
+}
+
+void Signal::SetzOffset(double zOffset)
+{
+    mzOffset = zOffset;
+}
+
+void Signal::Settype(string type)
+{
+    mtype = type;
+}
+
+void Signal::Setcountry(std::string country)
+{
+    mcountry = country;
+}
+
+void Signal::SetcountryRevision(std::string countryRevision)
+{
+    mcountryRevision = countryRevision;
+}
+
+void Signal::Setsubtype(string subtype)
+{
+    msubtype = subtype;
+}
+
+void Signal::SethOffset(double hOffset)
+{
+    mhOffset = hOffset;
+}
+
+void Signal::Setpitch(double pitch)
+{
+    mpitch = pitch;
+}
+
+void Signal::Setroll(double roll)
+{
+    mroll = roll;
+}
+
+void Signal::Setheight(double height)
+{
+    mheight = height;
+}
+
+void Signal::Setwidth(double width)
+{
+    mwidth = width;
+}
+
+void Signal::SetlaneValidity(int fromLane, int toLane)
+{
+    if(mpsignal_laneValidity == 0)
+    {
+        mpsignal_laneValidity = new signal_laneValidity(fromLane,toLane);
+    }
+    else
+    {
+        mpsignal_laneValidity->SetfromLane(fromLane);
+        mpsignal_laneValidity->SettoLane(toLane);
+    }
+}
+
+void Signal::SetpositionRoad(double s, double t, double zOffset, double hOffset, double pitch,double roll)
+{
+    if(mpsignal_positionRoad == 0)
+    {
+        mpsignal_positionRoad = new signal_positionRoad(s,t,zOffset,hOffset,pitch,roll);
+    }
+    else
+    {
+        mpsignal_positionRoad->Sets(s);
+        mpsignal_positionRoad->Sett(t);
+        mpsignal_positionRoad->SetzOffset(zOffset);
+        mpsignal_positionRoad->SethOffset(hOffset);
+        mpsignal_positionRoad->Setpitch(pitch);
+        mpsignal_positionRoad->Setroll(roll);
+    }
+}
+
+void Signal::SetpositionInertial(double x, double y, double z, double hdg, double pitch, double roll)
+{
+    if(mpsignal_positionInertial == 0)
+    {
+        mpsignal_positionInertial = new signal_positionInertial(x,y,z,hdg,pitch,roll);
+    }
+    else
+    {
+        mpsignal_positionInertial->Setx(x);
+        mpsignal_positionInertial->Sety(y);
+        mpsignal_positionInertial->Setz(z);
+        mpsignal_positionInertial->Sethdg(hdg);
+        mpsignal_positionInertial->Setpitch(pitch);
+        mpsignal_positionInertial->Setroll(roll);
+    }
+}
+
+signal_laneValidity * Signal::GetlaneValidity()
+{
+    return mpsignal_laneValidity;
+}
+
+
+
+

+ 163 - 0
src/common/common/xodr/OpenDrive/ObjectSignal.h

@@ -0,0 +1,163 @@
+#ifndef OBJECTSIGNAL_H
+#define OBJECTSIGNAL_H
+
+#include <vector>
+#include <string>
+
+using std::vector;
+using std::string;
+
+
+//***********************************************************************************
+//Object
+//***********************************************************************************
+class Object
+{
+public:
+	Object(){}
+};
+//----------------------------------------------------------------------------------
+
+
+
+class signal_positionRoad
+{
+private:
+    double ms;
+    double mt;
+    double mzOffset;
+    double mhOffset;
+    double mpitch;
+    double mroll;
+public:
+    signal_positionRoad(double s,double t,double zOffset,double hOffset, double pitch,double roll);
+    double Gets();
+    double Gett();
+    double GetzOffset();
+    double GethOffset();
+    double Getpitch();
+    double Getroll();
+    void Sets(double s);
+    void Sett(double t);
+    void SetzOffset(double zOffset);
+    void SethOffset(double hOffset);
+    void Setpitch(double pitch);
+    void Setroll(double roll);
+};
+
+class signal_positionInertial
+{
+private:
+    double mx;
+    double my;
+    double mz;
+    double mhdg;
+    double mpitch;
+    double mroll;
+public:
+    signal_positionInertial(double x,double y,double z,double hdg,double pitch,double roll );
+    double Getx();
+    double Gety();
+    double Getz();
+    double Gethdg();
+    double Getpitch();
+    double Getroll();
+    void Setx(double x);
+    void Sety(double y);
+    void Setz(double z);
+    void Sethdg(double hdg);
+    void Setpitch(double pitch);
+    void Setroll(double roll);
+};
+
+class signal_laneValidity
+{
+private:
+    int mfromLane;
+    int mtoLane;
+public:
+    signal_laneValidity(int fromLane,int toLane);
+    int GetfromLane();
+    int GettoLane();
+    void SetfromLane(int fromLane);
+    void SettoLane(int toLane);
+};
+
+
+//***********************************************************************************
+//Signal
+//***********************************************************************************
+class Signal
+{
+private:
+    double ms;
+    double mt;
+    string mid;
+    string mname;
+    bool mdynamic;
+    string morientation;
+    double mzOffset;
+    string mtype;
+    string mcountry;
+    string mcountryRevision;
+    string msubtype;
+    double mhOffset;
+    double mpitch;
+    double mroll;
+    double mheight;
+    double mwidth;
+    signal_positionRoad * mpsignal_positionRoad;
+    signal_positionInertial * mpsignal_positionInertial;
+    signal_laneValidity * mpsignal_laneValidity;
+public:
+    Signal(double s,double t,string id,string name,bool dynamic,string orientation,double zOffset,string type,string country,string countryRevision,
+           string subtype,double hOffset,double pitch,double roll ,double height,double width);
+    Signal();
+    ~Signal();
+    Signal& operator=(const Signal& x);
+    Signal(const Signal & x);
+    double Gets();
+    double Gett();
+    string Getid();
+    string Getname();
+    bool Getdynamic();
+    string Getorientation();
+    double GetzOffset();
+    string Gettype();
+    string Getcountry();
+    string GetcountryRevision();
+    string Getsubtype();
+    double GethOffset();
+    double Getpitch();
+    double Getroll();
+    double Getheight();
+    double Getwidth();
+    signal_positionRoad * GetpositionRoad();
+    signal_positionInertial * GetpositionInertial();
+    signal_laneValidity * GetlaneValidity();
+    void Sets(double s);
+    void Sett(double t);
+    void Setid(string id);
+    void Setname(string name);
+    void Setdynamic(bool dynamic);
+    void Setorientation(string orientation);
+    void SetzOffset(double zOffset);
+    void Settype(string type);
+    void Setcountry(string country);
+    void SetcountryRevision(string countryRevision);
+    void Setsubtype(string subtype);
+    void SethOffset(double hOffset);
+    void Setpitch(double pitch);
+    void Setroll(double roll);
+    void Setheight(double height);
+    void Setwidth(double width);
+    void SetlaneValidity(int fromLane, int toLane);
+    void SetpositionRoad(double s,double t, double zOffset,double hOffset,double pitch,double roll);
+    void SetpositionInertial(double x,double y, double z, double hdg,double pitch,double roll);
+
+
+};
+//----------------------------------------------------------------------------------
+
+
+#endif

+ 6 - 0
src/driver/driver_map_xodrload/OpenDrive/OpenDrive.cpp → src/common/common/xodr/OpenDrive/OpenDrive.cpp

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

+ 3 - 0
src/driver/driver_map_xodrload/OpenDrive/OpenDrive.h → src/common/common/xodr/OpenDrive/OpenDrive.h

@@ -181,6 +181,9 @@ public:
 
     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);
+
+
+    void GetLat0Lon0(double & lat0,double & lon0);
 };
 
 

+ 116 - 2
src/driver/driver_map_xodrload/OpenDrive/OpenDriveXmlParser.cpp → src/common/common/xodr/OpenDrive/OpenDriveXmlParser.cpp

@@ -75,7 +75,7 @@ bool OpenDriveXmlParser::ReadRoad(TiXmlElement *node)
 
 	int checker=TIXML_SUCCESS;
 	
-	checker+=node->QueryStringAttribute("name",&name);
+//	checker+=node->QueryStringAttribute("name",&name);
 	checker+=node->QueryDoubleAttribute("length",&length);
 	checker+=node->QueryStringAttribute("id",&id);
 	checker+=node->QueryStringAttribute("junction",&junction);
@@ -85,6 +85,11 @@ bool OpenDriveXmlParser::ReadRoad(TiXmlElement *node)
 		cout<<"Error parsing Road attributes"<<endl;
 		return false;
 	}
+
+    if(node->QueryStringAttribute("name",&name) != TIXML_SUCCESS)
+    {
+        name = "";
+    }
 	//fill in
 	mOpenDrive->AddRoad(name, length, id, junction);
 	Road* road = mOpenDrive->GetLastAddedRoad();
@@ -910,8 +915,117 @@ bool OpenDriveXmlParser::ReadObjects (Road* road, TiXmlElement *node)
 
 bool OpenDriveXmlParser::ReadSignals (Road* road, TiXmlElement *node)
 {
-	return true;
+
+    TiXmlElement *subNode = node->FirstChildElement("signal");
+    while (subNode)
+    {
+        ReadSignal(road, subNode);
+        subNode=subNode->NextSiblingElement("signal");
+    }
+    return true;
+
+
+}
+
+bool OpenDriveXmlParser::ReadSignal(Road *road, TiXmlElement *node)
+{
+    double s;
+    double t;
+    string id;
+    string name;
+    bool dynamic;
+    string strdynamic;
+    string orientation;
+    double zOffset;
+    string type;
+    string country;
+    string countryRevision;
+    string subtype;
+    double hOffset;
+    double pitch;
+    double roll;
+    double height;
+    double width;
+
+    int checker=TIXML_SUCCESS;
+    checker+=node->QueryDoubleAttribute("s",&s);
+    checker+=node->QueryDoubleAttribute("t",&t);
+    checker+=node->QueryStringAttribute("id",&id);
+    checker+=node->QueryStringAttribute("name",&name);
+    checker+=node->QueryStringAttribute("dynamic",&strdynamic);
+    checker+=node->QueryStringAttribute("orientation",&orientation);
+    checker+=node->QueryDoubleAttribute("zOffset",&zOffset);
+    checker+=node->QueryStringAttribute("type",&type);
+    checker+=node->QueryStringAttribute("country",&country);
+    checker+=node->QueryStringAttribute("countryRevision",&countryRevision);
+    checker+=node->QueryStringAttribute("subtype",&subtype);
+    checker+=node->QueryDoubleAttribute("hOffset",&hOffset);
+    checker+=node->QueryDoubleAttribute("pitch",&pitch);
+    checker+=node->QueryDoubleAttribute("roll",&roll);
+    checker+=node->QueryDoubleAttribute("height",&height);
+    checker+=node->QueryDoubleAttribute("width",&width);
+    if (checker!=TIXML_SUCCESS)
+    {
+        cout<<"Error parsing Lane Signals attributes"<<endl;
+        return false;
+    }
+    if(strncmp(strdynamic.data(),"no",256) == 0)dynamic = false;
+    else dynamic = true;
+    road->AddSignal(s,t,id,name,dynamic,orientation,zOffset,type,country,countryRevision,subtype,hOffset,
+                    pitch,roll,height,width);
+
+    Signal * pSignal = road->GetSignal(road->GetSignalCount() - 1);
+    TiXmlElement * subNode;
+    //Proceed to Signals
+    subNode=node->FirstChildElement("validity");
+    if (subNode)
+    {
+        ReadSignal_laneValidity(pSignal, subNode);
+    }
+    subNode=node->FirstChildElement("positionInertial");
+    if(subNode)
+    {
+        ReadSignal_positionInertial(pSignal,subNode);
+    }
+    return true;
 }
+
+bool OpenDriveXmlParser::ReadSignal_laneValidity(Signal *pSignal, TiXmlElement *node)
+{
+    int fromLane;
+    int toLane;
+    int checker=TIXML_SUCCESS;
+    checker+=node->QueryIntAttribute("fromLane",&fromLane);
+    checker+=node->QueryIntAttribute("toLane",&toLane);
+    if (checker!=TIXML_SUCCESS)
+    {
+        cout<<"Error parsing laneValidity attributes"<<endl;
+        return false;
+    }
+    pSignal->SetlaneValidity(fromLane,toLane);
+    return true;
+}
+
+bool OpenDriveXmlParser::ReadSignal_positionInertial(Signal *pSignal, TiXmlElement *node)
+{
+    double x,y,z,hdg,pitch,roll;
+    int checker=TIXML_SUCCESS;
+    checker+=node->QueryDoubleAttribute("x",&x);
+    checker+=node->QueryDoubleAttribute("y",&y);
+    checker+=node->QueryDoubleAttribute("z",&z);
+    checker+=node->QueryDoubleAttribute("hdg",&hdg);
+    checker+=node->QueryDoubleAttribute("pitch",&pitch);
+    checker+=node->QueryDoubleAttribute("roll",&roll);
+    if (checker!=TIXML_SUCCESS)
+    {
+        cout<<"Error parsing positionInertial attributes"<<endl;
+        return false;
+    }
+    pSignal->SetpositionInertial(x,y,z,hdg,pitch,roll);
+    return true;
+}
+
+
 //--------------
 
 bool OpenDriveXmlParser::ReadSurface (Road* road, TiXmlElement *node)

+ 3 - 0
src/driver/driver_map_xodrload/OpenDrive/OpenDriveXmlParser.h → src/common/common/xodr/OpenDrive/OpenDriveXmlParser.h

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

+ 75 - 0
src/driver/driver_map_xodrload/OpenDrive/OpenDriveXmlWriter.cpp → src/common/common/xodr/OpenDrive/OpenDriveXmlWriter.cpp

@@ -920,8 +920,83 @@ bool OpenDriveXmlWriter::WriteSignals (TiXmlElement *node, Road* road)
 	TiXmlElement* nodeSignals = new TiXmlElement("signals");
 	node->LinkEndChild(nodeSignals);
 
+    unsigned int lSignalSectionCount = road->GetSignalCount();
+    for(unsigned int i=0; i<lSignalSectionCount; i++)
+    {
+        WriteSignal(nodeSignals, road->GetSignal(i));
+    }
+
 	return true;
 }
+
+bool OpenDriveXmlWriter::WriteSignal(TiXmlElement *node, Signal * pSignal)
+{
+    TiXmlElement* nodeSignal = new TiXmlElement("signal");
+    node->LinkEndChild(nodeSignal);
+
+    nodeSignal->SetAttribute("s",pSignal->Gets());
+    nodeSignal->SetAttribute("t",pSignal->Gett());
+    nodeSignal->SetAttribute("id",pSignal->Getid());
+    nodeSignal->SetAttribute("name",pSignal->Getname());
+    if(pSignal->Getdynamic() == true)
+    nodeSignal->SetAttribute("dynamic","yes");
+    else
+        nodeSignal->SetAttribute("dynamic","no");
+    nodeSignal->SetAttribute("orientation",pSignal->Getorientation());
+    nodeSignal->SetAttribute("zOffset",pSignal->GetzOffset());
+    nodeSignal->SetAttribute("type",pSignal->Gettype());
+    nodeSignal->SetAttribute("country",pSignal->Getcountry());
+    nodeSignal->SetAttribute("countryRevision",pSignal->GetcountryRevision());
+    nodeSignal->SetAttribute("subtype",pSignal->Getsubtype());
+    nodeSignal->SetAttribute("hOffset",pSignal->GethOffset());
+    nodeSignal->SetAttribute("pitch",pSignal->Getpitch());
+    nodeSignal->SetAttribute("roll",pSignal->Getroll());
+    nodeSignal->SetAttribute("height",pSignal->Getheight());
+    nodeSignal->SetAttribute("width",pSignal->Getwidth());
+
+    signal_laneValidity * psignal_lanevalidity = pSignal->GetlaneValidity();
+    if(psignal_lanevalidity != 0)
+    {
+        WriteSignal_laneValidity(nodeSignal,psignal_lanevalidity);
+    }
+
+    signal_positionInertial * psignal_positionInertial = pSignal->GetpositionInertial();
+    if(psignal_positionInertial != 0)
+    {
+        WriteSignal_positionInertial(nodeSignal,psignal_positionInertial);
+    }
+
+    return true;
+}
+
+bool OpenDriveXmlWriter::WriteSignal_positionInertial(TiXmlElement *node, signal_positionInertial *pSignal_positionInertial)
+{
+    TiXmlElement* nodepositionInertial = new TiXmlElement("positionInertial");
+
+    node->LinkEndChild(nodepositionInertial);
+
+    nodepositionInertial->SetAttribute("x",pSignal_positionInertial->Getx());
+    nodepositionInertial->SetAttribute("y",pSignal_positionInertial->Gety());
+    nodepositionInertial->SetAttribute("z",pSignal_positionInertial->Getz());
+    nodepositionInertial->SetAttribute("hdg",pSignal_positionInertial->Gethdg());
+    nodepositionInertial->SetAttribute("pitch",pSignal_positionInertial->Getpitch());
+    nodepositionInertial->SetAttribute("roll",pSignal_positionInertial->Getroll());
+
+    return true;
+}
+
+bool OpenDriveXmlWriter::WriteSignal_laneValidity(TiXmlElement *node, signal_laneValidity *pSignal_laneValidity)
+{
+    TiXmlElement* nodelaneValidity = new TiXmlElement("validity");
+
+    node->LinkEndChild(nodelaneValidity);
+
+    nodelaneValidity->SetAttribute("fromLane",pSignal_laneValidity->GetfromLane());
+    nodelaneValidity->SetAttribute("toLane",pSignal_laneValidity->GettoLane());
+
+    return true;
+}
+
 //--------------
 
 bool OpenDriveXmlWriter::WriteSurface (TiXmlElement *node, Road* road)

+ 3 - 0
src/driver/driver_map_xodrload/OpenDrive/OpenDriveXmlWriter.h → src/common/common/xodr/OpenDrive/OpenDriveXmlWriter.h

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

+ 0 - 0
src/driver/driver_map_xodrload/OpenDrive/OtherStructures.cpp → src/common/common/xodr/OpenDrive/OtherStructures.cpp


+ 0 - 0
src/driver/driver_map_xodrload/OpenDrive/OtherStructures.h → src/common/common/xodr/OpenDrive/OtherStructures.h


+ 8 - 2
src/driver/driver_map_xodrload/OpenDrive/Road.cpp → src/common/common/xodr/OpenDrive/Road.cpp

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

+ 2 - 1
src/driver/driver_map_xodrload/OpenDrive/Road.h → src/common/common/xodr/OpenDrive/Road.h

@@ -229,7 +229,8 @@ public:
 	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();
+    unsigned int AddSignal(double s,double t,string id,string name,bool dynamic,string orientation,double zOffset,string type,string country,string countryRevision,
+                           string subtype,double hOffset,double pitch,double roll ,double height,double width);
 
 	/**
 	 * Methods used to clone child records in the respective vectors

+ 0 - 0
src/driver/driver_map_xodrload/OpenDrive/RoadGeometry.cpp → src/common/common/xodr/OpenDrive/RoadGeometry.cpp


+ 1 - 1
src/driver/driver_map_xodrload/OpenDrive/RoadGeometry.h → src/common/common/xodr/OpenDrive/RoadGeometry.h

@@ -30,7 +30,7 @@ protected:
 	double mHdg;
 	double mLength;
 	double mS2;
-    short int mGeomType;	//0-line, 1-spiral, 2-arc 3-poly3 4-parampoly3
+    short int mGeomType;	//0-line, 1-arc, 2-spiral 3-poly3 4-parampoly3
 public:
 	/**
 	 * Constructor that initializes the base properties of teh record

+ 0 - 0
src/driver/driver_map_xodrload/TinyXML/tinystr.cpp → src/common/common/xodr/TinyXML/tinystr.cpp


+ 0 - 0
src/driver/driver_map_xodrload/TinyXML/tinystr.h → src/common/common/xodr/TinyXML/tinystr.h


+ 0 - 0
src/driver/driver_map_xodrload/TinyXML/tinyxml.cpp → src/common/common/xodr/TinyXML/tinyxml.cpp


+ 0 - 0
src/driver/driver_map_xodrload/TinyXML/tinyxml.h → src/common/common/xodr/TinyXML/tinyxml.h


+ 0 - 0
src/driver/driver_map_xodrload/TinyXML/tinyxmlerror.cpp → src/common/common/xodr/TinyXML/tinyxmlerror.cpp


+ 0 - 0
src/driver/driver_map_xodrload/TinyXML/tinyxmlparser.cpp → src/common/common/xodr/TinyXML/tinyxmlparser.cpp


+ 0 - 0
src/driver/driver_map_xodrload/OpenDrive/ObjectSignal.cpp


+ 0 - 28
src/driver/driver_map_xodrload/OpenDrive/ObjectSignal.h

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