odtolanelet.cpp 9.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303
  1. #include "odtolanelet.h"
  2. #include <vector>
  3. #include "gaussprojector.h"
  4. namespace iv
  5. {
  6. }
  7. odtolanelet::odtolanelet(std::string strxodrfile)
  8. {
  9. mstrxodrfile = strxodrfile;
  10. }
  11. int odtolanelet::ConvertToLanelet(std::string strlanelet2file)
  12. {
  13. OpenDrive * pxodr = new OpenDrive(); //because add to xodr,so don't delete
  14. OpenDriveXmlParser x(pxodr);
  15. if(!x.ReadFile(mstrxodrfile))
  16. {
  17. std::cout<<"Can't load xodr file."<<std::endl;
  18. return -1;
  19. }
  20. lanelet::LaneletMapPtr laneletMap = std::make_shared<lanelet::LaneletMap>();
  21. unsigned int nroadnum = pxodr->GetRoadCount();
  22. unsigned int i;
  23. for(i=0;i<nroadnum;i++)
  24. {
  25. Road * pRoad = pxodr->GetRoad(i);
  26. lanelet::Lanelet let;
  27. if(Road2Lanelet(pRoad,laneletMap) == 0)
  28. {
  29. }
  30. }
  31. lanelet::Origin origin2({39.1364713, 117.0866293, 0});
  32. lanelet::write(strlanelet2file,*laneletMap,GaussProjector(origin2));
  33. std::cout<<"convert complete."<<std::endl;
  34. // lanelet::write(strlanelet2file,*laneletMap,origin2);
  35. return 0;
  36. }
  37. int odtolanelet::Road2Lanelet(Road * pRoad,lanelet::LaneletMapPtr & laneletMap)
  38. {
  39. if(pRoad == NULL)
  40. {
  41. std::cout<<"odtolanelet::Road2Lanelet Road is NULL. "<<std::endl;
  42. return -1;
  43. }
  44. std::shared_ptr<iv::RoadSample> pSample_ptr = std::shared_ptr<iv::RoadSample>(new iv::RoadSample(pRoad));
  45. // iv::RoadSample * pSample = new iv::RoadSample(pRoad);
  46. std::vector<iv::RoadPoint> * pvectorRoadPoint = pSample_ptr->GetRoadPointVector();
  47. unsigned int nRPSize = static_cast<unsigned int>(pvectorRoadPoint->size());
  48. unsigned int i;
  49. std::vector<lanelet::LineString3d> xvectorlinestring;
  50. std::vector<lanelet::Point3d> xvectorPoint;
  51. std::vector<lanelet::Point3d> xvectorLastPoint;
  52. unsigned int ncenterlanepos = 0;
  53. for(i=0;i<nRPSize;i++)
  54. {
  55. bool bNewLet = false;
  56. if(i == 0)
  57. {
  58. bNewLet = true;
  59. }
  60. else
  61. {
  62. if(pvectorRoadPoint->at(i).nSecNum != pvectorRoadPoint->at(i-1).nSecNum)
  63. {
  64. //Create LaneLet
  65. linetolet(laneletMap,xvectorlinestring,ncenterlanepos);
  66. bNewLet = true;
  67. }
  68. }
  69. if(bNewLet)
  70. {
  71. xvectorlinestring.clear();
  72. unsigned int nlanesize = static_cast<unsigned int>(pvectorRoadPoint->at(i).mvectorLanePoint.size());
  73. unsigned int j;
  74. for(j=0;j<nlanesize;j++)
  75. {
  76. lanelet::LineString3d xline;
  77. xline.setId(mid);mid++;
  78. odtypetolettype(pvectorRoadPoint->at(i).mvectorLanePoint[j],xline);
  79. xvectorlinestring.push_back(xline);
  80. if(pvectorRoadPoint->at(i).mvectorLanePoint[j].nLane == 0)
  81. {
  82. ncenterlanepos = j;
  83. }
  84. }
  85. if(i== 0)
  86. {
  87. LanePointToPoint3D(pvectorRoadPoint->at(i).mvectorLanePoint,xvectorPoint);
  88. unsigned int nlanesize = static_cast<unsigned int>(pvectorRoadPoint->at(i).mvectorLanePoint.size());
  89. unsigned int j;
  90. for(j=0;j<nlanesize;j++)xvectorlinestring[j].push_back(xvectorPoint[j]);
  91. }
  92. else
  93. {
  94. LanePointToPoint3DWithLast(pvectorRoadPoint->at(i).mvectorLanePoint,xvectorPoint,xvectorLastPoint);
  95. unsigned int nlanesize = static_cast<unsigned int>(pvectorRoadPoint->at(i).mvectorLanePoint.size());
  96. unsigned int j;
  97. for(j=0;j<nlanesize;j++)xvectorlinestring[j].push_back(xvectorPoint[j]);
  98. }
  99. }
  100. else
  101. {
  102. LanePointToPoint3D(pvectorRoadPoint->at(i).mvectorLanePoint,xvectorPoint);
  103. unsigned int nlanesize = static_cast<unsigned int>(pvectorRoadPoint->at(i).mvectorLanePoint.size());
  104. unsigned int j;
  105. for(j=0;j<nlanesize;j++)xvectorlinestring[j].push_back(xvectorPoint[j]);
  106. }
  107. xvectorLastPoint = xvectorPoint;
  108. // pvectorRoadPoint->at(i).mvectorLanePoint
  109. }
  110. if(xvectorlinestring.size()>0)
  111. {
  112. linetolet(laneletMap,xvectorlinestring,ncenterlanepos);
  113. }
  114. return 0;
  115. }
  116. void odtolanelet::odtypetolettype(iv::LanePoint & xLanePoint, lanelet::LineString3d & xlinestring)
  117. {
  118. if(xLanePoint.mstrroadmarkcolor.size()>0)
  119. {
  120. xlinestring.setAttribute("color",lanelet::Attribute(xLanePoint.mstrroadmarkcolor));
  121. }
  122. if(xLanePoint.mstrroadmarktype == "none")
  123. {
  124. xlinestring.setAttribute("type",lanelet::Attribute("virtual"));
  125. return;
  126. }
  127. if(xLanePoint.mstrroadmarktype == "solid")
  128. {
  129. xlinestring.setAttribute("type",lanelet::Attribute("line_thin"));
  130. xlinestring.setAttribute("subtype",lanelet::Attribute("solid"));
  131. return;
  132. }
  133. if(xLanePoint.mstrroadmarktype == "broken")
  134. {
  135. xlinestring.setAttribute("type",lanelet::Attribute("line_thin"));
  136. xlinestring.setAttribute("subtype",lanelet::Attribute("solid"));
  137. return;
  138. }
  139. if(xLanePoint.mstrroadmarktype == "broken")
  140. {
  141. xlinestring.setAttribute("type",lanelet::Attribute("line_thin"));
  142. xlinestring.setAttribute("subtype",lanelet::Attribute("dashed"));
  143. return;
  144. }
  145. if(xLanePoint.mstrroadmarktype == "solid solid")
  146. {
  147. xlinestring.setAttribute("type",lanelet::Attribute("line_thin"));
  148. xlinestring.setAttribute("subtype",lanelet::Attribute("solid_solid"));
  149. return;
  150. }
  151. if(xLanePoint.mstrroadmarktype == "solid broken")
  152. {
  153. xlinestring.setAttribute("type",lanelet::Attribute("line_thin"));
  154. xlinestring.setAttribute("subtype",lanelet::Attribute("solid_dashed"));
  155. return;
  156. }
  157. if(xLanePoint.mstrroadmarktype == "broken solid")
  158. {
  159. xlinestring.setAttribute("type",lanelet::Attribute("line_thin"));
  160. xlinestring.setAttribute("subtype",lanelet::Attribute("dashed_solid"));
  161. return;
  162. }
  163. if(xLanePoint.mstrroadmarktype == "curb")
  164. {
  165. xlinestring.setAttribute("type",lanelet::Attribute("curbstone"));
  166. xlinestring.setAttribute("subtype",lanelet::Attribute("high"));
  167. return;
  168. }
  169. if(xLanePoint.mstrroadmarktype == "edge")
  170. {
  171. xlinestring.setAttribute("type",lanelet::Attribute("road_border"));
  172. return;
  173. }
  174. xlinestring.setAttribute("type",lanelet::Attribute("virtual"));
  175. return;
  176. }
  177. void odtolanelet::LanePointToPoint3D(std::vector<iv::LanePoint> & xvectorLanePoint, std::vector<lanelet::Point3d> & xvectorPoint3D)
  178. {
  179. xvectorPoint3D.clear();
  180. unsigned int i;
  181. unsigned int nLPsize = static_cast<unsigned int>(xvectorLanePoint.size());
  182. for(i=0;i<nLPsize;i++)
  183. {
  184. lanelet::Point3d xPoint(mid,xvectorLanePoint[i].mx,xvectorLanePoint[i].my,xvectorLanePoint[i].mz);
  185. mid++;
  186. xvectorPoint3D.push_back(xPoint);
  187. }
  188. }
  189. void odtolanelet::LanePointToPoint3DWithLast(std::vector<iv::LanePoint> & xvectorLanePoint, std::vector<lanelet::Point3d> & xvectorPoint3D,
  190. std::vector<lanelet::Point3d> & xvectorPoint3DLast)
  191. {
  192. xvectorPoint3D.clear();
  193. unsigned int i;
  194. unsigned int nLPsize = static_cast<unsigned int>(xvectorLanePoint.size());
  195. for(i=0;i<nLPsize;i++)
  196. {
  197. unsigned int j;
  198. unsigned int nLastSize = static_cast<unsigned int>(xvectorPoint3DLast.size());
  199. bool bUseOld = false;
  200. for(j=0;j<nLastSize;j++)
  201. {
  202. if((fabs(xvectorLanePoint[i].mx - xvectorPoint3DLast[j].x())<0.001)&(fabs(xvectorLanePoint[i].my - xvectorPoint3DLast[j].y())<0.001))
  203. {
  204. bUseOld = true;
  205. xvectorPoint3D.push_back(xvectorPoint3DLast[j]);
  206. break;
  207. }
  208. }
  209. if(bUseOld == false)
  210. {
  211. lanelet::Point3d xPoint(mid,xvectorLanePoint[i].mx,xvectorLanePoint[i].my,xvectorLanePoint[i].mz);
  212. mid++;
  213. xvectorPoint3D.push_back(xPoint);
  214. }
  215. }
  216. }
  217. void odtolanelet::linetolet(lanelet::LaneletMapPtr & laneletMap,std::vector<lanelet::LineString3d> & xvectorlinestring, unsigned int ncenterlane)
  218. {
  219. unsigned int i;
  220. unsigned int nsize = static_cast<unsigned int>(xvectorlinestring.size()) ;
  221. for(i=0;i<ncenterlane;i++)
  222. {
  223. lanelet::LineString3d xleft;
  224. lanelet::LineString3d xright ;
  225. InvertLine(xleft,xvectorlinestring[i+1]);
  226. InvertLine(xright,xvectorlinestring[i]);
  227. lanelet::Lanelet xlet(mid,xleft,xright);
  228. mid++;
  229. laneletMap->add(xlet);
  230. }
  231. for(i=ncenterlane;i<(nsize-1);i++)
  232. {
  233. lanelet::Lanelet xlet(mid,xvectorlinestring[i],xvectorlinestring[i+1]);
  234. mid++;
  235. laneletMap->add(xlet);
  236. }
  237. }
  238. int odtolanelet::InvertLine(lanelet::LineString3d & xinvert,lanelet::LineString3d & xraw)
  239. {
  240. xinvert.setId(mid);mid++;
  241. if(xraw.hasAttribute("color"))xinvert.setAttribute("color",xraw.attribute("color"));
  242. if(xraw.hasAttribute("subtype"))xinvert.setAttribute("subtype",xraw.attribute("subtype"));
  243. if(xraw.hasAttribute("type"))xinvert.setAttribute("type",xraw.attribute("type"));
  244. xinvert.clear();
  245. unsigned int npointssize = static_cast<unsigned int >(xraw.size());
  246. unsigned int i;
  247. for(i=0;i<npointssize;i++)
  248. {
  249. xinvert.push_back(xraw[npointssize-1-i]);
  250. }
  251. return 0;
  252. }