|
@@ -181,7 +181,7 @@ int odtolanelet::Road2Lanelet(Road * pRoad,lanelet::LaneletMapPtr & laneletMap)
|
|
|
{
|
|
|
//Create LaneLet
|
|
|
|
|
|
- linetolet(laneletMap,xvectorlinestring,ncenterlanepos,pRoad->GetRoadId(),sstart,send);
|
|
|
+ linetolet(laneletMap,xvectorlinestring,ncenterlanepos,pRoad->GetRoadId(),sstart,send,pRoad);
|
|
|
bNewLet = true;
|
|
|
}
|
|
|
}
|
|
@@ -241,7 +241,7 @@ int odtolanelet::Road2Lanelet(Road * pRoad,lanelet::LaneletMapPtr & laneletMap)
|
|
|
|
|
|
if(xvectorlinestring.size()>0)
|
|
|
{
|
|
|
- linetolet(laneletMap,xvectorlinestring,ncenterlanepos,pRoad->GetRoadId(),sstart,send);
|
|
|
+ linetolet(laneletMap,xvectorlinestring,ncenterlanepos,pRoad->GetRoadId(),sstart,send,pRoad);
|
|
|
}
|
|
|
|
|
|
return 0;
|
|
@@ -349,7 +349,7 @@ void odtolanelet::LanePointToPoint3DWithLast(std::vector<iv::LanePoint> & xvecto
|
|
|
bool bUseOld = false;
|
|
|
for(j=0;j<nLastSize;j++)
|
|
|
{
|
|
|
- if((fabs(xvectorLanePoint[i].mx - xvectorPoint3DLast[j].x())<0.001)&(fabs(xvectorLanePoint[i].my - xvectorPoint3DLast[j].y())<0.001))
|
|
|
+ if((fabs(xvectorLanePoint[i].mx - xvectorPoint3DLast[j].x())<0.001)&&(fabs(xvectorLanePoint[i].my - xvectorPoint3DLast[j].y())<0.001))
|
|
|
{
|
|
|
bUseOld = true;
|
|
|
xvectorPoint3D.push_back(xvectorPoint3DLast[j]);
|
|
@@ -371,7 +371,7 @@ void odtolanelet::LanePointToPoint3DWithLast(std::vector<iv::LanePoint> & xvecto
|
|
|
}
|
|
|
|
|
|
void odtolanelet::linetolet(lanelet::LaneletMapPtr & laneletMap,std::vector<lanelet::LineString3d> & xvectorlinestring, unsigned int ncenterlane,
|
|
|
- std::string strroadid,double sstart,double send)
|
|
|
+ std::string strroadid,double sstart,double send,Road * pRoad)
|
|
|
{
|
|
|
unsigned int i;
|
|
|
unsigned int nsize = static_cast<unsigned int>(xvectorlinestring.size()) ;
|
|
@@ -391,6 +391,13 @@ void odtolanelet::linetolet(lanelet::LaneletMapPtr & laneletMap,std::vector<lane
|
|
|
xlet.setAttribute("speed_limit",lanelet::Attribute("30"));
|
|
|
xlet.setAttribute("subtype",lanelet::Attribute("road"));
|
|
|
xlet.setAttribute("turn_direction",lanelet::Attribute("straight"));
|
|
|
+ RoadTurnDirection::TURNDIRECTION xturn;
|
|
|
+ if(pRoad->GetRoadTurnDirection(xturn) == 1)
|
|
|
+ {
|
|
|
+ if(xturn == RoadTurnDirection::STRAIGHT)xlet.setAttribute("turn_direction",lanelet::Attribute("straight"));
|
|
|
+ if(xturn == RoadTurnDirection::LEFT)xlet.setAttribute("turn_direction",lanelet::Attribute("left"));
|
|
|
+ if(xturn == RoadTurnDirection::RIGHT)xlet.setAttribute("turn_direction",lanelet::Attribute("right"));
|
|
|
+ }
|
|
|
mid++;
|
|
|
laneletMap->add(xlet);
|
|
|
}
|
|
@@ -406,6 +413,13 @@ void odtolanelet::linetolet(lanelet::LaneletMapPtr & laneletMap,std::vector<lane
|
|
|
xlet.setAttribute("speed_limit",lanelet::Attribute("30"));
|
|
|
xlet.setAttribute("subtype",lanelet::Attribute("road"));
|
|
|
xlet.setAttribute("turn_direction",lanelet::Attribute("straight"));
|
|
|
+ RoadTurnDirection::TURNDIRECTION xturn;
|
|
|
+ if(pRoad->GetRoadTurnDirection(xturn) == 1)
|
|
|
+ {
|
|
|
+ if(xturn == RoadTurnDirection::STRAIGHT)xlet.setAttribute("turn_direction",lanelet::Attribute("straight"));
|
|
|
+ if(xturn == RoadTurnDirection::LEFT)xlet.setAttribute("turn_direction",lanelet::Attribute("left"));
|
|
|
+ if(xturn == RoadTurnDirection::RIGHT)xlet.setAttribute("turn_direction",lanelet::Attribute("right"));
|
|
|
+ }
|
|
|
mid++;
|
|
|
laneletMap->add(xlet);
|
|
|
}
|