Browse Source

change odtolanelet.

yuchuli 2 years ago
parent
commit
99dace258b

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

@@ -717,6 +717,29 @@ bool OpenDriveXmlParser::ReadLateralProfile (Road* road, TiXmlElement *node)
 		subNode=subNode->NextSiblingElement("superelevation");
 	}
 
+    subNode=node->FirstChildElement("shape");
+    double t;
+    while (subNode)
+    {
+        int checker=TIXML_SUCCESS;
+        checker+=subNode->QueryDoubleAttribute("s",&s);
+        checker+=subNode->QueryDoubleAttribute("t",&t);
+        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 Shape attributes"<<endl;
+            return false;
+        }
+
+        road->AddShape(s,t,a,b,c,d);
+
+        subNode=subNode->NextSiblingElement("shape");
+    }
+
 	subNode=node->FirstChildElement("crossfall");
 	string side;
 	while (subNode)

+ 40 - 1
src/common/common/xodr/OpenDrive/OpenDriveXmlWriter.cpp

@@ -584,7 +584,7 @@ bool OpenDriveXmlWriter::WriteElevationProfile (TiXmlElement *node, Road* road)
 
 bool OpenDriveXmlWriter::WriteLateralProfile (TiXmlElement *node, Road* road)
 {
-	double s, a, b, c, d;
+    double s, t, a, b, c, d;
 	string side;
 
 	TiXmlElement* nodeLateralProfile = new TiXmlElement("lateralProfile");
@@ -624,6 +624,45 @@ bool OpenDriveXmlWriter::WriteLateralProfile (TiXmlElement *node, Road* road)
 		nodeSuperElevation->SetAttribute("d",sd.str());
 	}
 
+    unsigned int lShapeCount = road->GetShapeCount();
+    for(unsigned int i=0; i<lShapeCount; i++)
+    {
+        Shape *lShape = road->GetShape(i);
+        s=lShape->GetS();
+        t=lShape->GetT();
+        a=lShape->GetA();
+        b=lShape->GetB();
+        c=lShape->GetC();
+        d=lShape->GetD();
+
+        TiXmlElement *nodeShape = new TiXmlElement("shape");
+        nodeLateralProfile->LinkEndChild(nodeShape);
+
+        std::stringstream ss;
+        ss << setprecision(16) << setiosflags (ios_base::scientific) << s;
+        nodeShape->SetAttribute("s",ss.str());
+
+        std::stringstream st;
+        st << setprecision(16) << setiosflags (ios_base::scientific) << t;
+        nodeShape->SetAttribute("t",ss.str());
+
+        std::stringstream sa;
+        sa << setprecision(16) << setiosflags (ios_base::scientific) << a;
+        nodeShape->SetAttribute("a",sa.str());
+
+        std::stringstream sb;
+        sb << setprecision(16) << setiosflags (ios_base::scientific) << b;
+        nodeShape->SetAttribute("b",sb.str());
+
+        std::stringstream sc;
+        sc << setprecision(16) << setiosflags (ios_base::scientific) << c;
+        nodeShape->SetAttribute("c",sc.str());
+
+        std::stringstream sd;
+        sd << setprecision(16) << setiosflags (ios_base::scientific) << d;
+        nodeShape->SetAttribute("d",sd.str());
+    }
+
 
 	unsigned int lCrossfallCount = road->GetCrossfallCount();
 	for(unsigned int i=0; i<lCrossfallCount; i++)

+ 107 - 0
src/common/common/xodr/OpenDrive/OtherStructures.cpp

@@ -88,3 +88,110 @@ double ThirdOrderPolynom::GetValue(double s_check)
 	return value;
 }
 //----------------------------------------------------------------------------------
+
+
+//***********************************************************************************
+//Polynom of 2D 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
+ */
+Third2DOrderPolynom::Third2DOrderPolynom (double s, double t,double a, double b, double c, double d)
+{
+    mS=s;mT=t; mA=a; mB=b; mC=c; mD=d;
+}
+
+/**
+ * Getters for base properties
+ */
+double Third2DOrderPolynom::GetS()
+{
+    return mS;
+}
+double Third2DOrderPolynom::GetT()
+{
+    return mT;
+}
+double Third2DOrderPolynom::GetA()
+{
+    return mA;
+}
+double Third2DOrderPolynom::GetB()
+{
+    return mB;
+}
+double Third2DOrderPolynom::GetC()
+{
+    return mC;
+}
+
+double Third2DOrderPolynom::GetD()
+{
+    return mD;
+}
+
+/**
+ * Setters for base properties
+ */
+void Third2DOrderPolynom::SetS(double s)
+{
+    mS=s;
+}
+void Third2DOrderPolynom::SetT(double t)
+{
+    mT=t;
+}
+void Third2DOrderPolynom::SetA(double a)
+{
+    mA=a;
+}
+void Third2DOrderPolynom::SetB(double b)
+{
+    mB=b;
+}
+void Third2DOrderPolynom::SetC(double c)
+{
+    mC=c;
+}
+void Third2DOrderPolynom::SetD(double d)
+{
+    mD=d;
+}
+
+
+/**
+ * Method to check if sample S is inside the record interval
+ */
+bool Third2DOrderPolynom::CheckInterval (double s_check,double t_check)
+{
+    if (s_check>=mS)
+    {
+        if(t_check>=mT)
+        {
+            return true;
+        }
+        else
+        {
+            return false;
+        }
+    }
+    else
+        return false;
+}
+
+/**
+ * Returns the value at sample S
+ */
+double Third2DOrderPolynom::GetValue(double t_check)
+{
+    double dt = t_check-mT;
+    double value = mA+ mB*dt+ mC*dt*dt + mD*dt*dt*dt;
+    return value;
+}
+//----------------------------------------------------------------------------------

+ 63 - 0
src/common/common/xodr/OpenDrive/OtherStructures.h

@@ -62,5 +62,68 @@ public:
 //----------------------------------------------------------------------------------
 
 
+/**
+ * Polynom of 2D third order
+ *
+ */
+
+
+class Third2DOrderPolynom
+{
+protected:
+    double mS;
+    double mT;
+    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
+     */
+    Third2DOrderPolynom (double s, double t, double a, double b, double c, double d);
+
+
+    /**
+     * Setters for base properties
+     */
+    void SetS(double s);
+    void SetT(double t);
+    void SetA(double a);
+    void SetB(double b);
+    void SetC(double c);
+    void SetD(double d);
+
+
+    /**
+     * Getters for base properties
+     */
+    double GetS();
+    double GetT();
+    double GetA();
+    double GetB();
+    double GetC();
+    double GetD();
+
+
+    /**
+     * Method to check if sample S is inside the record interval
+     */
+    bool CheckInterval (double s_check,double t_check);
+
+    /**
+     * Returns the value at sample S
+     */
+    double GetValue(double t_check);
+
+};
+//----------------------------------------------------------------------------------
+
 
 #endif

+ 117 - 0
src/common/common/xodr/OpenDrive/Road.cpp

@@ -66,6 +66,7 @@ Road::Road (const Road& road)
     mRoadNoavoidVector = road.mRoadNoavoidVector;
     mSurfaceCRGVector = road.mSurfaceCRGVector;
     mRoadPriorityVector = road.mRoadPriorityVector;
+    mShapeVector = road.mShapeVector;
 
 }
 
@@ -113,6 +114,7 @@ const Road& Road::operator=(const Road& otherRoad)
         mRoadNoavoidVector = otherRoad.mRoadNoavoidVector;
         mSurfaceCRGVector = otherRoad.mSurfaceCRGVector;
         mRoadPriorityVector = otherRoad.mRoadPriorityVector;
+        mShapeVector = otherRoad.mShapeVector;
 	}
 	return *this;
 }
@@ -245,6 +247,22 @@ unsigned int Road::GetElevationCount()
 {
 	return mElevationVector.size();
 }
+// Road Shape records
+vector<Shape> *Road::GetShapeVector()
+{
+    return &mShapeVector;
+}
+Shape*	Road::GetShape(unsigned int i)
+{
+    if ((mShapeVector.size()>0)&&(i<mShapeVector.size()))
+        return &mShapeVector.at(i);
+    else
+        return NULL;
+}
+unsigned int Road::GetShapeCount()
+{
+    return static_cast<unsigned int>(mShapeVector.size()) ;
+}
 // Road superelevation records
 vector<SuperElevation> *Road::GetSuperElevationVector()
 {
@@ -525,6 +543,13 @@ Elevation*	Road::GetLastElevation()
 	else
 		return NULL;
 }
+Shape*      Road::GetLastShape()
+{
+    if(mShapeVector.size()>0)
+        return &mShapeVector.at(mShapeVector.size()-1);
+    else
+        return  NULL;
+}
 SuperElevation*	Road::GetLastSuperElevation()
 {	
 	if (mSuperElevationVector.size()>0)
@@ -647,6 +672,13 @@ Elevation* Road::GetLastAddedElevation()
 	else
 		return NULL;
 }
+Shape*     Road::GetLastAddedShape()
+{
+    if(mLastAddedShape<mShapeVector.size())
+        return &mShapeVector.at(mLastAddedShape);
+    else
+        return NULL;
+}
 SuperElevation* Road::GetLastAddedSuperElevation()
 {
 	if(mLastAddedSuperElevation<mSuperElevationVector.size())
@@ -882,6 +914,17 @@ unsigned int Road::AddElevation(double s, double a, double b, double c, double d
 	return index;
 }
 //-------------
+unsigned int Road::AddShape(double s, double t, double a, double b, double c, double d)
+{
+    // Check the first method in the group for details
+
+    unsigned int index = CheckShapeInterval(s,t)+1;
+    if(index>=GetShapeCount()) mShapeVector.push_back(Shape(s,t,a,b,c,d));
+    else mShapeVector.insert(mShapeVector.begin()+index, Shape(s,t,a,b,c,d));
+    mLastAddedShape=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
@@ -1048,6 +1091,17 @@ unsigned int Road::CloneElevation(unsigned int index)
 	mLastAddedElevation=index+1;
 	return mLastAddedElevation;
 }
+unsigned int Road::CloneShape(unsigned int index)
+{
+    // Check the first method in the group for details
+
+    if(index<mShapeVector.size()-1)
+        mShapeVector.insert(mShapeVector.begin()+index+1, mShapeVector[index]);
+    else if(index==mShapeVector.size()-1)
+        mShapeVector.push_back(mShapeVector[index]);
+    mLastAddedShape=index+1;
+    return mLastAddedShape;
+}
 unsigned int Road::CloneSuperElevation(unsigned int index)
 {
 	// Check the first method in the group for details
@@ -1287,6 +1341,10 @@ void Road::DeleteElevation(unsigned int index)
 {
 	mElevationVector.erase(mElevationVector.begin()+index);
 }
+void Road::DeleteShape(unsigned int index)
+{
+    mShapeVector.erase(mShapeVector.begin()+index);
+}
 void Road::DeleteSuperElevation(unsigned int index)
 {
 	mSuperElevationVector.erase(mSuperElevationVector.begin()+index);
@@ -1585,6 +1643,33 @@ double  Road::GetElevationValue (double s_check)
 		retVal= (mElevationVector.at(index).GetValue(s_check));
 	return retVal;
 
+}
+//-----------
+int  Road::CheckShapeInterval(double s_check,double t_check)
+{
+    int res=-1;
+    //Go through all the road type records
+    for (unsigned int i=0;i<mShapeVector.size();i++)
+    {
+        //check if the s_check belongs to the current record
+        if (mShapeVector.at(i).CheckInterval(s_check,t_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::GetShapeValue (double s_check,double t_check)
+{
+    double retVal=0;
+    //find the record where s_check belongs
+    int index=CheckShapeInterval(s_check,t_check);
+    //If found, return the type
+    if (index>=0)
+        retVal= (mShapeVector.at(index).GetValue(t_check));
+    return retVal;
+
 }
 //-----------
 int  Road::CheckSuperElevationInterval(double s_check)
@@ -2351,7 +2436,29 @@ double Road::GetDis(const double x,const double y, const double hdg, double & fR
 }
 
 
+short int Road::GetLaneCoords(double s_check, double t_check,double &retX, double &retY, double &retZ,double &retHDG)
+{
+    short int nrtn;
+    double fRefX,fRefY,fRefHDG;
+    nrtn = GetGeometryCoords(s_check,fRefX,fRefY,fRefHDG);
+    if(nrtn<0)
+    {
+        return nrtn;
+    }
+
+    double fOffValue = GetLaneOffsetValue(s_check);
+
+    double fSuperElevationValue = GetSuperElevationValue(s_check);
+
+    retX = fRefX + t_check*cos(fSuperElevationValue)*cos(retHDG + M_PI/2.0) + fOffValue;
+    retY = fRefY + t_check*cos(fSuperElevationValue)*sin(retHDG + M_PI/2.0) + fOffValue;
+
+    double fElevation = GetElevationValue(s_check);
 
+    retZ = fElevation + t_check*sin(fSuperElevationValue) + GetShapeValue(s_check,t_check);
+
+    return nrtn;
+}
 
 //-------------------------------------------------
 
@@ -2643,6 +2750,16 @@ SuperElevation::SuperElevation(double s, double a, double b, double c, double d)
 {}
 
 
+//***********************************************************************************
+//Shape record
+//***********************************************************************************
+/**
+ * Constructor which intializes the basic properties
+ */
+Shape::Shape(double s, double t, double a, double b, double c, double d): Third2DOrderPolynom(s,t,a,b,c,d)
+{}
+
+
 
 
 

+ 32 - 0
src/common/common/xodr/OpenDrive/Road.h

@@ -34,6 +34,7 @@ class LaneOffset;
 //objects, signals
 class Object;
 class Signal;
+class Shape;
 
 //--------------
 
@@ -75,6 +76,8 @@ private:
 	vector<Elevation> mElevationVector;
 	// Superelevation vector
 	vector<SuperElevation> mSuperElevationVector;
+    // Shape vector
+    vector<Shape> mShapeVector;
 	// Crossfall vector
 	vector<Crossfall> mCrossfallVector;
 	// Lane Section vector
@@ -127,6 +130,7 @@ private:
     unsigned int mLastAddedRoadNoavoid;
     unsigned int mLastAddedSurfaceCRG;
     unsigned int mLastAddedRailroadSwitch;
+    unsigned int mLastAddedShape;
 
 public:
 	/**
@@ -187,6 +191,10 @@ public:
 	vector<Elevation> *GetElevationVector();
 	Elevation*	GetElevation(unsigned int i);
 	unsigned int GetElevationCount();
+    // Road Shape records
+    vector<Shape> *GetShapeVector();
+    Shape*	GetShape(unsigned int i);
+    unsigned int GetShapeCount();
 	// Road superelevation records
 	vector<SuperElevation> *GetSuperElevationVector();
 	SuperElevation*	GetSuperElevation(unsigned int i);
@@ -255,6 +263,7 @@ public:
 	RoadType*		GetLastRoadType();
 	GeometryBlock*	GetLastGeometryBlock();
 	Elevation*		GetLastElevation();
+    Shape*          GetLastShape();
     SuperElevation*	GetLastSuperElevation();
 	Crossfall*		GetLastCrossfall();
 	LaneSection*	GetLastLaneSection();
@@ -275,6 +284,7 @@ public:
 	RoadType*		GetLastAddedRoadType();
 	GeometryBlock*	GetLastAddedGeometryBlock();
 	Elevation*		GetLastAddedElevation();
+    Shape*          GetLastAddedShape();
 	SuperElevation*	GetLastAddedSuperElevation();
 	Crossfall*		GetLastAddedCrossfall();
 	LaneSection*	GetLastAddedLaneSection();
@@ -325,6 +335,7 @@ public:
     unsigned int AddRoadType(double s, string type,string country = "");
 	unsigned int AddGeometryBlock();
 	unsigned int AddElevation(double s, double a, double b, double c, double d);
+    unsigned int AddShape(double s, double t, 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);
@@ -346,6 +357,7 @@ public:
 	 */
 	unsigned int CloneRoadType(unsigned int index);
 	unsigned int CloneElevation(unsigned int index);
+    unsigned int CloneShape(unsigned int index);
 	unsigned int CloneSuperElevation(unsigned int index);
 	unsigned int CloneCrossfall(unsigned int index);
 	unsigned int CloneLaneSection(unsigned int index);
@@ -367,6 +379,7 @@ public:
 	void DeleteRoadType(unsigned int index);
 	void DeleteGeometryBlock(unsigned int index);
 	void DeleteElevation(unsigned int index);
+    void DeleteShape(unsigned int index);
 	void DeleteSuperElevation(unsigned int index);
 	void DeleteCrossfall(unsigned int index);
 	void DeleteLaneSection(unsigned int index);
@@ -418,6 +431,9 @@ public:
 	int CheckElevationInterval(double s_check);
 	double GetElevationValue (double s_check);
 
+    int CheckShapeInterval(double s_check,double t_check);
+    double GetShapeValue(double s_check,double t_check);
+
 	int CheckSuperElevationInterval(double s_check);
 	double GetSuperElevationValue (double s_check);
 
@@ -469,6 +485,8 @@ public:
 
     double GetDis(const double x,const double y, const double hdg, double & fRefDis, double & fHdgDiff, int & nlane,double & s,double & refx,double & refy,double & refhdg); //fRefDis distance to reference line,  nlane if dis is 0, nlane which lane is distance is 0
 
+    short int GetLaneCoords(double s_check, double t_check,double &retX, double &retY, double &retZ,double &retHDG);
+
 	
 	//-------------------------------------------------
 
@@ -690,6 +708,20 @@ public:
 };
 //----------------------------------------------------------------------------------
 
+
+/**
+ * Shape Class is used to store information about a road shape record
+ * It inherits the Polynom class and has no additional properties
+ *
+ *
+ */
+class Shape : public  Third2DOrderPolynom
+{
+public:
+    Shape(double s,double t,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

+ 31 - 18
src/map/odtolanelet/roadsample.cpp

@@ -52,7 +52,7 @@ int RoadSample::SampleRoad(Road * pRoad)
             xRP.mfLaneOffValue = fOffsetValue;
 
             std::vector<LanePoint> xvectorLanePoint;
-            SampleLanePoint(pRoad,pLS,fS,fRefX,fRefY,fRefZ,fRefHdg,fOffsetValue,xvectorLanePoint);
+            SampleLanePoint(pRoad,pLS,fS,xvectorLanePoint);
 
             bool bInserPoint = false;
 
@@ -93,11 +93,9 @@ int RoadSample::SampleRoad(Road * pRoad)
     return 0;
 }
 
-int RoadSample::SampleLanePoint(Road * pRoad,LaneSection * pLS, double fS,double fRefX,double fRefY,double fRefZ,double fRefHdg,double fLaneOffValue,std::vector<LanePoint> & xvectorLanePoint)
+int RoadSample::SampleLanePoint(Road * pRoad,LaneSection * pLS, double fS,std::vector<LanePoint> & xvectorLanePoint)
 {
-    Lane * pLane;
 
-    unsigned int nLaneCount = pLS->GetLaneCount();
     unsigned int nLeftLaneCount = pLS->GetLeftLaneCount();
     unsigned int nRightLaneCount = pLS->GetRightLaneCount();
 
@@ -119,49 +117,64 @@ int RoadSample::SampleLanePoint(Road * pRoad,LaneSection * pLS, double fS,double
         return -2;
     }
 
-    std::vector<double> xvectorLeftLaneOff;
-    std::vector<double> xvecorRightLaneOff;
+    std::vector<double> xvectorLeftLaneT;
+    std::vector<double> xvectorRightLaneT;
 
     unsigned int i;
     for(i=0;i<nLeftLaneCount;i++)
     {
         unsigned int j;
-        double fValue = fLaneOffValue + xLeftWidth[nLeftLaneCount-i-1];
+        double fValue = xLeftWidth[nLeftLaneCount-i-1];
         for(j=(nLeftLaneCount-i-1);j>0;j--)
         {
             fValue = fValue + xLeftWidth[j-1];
         }
-        xvectorLeftLaneOff.push_back(fValue);
+        xvectorLeftLaneT.push_back(fValue);
     }
 
     for(i=0;i<nRightLaneCount;i++)
     {
         unsigned int j;
-        double fValue = fLaneOffValue;
+        double fValue = 0;
         for(j=0;j<=i;j++)
         {
             fValue = fValue - xRightWidth[j];
         }
-        xvecorRightLaneOff.push_back(fValue);
+        xvectorRightLaneT.push_back(fValue);
     }
 
 
+    iv::LanePoint xLanePoint;
     for(i=0;i<nLeftLaneCount;i++)
-    {
-        iv::LanePoint xLanePoint;
-        xLanePoint.mx = fRefX + xvectorLeftLaneOff[i]*cos(fRefHdg + M_PI/2.0);
-        xLanePoint.my = fRefY + xvectorLeftLaneOff[i]*sin(fRefHdg + M_PI/2.0);
-        xLanePoint.mz = fRefZ;
-        xLanePoint.mhdg = fRefHdg;
-
+    {      
+        pRoad->GetLaneCoords(fS,xvectorLeftLaneT[i],xLanePoint.mx,xLanePoint.my,xLanePoint.mz,xLanePoint.mhdg);
         LaneRoadMark xRoadMark = pRoad->GetLaneRoadMarkValue(fS,static_cast<int>(i));
         xLanePoint.mfmarkwidth = xRoadMark.GetWidth();
         xLanePoint.mstrroadmarkcolor = xRoadMark.GetColor();
         xLanePoint.mstrroadmarktype = xRoadMark.GetType();
-
         xLanePoint.nLane = static_cast<int>(i);
         xLanePoint.mstrLaneType = pLS->GetLeftLaneAt(i)->GetType();
+        xvectorLanePoint.push_back(xLanePoint);
+    }
+
+    pRoad->GetLaneCoords(fS,0,xLanePoint.mx,xLanePoint.my,xLanePoint.mz,xLanePoint.mhdg);
+    LaneRoadMark xRoadMark = pRoad->GetLaneRoadMarkValue(fS,0);
+    xLanePoint.mfmarkwidth = xRoadMark.GetWidth();
+    xLanePoint.mstrroadmarkcolor = xRoadMark.GetColor();
+    xLanePoint.mstrroadmarktype = xRoadMark.GetType();
+    xLanePoint.nLane = static_cast<int>(i);
+    xLanePoint.mstrLaneType = pLS->GetLeftLaneAt(i)->GetType();
+    xvectorLanePoint.push_back(xLanePoint);
 
+    for(i=0;i<nRightLaneCount;i++)
+    {
+        pRoad->GetLaneCoords(fS,xvectorRightLaneT[i],xLanePoint.mx,xLanePoint.my,xLanePoint.mz,xLanePoint.mhdg);
+        LaneRoadMark xRoadMark = pRoad->GetLaneRoadMarkValue(fS,static_cast<int>(i)*(-1));
+        xLanePoint.mfmarkwidth = xRoadMark.GetWidth();
+        xLanePoint.mstrroadmarkcolor = xRoadMark.GetColor();
+        xLanePoint.mstrroadmarktype = xRoadMark.GetType();
+        xLanePoint.nLane = static_cast<int>(i);
+        xLanePoint.mstrLaneType = pLS->GetLeftLaneAt(i)->GetType();
         xvectorLanePoint.push_back(xLanePoint);
     }
 

+ 5 - 1
src/map/odtolanelet/roadsample.h

@@ -12,6 +12,8 @@ namespace iv
 struct LanePoint
 {
 public:
+
+    //
     int nLane; // 1 left 1   0 center lane   -1 right lane1
     double mx;
     double my;
@@ -19,11 +21,13 @@ public:
     double mhdg;
     std::string mstrroadmarktype = "none";
     std::string mstrroadmarkcolor = "standard";
+    bool mbMarkVisable = false; //IF solid all is visialbe, if broken mark type  6-9   2-4 3-6  if motor way is 6-9 or 3-6 other 2-4
     double mfroadmarkwidth;
 
     double mfLaneWidth;
     double mfmarkwidth;
     std::string mstrLaneType;  //if nlane = 0 center lane, lanetype is not valid.
+
 };
 
 struct RoadPoint
@@ -61,7 +65,7 @@ private:
     int SampleRoad(Road * pRoad);
 
 
-    int SampleLanePoint(Road * pRoad,LaneSection * pLS, double fS,double fRefX,double fRefY,double fRefZ,double fRefHdg,double fLaneOffValue,std::vector<LanePoint> & xvectorLanePoint);
+    int SampleLanePoint(Road * pRoad,LaneSection * pLS, double fS,std::vector<LanePoint> & xvectorLanePoint);
 };
 
 }