|
@@ -9,5 +9,114 @@ odtolanelet::odtolanelet(std::string strxodrfile)
|
|
|
int odtolanelet::ConvertToLanelet(std::string strlanelet2file)
|
|
|
{
|
|
|
|
|
|
+
|
|
|
+ OpenDrive * pxodr = new OpenDrive(); //because add to xodr,so don't delete
|
|
|
+ OpenDriveXmlParser x(pxodr);
|
|
|
+ if(!x.ReadFile(strlanelet2file))
|
|
|
+ {
|
|
|
+ std::cout<<"Can't load xodr file."<<std::endl;
|
|
|
+ return -1;
|
|
|
+ }
|
|
|
+
|
|
|
+ unsigned int nroadnum = pxodr->GetRoadCount();
|
|
|
+ unsigned int i;
|
|
|
+ for(i=0;i<nroadnum;i++)
|
|
|
+ {
|
|
|
+ Road * pRoad = pxodr->GetRoad(i);
|
|
|
+ lanelet::Lanelet let;
|
|
|
+ if(Road2Lanelet(pRoad,let) == 0)
|
|
|
+ {
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+ return 0;
|
|
|
+}
|
|
|
+
|
|
|
+int odtolanelet::Road2Lanelet(Road * pRoad,lanelet::Lanelet & LaneLet)
|
|
|
+{
|
|
|
+ if(pRoad == NULL)
|
|
|
+ {
|
|
|
+ std::cout<<"odtolanelet::Road2Lanelet Road is NULL. "<<std::endl;
|
|
|
+ return -1;
|
|
|
+ }
|
|
|
+
|
|
|
+ std::vector<lanelet::LineString3d> xvectorlinestring;
|
|
|
+ std::vector<std::string> xvectortype;
|
|
|
+ std::vector<std::string> xvectorsubtype;
|
|
|
+
|
|
|
+ unsigned int nLSCount = pRoad->GetLaneSectionCount();
|
|
|
+ unsigned int i;
|
|
|
+
|
|
|
+ unsigned nleftcount = 0;
|
|
|
+ unsigned nrightcount = 0;
|
|
|
+
|
|
|
+ double fS = 0;
|
|
|
+ const double fstep = 0.1;
|
|
|
+
|
|
|
+ for(i=0;i<nLSCount;i++)
|
|
|
+ {
|
|
|
+ LaneSection * pLS = pRoad->GetLaneSection(i);
|
|
|
+
|
|
|
+ if(i == 0)
|
|
|
+ {
|
|
|
+ nleftcount = pLS->GetLeftLaneCount();
|
|
|
+ nrightcount = pLS->GetRightLaneCount();
|
|
|
+ unsigned int nline = pLS->GetLeftLaneCount() + pLS->GetRightLaneCount() + 1;
|
|
|
+ unsigned int j;
|
|
|
+
|
|
|
+ for(j=0;j<nline;j++)
|
|
|
+ {
|
|
|
+ lanelet::LineString3d xline;
|
|
|
+ xline.setId(mid);mid++;
|
|
|
+ xvectorlinestring.push_back(xline);
|
|
|
+ xvectortype.clear();
|
|
|
+ xvectorsubtype.clear();
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ bool bNeedNewLine = false;
|
|
|
+ if((pLS->GetLeftLaneCount() != pRoad->GetLaneSection(i-1)->GetLeftLaneCount())||(pLS->GetRightLaneCount() != pRoad->GetLaneSection(i-1)->GetRightLaneCount()))
|
|
|
+ {
|
|
|
+ bNeedNewLine = true;
|
|
|
+ }
|
|
|
+
|
|
|
+ if(bNeedNewLine)
|
|
|
+ {
|
|
|
+ //Create LaneLet
|
|
|
+
|
|
|
+ nleftcount = pLS->GetLeftLaneCount();
|
|
|
+ nrightcount = pLS->GetRightLaneCount();
|
|
|
+ unsigned int nline = pLS->GetLeftLaneCount() + pLS->GetRightLaneCount() + 1;
|
|
|
+ unsigned int j;
|
|
|
+
|
|
|
+ for(j=0;j<nline;j++)
|
|
|
+ {
|
|
|
+ lanelet::LineString3d xline;
|
|
|
+ xline.setId(mid);mid++;
|
|
|
+ xvectorlinestring.push_back(xline);
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+ fS = pLS->GetS();
|
|
|
+
|
|
|
+ // pLS->GetLane(0)->GetRoadMarkValue(s);
|
|
|
+
|
|
|
+ while(fS<pLS->GetS2())
|
|
|
+ {
|
|
|
+
|
|
|
+ fS = fS + fstep;
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
return 0;
|
|
|
}
|