cdaproc.cpp 38 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884
  1. #include "cdaproc.h"
  2. #include <iostream>
  3. #include <math.h>
  4. static std::string cda_lanetype_sel[9] = {"shoulder","border","driving","stop","none","parking","biking","sidewalk",
  5. "median"};
  6. static std::string cda_lanemarkcolor_sel[2] = {"standard","yellow"};
  7. static std::string cda_lanemarktype_sel[7] = {"broken","solid","broken broken","solid solid","broken solid","solid broken","none"};
  8. CDAProc::CDAProc()
  9. {
  10. }
  11. static void OffRotate(double nowx,double nowy,double nowhdg,double rel_x,double rel_y,double rel_hdg,double & a_x,double & a_y,double & a_hdg)
  12. {
  13. a_x = nowx + rel_x * cos(nowhdg) - rel_y * sin(nowhdg) ;
  14. a_y= nowy + rel_x * sin(nowhdg) + rel_y * cos(nowhdg) ;
  15. a_hdg = rel_hdg+ nowhdg;
  16. if(a_hdg> 2.0*M_PI)a_hdg = a_hdg - 2.0*M_PI;
  17. }
  18. int CDAProc::ProcIntersectionRoad(OpenDrive * pxodr, iv::map::cdadraw * pcdadraw,int ngeo,int & nroadid,double & nowx,double & nowy, double & nowhdg)
  19. {
  20. iv::map::cdageo * pgeo = pcdadraw->mutable_mgeos(ngeo);
  21. double fRoadLen = pgeo->geolen();
  22. // double flanewidth = atof(strlanewidth.data());
  23. std::vector<double> xvectorlanewidth;
  24. int i;
  25. for(i=0;i<pcdadraw->mlanes_size();i++)
  26. {
  27. xvectorlanewidth.push_back(pcdadraw->mutable_mlanes(i)->lanewidth());
  28. }
  29. double flanewidth11 = 0;
  30. for(i=0;i<(pcdadraw->mlanes_size()-1);i++)
  31. {
  32. flanewidth11 = flanewidth11 + xvectorlanewidth[i];
  33. }
  34. int nlanecount = pcdadraw->mlanes_size();
  35. if(nlanecount<=0)
  36. {
  37. std::cout<<" no lane "<<std::endl;
  38. return -1;
  39. }
  40. double fdefradius = 6.0;
  41. double finsectlen = fdefradius*2.0 + 2.0*flanewidth11;
  42. if(fRoadLen < (finsectlen+10.0))
  43. {
  44. fRoadLen = finsectlen + 10.0;
  45. }
  46. double flinelen = (fRoadLen -finsectlen)/2.0;
  47. double flinex[4],fliney[4],flinehdg[4];
  48. flinex[0] = 0;fliney[0]=0;flinehdg[0] = 0;
  49. flinex[1] = fRoadLen*(0.5);fliney[1] = fRoadLen*(-0.5); flinehdg[1] = M_PI/2.0;
  50. flinex[2] = fRoadLen*0.5 + finsectlen*0.5;fliney[2] = 0; flinehdg[2] = 0;
  51. flinex[3] = fRoadLen*(0.5);fliney[3] = finsectlen*0.5; flinehdg[3] = M_PI/2.0;
  52. double flinex_c[4],fliney_c[4],flinehdg_c[4];
  53. double nowx_n,nowy_n,nowhdg_n;
  54. for(i=0;i<4;i++)
  55. {
  56. flinex_c[i] = nowx + flinex[i] * cos(nowhdg) - fliney[i] * sin(nowhdg) ;
  57. fliney_c[i] = nowy + flinex[i] * sin(nowhdg) + fliney[i] * cos(nowhdg) ;
  58. flinehdg_c[i] = flinehdg[i] + nowhdg;
  59. if(flinehdg_c[i]> 2.0*M_PI)flinehdg_c[i] = flinehdg_c[i] - 2.0*M_PI;
  60. char strroadid[100];
  61. nroadid++;
  62. snprintf(strroadid,100,"%d",nroadid);
  63. pxodr->AddRoad("zl",flinelen,strroadid,"-1");
  64. Road * pRoad = pxodr->GetLastAddedRoad();
  65. pRoad->AddGeometryBlock();
  66. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  67. pgeob->AddGeometryLine(0,flinex_c[i],fliney_c[i],flinehdg_c[i],flinelen);
  68. pRoad->AddLaneSection(0);
  69. LaneSection * pLS = pRoad->GetLaneSection(0);
  70. pLS->AddLane(0,0,"none",false);
  71. Lane * pcenterlane = pLS->GetLastAddedLane();
  72. iv::map::cdalanemarkline * pmark = pcdadraw->mutable_mlanemarkline(0);
  73. if(pmark == NULL)
  74. pcenterlane->AddRoadMarkRecord(0,"solid solid","standard","yellow",0.15,"none");
  75. else
  76. {
  77. pcenterlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  78. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  79. if(pmark->lanemarktype() == 0)
  80. {
  81. LaneRoadMark * pLaneRoadMark = pcenterlane->GetLastAddedLaneRoadMark();
  82. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  83. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  84. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  85. }
  86. }
  87. int j;
  88. for(j=0;j<nlanecount;j++)
  89. {
  90. iv::map::cdalane * pcdalane = pcdadraw->mutable_mlanes(j);
  91. pLS->AddLane(-1,(j+1)*(-1),cda_lanetype_sel[pcdalane->lanetype()],false,true);
  92. Lane * pnewlane = pLS->GetLastAddedLane();
  93. pnewlane->AddWidthRecord(0,pcdalane->lanewidth(),0,0,0);
  94. pmark = pcdadraw->mutable_mlanemarkline(j+1);
  95. if(pmark != NULL)
  96. {
  97. pnewlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  98. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  99. if(pmark->lanemarktype() == 0)
  100. {
  101. LaneRoadMark * pLaneRoadMark = pnewlane->GetLastAddedLaneRoadMark();
  102. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  103. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  104. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  105. }
  106. }
  107. pLS->AddLane(1,(j+1)*(1),cda_lanetype_sel[pcdalane->lanetype()],false,true);
  108. pnewlane = pLS->GetLastAddedLane();
  109. pnewlane->AddWidthRecord(0,pcdalane->lanewidth(),0,0,0);
  110. if(pmark != NULL)
  111. {
  112. pnewlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  113. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  114. if(pmark->lanemarktype() == 0)
  115. {
  116. LaneRoadMark * pLaneRoadMark = pnewlane->GetLastAddedLaneRoadMark();
  117. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  118. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  119. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  120. }
  121. }
  122. }
  123. if(i==2)
  124. {
  125. pRoad->GetGeometryCoords(pRoad->GetRoadLength(),nowx_n,nowy_n,nowhdg_n);
  126. }
  127. }
  128. double frightlen = fdefradius * M_PI/2.0;
  129. double frightx[4],frighty[4],frighthdg[4];
  130. frightx[0] = flinelen;frighty[0] = flanewidth11*(-1);frighthdg[0] = 0;
  131. frightx[1] = fRoadLen*0.5 + flanewidth11 ;frighty[1] = finsectlen*(-0.5);frighthdg[1] = M_PI/2.0;
  132. frightx[2] = fRoadLen*0.5 + finsectlen*0.5;frighty[2] = flanewidth11*(1);frighthdg[2] = M_PI;
  133. frightx[3] = fRoadLen*0.5 - flanewidth11;frighty[3] = finsectlen*0.5;frighthdg[3] = 3.0*M_PI/2.0;
  134. for(i=0;i<4;i++)
  135. {
  136. flinex_c[i] = nowx + frightx[i] * cos(nowhdg) - frighty[i] * sin(nowhdg) ;
  137. fliney_c[i] = nowy + frightx[i] * sin(nowhdg) + frighty[i] * cos(nowhdg) ;
  138. flinehdg_c[i] = frighthdg[i] + nowhdg;
  139. if(flinehdg_c[i]> 2.0*M_PI)flinehdg_c[i] = flinehdg_c[i] - 2.0*M_PI;
  140. char strroadid[100];
  141. nroadid++;
  142. snprintf(strroadid,100,"%d",nroadid);
  143. pxodr->AddRoad("zl",flinelen,strroadid,"-1");
  144. Road * pRoad = pxodr->GetLastAddedRoad();
  145. pRoad->AddGeometryBlock();
  146. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  147. pgeob->AddGeometryArc(0,flinex_c[i],fliney_c[i],flinehdg_c[i],frightlen,-1.0/fdefradius);
  148. pRoad->AddLaneSection(0);
  149. LaneSection * pLS = pRoad->GetLaneSection(0);
  150. pLS->AddLane(0,0,"none",false);
  151. // Lane * pcenterlane = pLS->GetLastAddedLane();
  152. // pcenterlane->AddRoadMarkRecord(0,"solid","standard","yellow",0.15,"none");
  153. iv::map::cdalane * pcdalane = pcdadraw->mutable_mlanes(pcdadraw->mlanes_size()-1);
  154. pLS->AddLane(-1,-1,cda_lanetype_sel[pcdalane->lanetype()],false,true);
  155. Lane * pnewlane = pLS->GetLastAddedLane();
  156. pnewlane->AddWidthRecord(0,pcdadraw->mutable_mlanes(pcdadraw->mlanes_size()-1)->lanewidth(),0,0,0);
  157. }
  158. double fleftx[4],flefty[4],flefthdg[4];
  159. fleftx[0] = flinelen;flefty[0] = 0;flefthdg[0] = 0;
  160. fleftx[1] = fRoadLen*0.5;flefty[1] = finsectlen*(-0.5);flefthdg[1] = M_PI/2.0;
  161. fleftx[2] = flinelen+finsectlen;flefty[2] = 0;flefthdg[2] = M_PI;
  162. fleftx[3] = fRoadLen*0.5;flefty[3] = finsectlen*0.5;flefthdg[3] = 3.0*M_PI/2.0;
  163. for(i=0;i<4;i++)
  164. {
  165. double fleftlinelen = 0.5*finsectlen - fdefradius;
  166. double fleftarcx = fleftx[i] + fleftlinelen * cos(flefthdg[i]);
  167. double fleftarcy = flefty[i] + fleftlinelen * sin(flefthdg[i]);
  168. double fleftarchdg = flefthdg[i];
  169. double a_x,a_y,a_hdg;
  170. char strroadid[100];
  171. nroadid++;
  172. snprintf(strroadid,100,"%d",nroadid);
  173. pxodr->AddRoad("zl",fleftlinelen*2.0+fdefradius*M_PI/2.0,strroadid,"-1");
  174. Road * pRoad = pxodr->GetLastAddedRoad();
  175. GeometryBlock * pgeob;
  176. if(fleftlinelen >0.00000000001)
  177. {
  178. pRoad->AddGeometryBlock();
  179. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  180. OffRotate(nowx,nowy,nowhdg,fleftx[i],flefty[i],flefthdg[i],a_x,a_y,a_hdg);
  181. pgeob->AddGeometryLine(0,a_x,a_y,a_hdg,fleftlinelen);
  182. }
  183. pRoad->AddGeometryBlock();
  184. pgeob= pRoad->GetLastAddedGeometryBlock();
  185. OffRotate(nowx,nowy,nowhdg,fleftarcx,fleftarcy,fleftarchdg,a_x,a_y,a_hdg);
  186. pgeob->AddGeometryArc(fleftlinelen,a_x,a_y,a_hdg,fdefradius*M_PI/2.0,1.0/fdefradius);
  187. if(fleftlinelen >0.00000000001)
  188. {
  189. pRoad->AddGeometryBlock();
  190. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  191. OffRotate(nowx,nowy,nowhdg,fleftarcx + fdefradius*cos(flefthdg[i]) + fdefradius*cos(flefthdg[i] + M_PI/2.0) ,
  192. fleftarcy + fdefradius*sin(flefthdg[i]) + fdefradius*sin(flefthdg[i] + M_PI/2.0),flefthdg[i] +M_PI/2.0,a_x,a_y,a_hdg);
  193. pgeob->AddGeometryLine(fleftlinelen + fdefradius*M_PI/2.0,a_x,a_y,a_hdg,fleftlinelen);
  194. }
  195. pRoad->AddLaneSection(0);
  196. LaneSection * pLS = pRoad->GetLaneSection(0);
  197. pLS->AddLane(0,0,"none",false);
  198. // Lane * pcenterlane = pLS->GetLastAddedLane();
  199. // pcenterlane->AddRoadMarkRecord(0,"solid","standard","yellow",0.15,"none");
  200. iv::map::cdalane * pcdalane = pcdadraw->mutable_mlanes(0);
  201. pLS->AddLane(-1,-1,cda_lanetype_sel[pcdalane->lanetype()],false,true);
  202. Lane * pnewlane = pLS->GetLastAddedLane();
  203. pnewlane->AddWidthRecord(0,pcdadraw->mutable_mlanes(0)->lanewidth(),0,0,0);
  204. }
  205. double finlinex[4],finliney[4],finlinehdg[4];
  206. finlinex[0] = flinelen;finliney[0] = 0;finlinehdg[0] = 0;
  207. finlinex[1] = fRoadLen*0.5;finliney[1] = finsectlen*(-0.5);finlinehdg[1] = M_PI/2.0;
  208. finlinex[2] = flinelen+finsectlen;finliney[2] = 0;finlinehdg[2] = M_PI;
  209. finlinex[3] = fRoadLen*0.5;finliney[3] = finsectlen*0.5;finlinehdg[3] = 3.0*M_PI/2.0;
  210. for(i=0;i<4;i++)
  211. {
  212. char strroadid[100];
  213. nroadid++;
  214. snprintf(strroadid,100,"%d",nroadid);
  215. pxodr->AddRoad("zl",flinelen,strroadid,"-1");
  216. Road * pRoad = pxodr->GetLastAddedRoad();
  217. pRoad->AddGeometryBlock();
  218. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  219. double a_x,a_y,a_hdg;
  220. OffRotate(nowx,nowy,nowhdg,finlinex[i],finliney[i],finlinehdg[i],a_x,a_y,a_hdg);
  221. pgeob->AddGeometryLine(0,a_x,a_y,a_hdg,finsectlen);
  222. pRoad->AddLaneSection(0);
  223. LaneSection * pLS = pRoad->GetLaneSection(0);
  224. pLS->AddLane(0,0,"none",false);
  225. // Lane * pcenterlane = pLS->GetLastAddedLane();
  226. // pcenterlane->AddRoadMarkRecord(0,"solid solid","standard","yellow",0.15,"none");
  227. int j;
  228. for(j=0;j<nlanecount;j++)
  229. {
  230. iv::map::cdalane * pcdalane = pcdadraw->mutable_mlanes(j);
  231. pLS->AddLane(-1,(j+1)*(-1),cda_lanetype_sel[pcdalane->lanetype()],false,true);
  232. Lane * pnewlane = pLS->GetLastAddedLane();
  233. pnewlane->AddWidthRecord(0,pcdalane->lanewidth(),0,0,0);
  234. pLS->AddLane(1,(j+1)*(1),cda_lanetype_sel[pcdalane->lanetype()],false,true);
  235. pnewlane = pLS->GetLastAddedLane();
  236. pnewlane->AddWidthRecord(0,pcdalane->lanewidth(),0,0,0);
  237. }
  238. }
  239. nowx = nowx_n;
  240. nowy = nowy_n;
  241. nowhdg = nowhdg_n;
  242. }
  243. int CDAProc::ProcIntersectionRoad(OpenDrive * pxodr, std::string strtype,std::string strradius,std::string strroadlen,std::string strlanewidth,
  244. std::string strlannecount,std::string strlanetype,std::string strlanemarkcolor,std::string strlanemarktype)
  245. {
  246. double fRoadLen = atof(strroadlen.data());
  247. double flanewidth = atof(strlanewidth.data());
  248. int nlanecount = atoi(strlannecount.data());
  249. if(flanewidth<=0)flanewidth = 3.5;
  250. if(nlanecount<=0)nlanecount = 1;
  251. double fdefradius = 6.0;
  252. double finsectlen = fdefradius*2.0 + 2.0*(flanewidth*(nlanecount-1));
  253. if(fRoadLen < (finsectlen+10.0))
  254. {
  255. fRoadLen = finsectlen + 10.0;
  256. }
  257. double flinelen = (fRoadLen -finsectlen)/2.0;
  258. double flinex[4],fliney[4],flinehdg[4];
  259. flinex[0] = 0;fliney[0]=0;flinehdg[0] = 0;
  260. flinex[1] = fRoadLen*(0.5);fliney[1] = fRoadLen*(-0.5); flinehdg[1] = M_PI/2.0;
  261. flinex[2] = fRoadLen*0.5 + finsectlen*0.5;fliney[2] = 0; flinehdg[2] = 0;
  262. flinex[3] = fRoadLen*(0.5);fliney[3] = finsectlen*0.5; flinehdg[3] = M_PI/2.0;
  263. int i;
  264. for(i=0;i<4;i++)
  265. {
  266. char strroadid[100];
  267. snprintf(strroadid,100,"%d",i+1);
  268. pxodr->AddRoad("zl",flinelen,strroadid,"-1");
  269. Road * pRoad = pxodr->GetLastAddedRoad();
  270. pRoad->AddGeometryBlock();
  271. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  272. pgeob->AddGeometryLine(0,flinex[i],fliney[i],flinehdg[i],flinelen);
  273. pRoad->AddLaneSection(0);
  274. LaneSection * pLS = pRoad->GetLaneSection(0);
  275. pLS->AddLane(0,0,"none",false);
  276. Lane * pcenterlane = pLS->GetLastAddedLane();
  277. pcenterlane->AddRoadMarkRecord(0,"solid solid","standard","yellow",0.15,"none");
  278. int j;
  279. for(j=0;j<nlanecount;j++)
  280. {
  281. pLS->AddLane(-1,(j+1)*(-1),"driving",false,true);
  282. Lane * pnewlane = pLS->GetLastAddedLane();
  283. pnewlane->AddWidthRecord(0,flanewidth,0,0,0);
  284. if(j == (nlanecount -1))
  285. {
  286. pnewlane->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"none");
  287. }
  288. else
  289. {
  290. std::string type = "broken";
  291. if(strlanemarktype == "实线")type = "solid";
  292. std::string color = "standard";
  293. if(strlanemarkcolor == "黄色")color = "yellow";
  294. pnewlane->AddRoadMarkRecord(0,type,"standard",color,0.15,"none");
  295. // pnewlane->AddRoadMarkRecord(0,"broken","standard","standard",0.15,"none");
  296. }
  297. pLS->AddLane(1,(j+1)*(1),"driving",false,true);
  298. pnewlane = pLS->GetLastAddedLane();
  299. pnewlane->AddWidthRecord(0,flanewidth,0,0,0);
  300. if(j == (nlanecount -1))
  301. {
  302. pnewlane->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"none");
  303. }
  304. else
  305. {
  306. std::string type = "broken";
  307. if(strlanemarktype == "实线")type = "solid";
  308. std::string color = "standard";
  309. if(strlanemarkcolor == "黄色")color = "yellow";
  310. pnewlane->AddRoadMarkRecord(0,type,"standard",color,0.15,"none");
  311. // pnewlane->AddRoadMarkRecord(0,"broken","standard","standard",0.15,"none");
  312. }
  313. }
  314. }
  315. double frightlen = fdefradius * M_PI/2.0;
  316. double frightx[4],frighty[4],frighthdg[4];
  317. frightx[0] = flinelen;frighty[0] = flanewidth*(nlanecount-1)*(-1);frighthdg[0] = 0;
  318. frightx[1] = fRoadLen*0.5 + flanewidth*(nlanecount-1) ;frighty[1] = finsectlen*(-0.5);frighthdg[1] = M_PI/2.0;
  319. frightx[2] = fRoadLen*0.5 + finsectlen*0.5;frighty[2] = flanewidth*(nlanecount-1)*(1);frighthdg[2] = M_PI;
  320. frightx[3] = fRoadLen*0.5 - flanewidth*(nlanecount-1);frighty[3] = finsectlen*0.5;frighthdg[3] = 3.0*M_PI/2.0;
  321. for(i=0;i<4;i++)
  322. {
  323. char strroadid[100];
  324. snprintf(strroadid,100,"%d",i+5);
  325. pxodr->AddRoad("zl",flinelen,strroadid,"-1");
  326. Road * pRoad = pxodr->GetLastAddedRoad();
  327. pRoad->AddGeometryBlock();
  328. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  329. pgeob->AddGeometryArc(0,frightx[i],frighty[i],frighthdg[i],frightlen,-1.0/fdefradius);
  330. pRoad->AddLaneSection(0);
  331. LaneSection * pLS = pRoad->GetLaneSection(0);
  332. pLS->AddLane(0,0,"none",false);
  333. // Lane * pcenterlane = pLS->GetLastAddedLane();
  334. // pcenterlane->AddRoadMarkRecord(0,"solid","standard","yellow",0.15,"none");
  335. pLS->AddLane(-1,-1,"driving",false,true);
  336. Lane * pnewlane = pLS->GetLastAddedLane();
  337. pnewlane->AddWidthRecord(0,flanewidth,0,0,0);
  338. }
  339. double fleftx[4],flefty[4],flefthdg[4];
  340. fleftx[0] = flinelen;flefty[0] = 0;flefthdg[0] = 0;
  341. fleftx[1] = fRoadLen*0.5;flefty[1] = finsectlen*(-0.5);flefthdg[1] = M_PI/2.0;
  342. fleftx[2] = flinelen+finsectlen;flefty[2] = 0;flefthdg[2] = M_PI;
  343. fleftx[3] = fRoadLen*0.5;flefty[3] = finsectlen*0.5;flefthdg[3] = 3.0*M_PI/2.0;
  344. for(i=0;i<4;i++)
  345. {
  346. double fleftlinelen = 0.5*finsectlen - fdefradius;
  347. double fleftarcx = fleftx[i] + fleftlinelen * cos(flefthdg[i]);
  348. double fleftarcy = flefty[i] + fleftlinelen * sin(flefthdg[i]);
  349. double fleftarchdg = flefthdg[i];
  350. char strroadid[100];
  351. snprintf(strroadid,100,"%d",i+9);
  352. pxodr->AddRoad("zl",fleftlinelen*2.0+fdefradius*M_PI/2.0,strroadid,"-1");
  353. Road * pRoad = pxodr->GetLastAddedRoad();
  354. GeometryBlock * pgeob;
  355. if(fleftlinelen >0.00000000001)
  356. {
  357. pRoad->AddGeometryBlock();
  358. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  359. pgeob->AddGeometryLine(0,fleftx[i],flefty[i],flefthdg[i],fleftlinelen);
  360. }
  361. pRoad->AddGeometryBlock();
  362. pgeob= pRoad->GetLastAddedGeometryBlock();
  363. pgeob->AddGeometryArc(fleftlinelen,fleftarcx,fleftarcy,fleftarchdg,fdefradius*M_PI/2.0,1.0/fdefradius);
  364. if(fleftlinelen >0.00000000001)
  365. {
  366. pRoad->AddGeometryBlock();
  367. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  368. pgeob->AddGeometryLine(fleftlinelen + fdefradius*M_PI/2.0,fleftarcx + fdefradius*cos(flefthdg[i]) + fdefradius*cos(flefthdg[i] + M_PI/2.0) ,
  369. fleftarcy + fdefradius*sin(flefthdg[i]) + fdefradius*sin(flefthdg[i] + M_PI/2.0),flefthdg[i] +M_PI/2.0,fleftlinelen);
  370. }
  371. pRoad->AddLaneSection(0);
  372. LaneSection * pLS = pRoad->GetLaneSection(0);
  373. pLS->AddLane(0,0,"none",false);
  374. // Lane * pcenterlane = pLS->GetLastAddedLane();
  375. // pcenterlane->AddRoadMarkRecord(0,"solid","standard","yellow",0.15,"none");
  376. pLS->AddLane(-1,-1,"driving",false,true);
  377. Lane * pnewlane = pLS->GetLastAddedLane();
  378. pnewlane->AddWidthRecord(0,flanewidth,0,0,0);
  379. }
  380. double finlinex[4],finliney[4],finlinehdg[4];
  381. finlinex[0] = flinelen;finliney[0] = 0;finlinehdg[0] = 0;
  382. finlinex[1] = fRoadLen*0.5;finliney[1] = finsectlen*(-0.5);finlinehdg[1] = M_PI/2.0;
  383. finlinex[2] = flinelen+finsectlen;finliney[2] = 0;finlinehdg[2] = M_PI;
  384. finlinex[3] = fRoadLen*0.5;finliney[3] = finsectlen*0.5;finlinehdg[3] = 3.0*M_PI/2.0;
  385. for(i=0;i<4;i++)
  386. {
  387. char strroadid[100];
  388. snprintf(strroadid,100,"%d",i+13);
  389. pxodr->AddRoad("zl",flinelen,strroadid,"-1");
  390. Road * pRoad = pxodr->GetLastAddedRoad();
  391. pRoad->AddGeometryBlock();
  392. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  393. pgeob->AddGeometryLine(0,finlinex[i],finliney[i],finlinehdg[i],finsectlen);
  394. pRoad->AddLaneSection(0);
  395. LaneSection * pLS = pRoad->GetLaneSection(0);
  396. pLS->AddLane(0,0,"none",false);
  397. // Lane * pcenterlane = pLS->GetLastAddedLane();
  398. // pcenterlane->AddRoadMarkRecord(0,"solid solid","standard","yellow",0.15,"none");
  399. int j;
  400. for(j=0;j<nlanecount;j++)
  401. {
  402. pLS->AddLane(-1,(j+1)*(-1),"driving",false,true);
  403. Lane * pnewlane = pLS->GetLastAddedLane();
  404. pnewlane->AddWidthRecord(0,flanewidth,0,0,0);
  405. // if(j == (nlanecount -1))
  406. // {
  407. // pnewlane->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"none");
  408. // }
  409. // else
  410. // pnewlane->AddRoadMarkRecord(0,"broken","standard","standard",0.15,"none");
  411. pLS->AddLane(1,(j+1)*(1),"driving",false,true);
  412. pnewlane = pLS->GetLastAddedLane();
  413. pnewlane->AddWidthRecord(0,flanewidth,0,0,0);
  414. // if(j == (nlanecount -1))
  415. // {
  416. // pnewlane->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"none");
  417. // }
  418. // else
  419. // pnewlane->AddRoadMarkRecord(0,"broken","standard","standard",0.15,"none");
  420. }
  421. }
  422. return 0;
  423. }
  424. int CDAProc::ProcArcRoad(OpenDrive * pxodr, std::string strtype,std::string strradius,std::string strroadlen,std::string strlanewidth,
  425. std::string strlannecount,std::string strlanetype,std::string strlanemarkcolor,std::string strlanemarktype)
  426. {
  427. double fRoadLen = atof(strroadlen.data());
  428. double fRadius = atof(strradius.data());
  429. if(fabs(fRadius) < 0.000000000000001)return -5;
  430. pxodr->AddRoad("wd",fRoadLen,"1","-1");
  431. Road * pRoad = pxodr->GetLastAddedRoad();
  432. double fArcLen = fabs(fRadius) * M_PI/2.0;
  433. bool bHaveLine = false;
  434. double fxline,fyline,fhdgline,flinelen;
  435. if(fArcLen>=fRoadLen)
  436. {
  437. fArcLen = fRoadLen;
  438. }
  439. else
  440. {
  441. bHaveLine = true;
  442. flinelen = fRoadLen - fArcLen;
  443. fxline = fabs(fRadius);
  444. fyline = fRadius;
  445. fhdgline = (fyline/fxline)*(M_PI/2.0);
  446. }
  447. pRoad->AddGeometryBlock();
  448. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  449. pgeob->AddGeometryArc(0,0,0,0,fArcLen,1.0/fRadius);
  450. if(bHaveLine == true)
  451. {
  452. pRoad->AddGeometryBlock();
  453. pgeob = pRoad->GetLastAddedGeometryBlock();
  454. pgeob->AddGeometryLine(fArcLen,fxline,fyline,fhdgline,flinelen);
  455. }
  456. pRoad->AddLaneSection(0);
  457. LaneSection * pLS = pRoad->GetLaneSection(0);
  458. pLS->AddLane(0,0,"none",false);
  459. Lane * pcenterlane = pLS->GetLastAddedLane();
  460. pcenterlane->AddRoadMarkRecord(0,"solid","standard","yellow",0.15,"none");
  461. int nlanecount = atoi(strlannecount.data());
  462. double flanewidth = atof(strlanewidth.data());
  463. int i;
  464. for(i=0;i<nlanecount;i++)
  465. {
  466. pLS->AddLane(-1,(i+1)*(-1),"driving",false,true);
  467. Lane * pnewlane = pLS->GetLastAddedLane();
  468. pnewlane->AddWidthRecord(0,flanewidth,0,0,0);
  469. if(i == (nlanecount -1))
  470. {
  471. pnewlane->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"none");
  472. }
  473. else
  474. {
  475. std::string type = "broken";
  476. if(strlanemarktype == "实线")type = "solid";
  477. std::string color = "standard";
  478. if(strlanemarkcolor == "黄色")color = "yellow";
  479. pnewlane->AddRoadMarkRecord(0,type,"standard",color,0.15,"none");
  480. // pnewlane->AddRoadMarkRecord(0,"broken","standard","standard",0.15,"none");
  481. }
  482. }
  483. return 0;
  484. }
  485. int CDAProc::ProcLineRoad(OpenDrive * pxodr, std::string strtype,std::string strradius,std::string strroadlen,std::string strlanewidth,
  486. std::string strlannecount,std::string strlanetype,std::string strlanemarkcolor,std::string strlanemarktype)
  487. {
  488. pxodr->AddRoad("zl",atof(strroadlen.data()),"1","-1");
  489. Road * pRoad = pxodr->GetLastAddedRoad();
  490. pRoad->AddGeometryBlock();
  491. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  492. pgeob->AddGeometryLine(0,0,0,0,atof(strroadlen.data()));
  493. pRoad->AddLaneSection(0);
  494. LaneSection * pLS = pRoad->GetLaneSection(0);
  495. pLS->AddLane(0,0,"none",false);
  496. Lane * pcenterlane = pLS->GetLastAddedLane();
  497. pcenterlane->AddRoadMarkRecord(0,"solid","standard","yellow",0.15,"none");
  498. int nlanecount = atoi(strlannecount.data());
  499. double flanewidth = atof(strlanewidth.data());
  500. int i;
  501. for(i=0;i<nlanecount;i++)
  502. {
  503. pLS->AddLane(-1,(i+1)*(-1),"driving",false,true);
  504. Lane * pnewlane = pLS->GetLastAddedLane();
  505. pnewlane->AddWidthRecord(0,flanewidth,0,0,0);
  506. if(i == (nlanecount -1))
  507. {
  508. pnewlane->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"none");
  509. }
  510. else
  511. {
  512. std::string type = "broken";
  513. if(strlanemarktype == "实线")type = "solid";
  514. std::string color = "standard";
  515. if(strlanemarkcolor == "黄色")color = "yellow";
  516. pnewlane->AddRoadMarkRecord(0,type,"standard",color,0.15,"none");
  517. // pnewlane->AddRoadMarkRecord(0,"broken","standard","standard",0.15,"none");
  518. }
  519. }
  520. return 0;
  521. }
  522. int CDAProc::ProcRoad(OpenDrive * pxodr, std::string strtype,std::string strradius,std::string strroadlen,std::string strlanewidth,
  523. std::string strlannecount,std::string strlanetype,std::string strlanemarkcolor,std::string strlanemarktype)
  524. {
  525. if(atof(strroadlen.data())<0.00000001)
  526. {
  527. return -2;
  528. }
  529. if(atof(strlanewidth.data())<0.00000001)
  530. {
  531. return -3;
  532. }
  533. if(atoi(strlannecount.data())<1)
  534. {
  535. return -4;
  536. }
  537. if(strtype == "直路" )
  538. {
  539. std::cout<<" is zl . "<<std::endl;
  540. return ProcLineRoad(pxodr,strtype,strradius,strroadlen,strlanewidth,strlannecount,strlanetype,strlanemarkcolor,strlanemarktype);
  541. }
  542. if(strtype == "弯路" )
  543. {
  544. std::cout<<" is wl . "<<std::endl;
  545. return ProcArcRoad(pxodr,strtype,strradius,strroadlen,strlanewidth,strlannecount,strlanetype,strlanemarkcolor,strlanemarktype);
  546. }
  547. if(strtype == "路口" )
  548. {
  549. std::cout<<" is lk . "<<std::endl;
  550. return ProcIntersectionRoad(pxodr,strtype,strradius,strroadlen,strlanewidth,strlannecount,strlanetype,strlanemarkcolor,strlanemarktype);
  551. }
  552. return -1;
  553. }
  554. int CDAProc::Proc(std::string strxlsxpath,OpenDrive * pxodr)
  555. {
  556. void * pexcel = ServiceExcelAPI.Openxlsx(strxlsxpath);
  557. std::string strtype;
  558. std::string strradius;
  559. std::string strroadlen;
  560. std::string strlanewidth;
  561. std::string strlannecount;
  562. std::string strlanetype;
  563. std::string strlanemarkcolor;
  564. std::string strlanemarktype;
  565. ServiceExcelAPI.getcellvalue(pexcel,119,4,strtype);
  566. ServiceExcelAPI.getcellvalue(pexcel,120,4,strradius);
  567. ServiceExcelAPI.getcellvalue(pexcel,121,4,strroadlen);
  568. ServiceExcelAPI.getcellvalue(pexcel,122,4,strlanewidth);
  569. ServiceExcelAPI.getcellvalue(pexcel,123,4,strlannecount);
  570. // ServiceExcelAPI.getcellvalue(pexcel,124,4,strlanetype);
  571. ServiceExcelAPI.getcellvalue(pexcel,124,4,strlanemarkcolor);
  572. ServiceExcelAPI.getcellvalue(pexcel,125,4,strlanemarktype);
  573. std::cout<<"type : "<<strtype<<std::endl;
  574. ServiceExcelAPI.Closexlsx(pexcel);
  575. return ProcRoad(pxodr,strtype,strradius,strroadlen,strlanewidth,strlannecount,strlanemarktype,strlanemarkcolor,strlanemarktype);
  576. }
  577. #include <QDateTime>
  578. #include <OpenDrive/OpenDriveXmlWriter.h>
  579. int CDAProc::ProcRoads(std::string strxlsxpath,std::string stroutpath)
  580. {
  581. void * pexcel = ServiceExcelAPI.Openxlsx(strxlsxpath);
  582. std::string strtype;
  583. std::string strradius;
  584. std::string strroadlen;
  585. std::string strlanewidth;
  586. std::string strlannecount;
  587. std::string strlanetype;
  588. std::string strlanemarkcolor;
  589. std::string strlanemarktype;
  590. std::string strname;
  591. bool bComplete = false;
  592. int i = 4;
  593. int nr = 0;
  594. while(bComplete == false)
  595. {
  596. strtype = "";
  597. strname = "";
  598. ServiceExcelAPI.getcellvalue(pexcel,26,i,strname);
  599. ServiceExcelAPI.getcellvalue(pexcel,119,i,strtype);
  600. ServiceExcelAPI.getcellvalue(pexcel,120,i,strradius);
  601. ServiceExcelAPI.getcellvalue(pexcel,121,i,strroadlen);
  602. ServiceExcelAPI.getcellvalue(pexcel,122,i,strlanewidth);
  603. ServiceExcelAPI.getcellvalue(pexcel,123,i,strlannecount);
  604. // ServiceExcelAPI.getcellvalue(pexcel,124,4,strlanetype);
  605. ServiceExcelAPI.getcellvalue(pexcel,124,i,strlanemarkcolor);
  606. ServiceExcelAPI.getcellvalue(pexcel,125,i,strlanemarktype);
  607. if((strtype == "")||(strname == ""))
  608. {
  609. bComplete = true;
  610. }
  611. else
  612. {
  613. std::cout<<" name : "<<strname<<" type: "<<strtype<<std::endl;
  614. OpenDrive xxodr;
  615. int nrtn = ProcRoad(&xxodr,strtype,strradius,strroadlen,strlanewidth,strlannecount,strlanemarktype,strlanemarkcolor,strlanemarktype);
  616. if(nrtn == 0)
  617. {
  618. if(xxodr.GetHeader() == NULL)
  619. {
  620. xxodr.SetHeader(1,1,"adcmap",1.1,QDateTime::currentDateTime().toString("yyyy-MM-dd").toLatin1().data(),0,0,0,0,39,117,0);
  621. xxodr.GetHeader()->SetVendor("adc");
  622. }
  623. else
  624. {
  625. xxodr.GetHeader()->SetVendor("adc");
  626. }
  627. OpenDriveXmlWriter x(&xxodr);
  628. std::string strfilepath = stroutpath + "/"+ strname+".xodr";
  629. x.WriteFile(strfilepath);
  630. }
  631. else
  632. {
  633. nr = nr + nrtn;
  634. std::cout<<" Convert row "<<i<<" name: "<<strname<<" fail. fail code : "<<nrtn<<std::endl;
  635. }
  636. }
  637. i++;
  638. }
  639. ServiceExcelAPI.Closexlsx(pexcel);
  640. return nr;
  641. }
  642. int CDAProc::ProcCDA(iv::map::cdadraw & xcdadraw,OpenDrive * pxodr)
  643. {
  644. if(xcdadraw.mgeos_size() == 0)
  645. {
  646. std::cout<<" no geo. "<<std::endl;
  647. return -1;
  648. }
  649. int i;
  650. double xnow,ynow,hdgnow;
  651. xnow = 0;
  652. ynow = 0;
  653. hdgnow = 0;
  654. int nroadid = 0;
  655. for(i=0;i<xcdadraw.mgeos_size();i++)
  656. {
  657. iv::map::cdageo * pgeo = xcdadraw.mutable_mgeos(i);
  658. if(pgeo->geotype() == 0)
  659. {
  660. nroadid++;
  661. char strroadid[256];
  662. snprintf(strroadid,256,"%d",nroadid);
  663. pxodr->AddRoad("zl",pgeo->geolen(),strroadid,"-1");
  664. Road * pRoad = pxodr->GetLastAddedRoad();
  665. pRoad->AddGeometryBlock();
  666. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  667. pgeob->AddGeometryLine(0,xnow,ynow,hdgnow,pgeo->geolen());
  668. pRoad->GetGeometryCoords(pgeo->geolen(),xnow,ynow,hdgnow);
  669. pRoad->AddLaneSection(0);
  670. LaneSection * pLS = pRoad->GetLaneSection(0);
  671. pLS->AddLane(0,0,"none",false);
  672. Lane * pcenterlane = pLS->GetLastAddedLane();
  673. iv::map::cdalanemarkline * pmark = xcdadraw.mutable_mlanemarkline(0);
  674. if(pmark == NULL)
  675. pcenterlane->AddRoadMarkRecord(0,"solid solid","standard","yellow",0.15,"none");
  676. else
  677. {
  678. pcenterlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  679. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  680. if(pmark->lanemarktype() == 0)
  681. {
  682. LaneRoadMark * pLaneRoadMark = pcenterlane->GetLastAddedLaneRoadMark();
  683. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  684. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  685. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  686. }
  687. }
  688. int j;
  689. iv::map::cdadraw * pcdadraw = &xcdadraw;
  690. int nlanecount = pcdadraw->mlanes_size();
  691. for(j=0;j<nlanecount;j++)
  692. {
  693. iv::map::cdalane * pcdalane = pcdadraw->mutable_mlanes(j);
  694. pLS->AddLane(-1,(j+1)*(-1),cda_lanetype_sel[pcdalane->lanetype()],false,true);
  695. Lane * pnewlane = pLS->GetLastAddedLane();
  696. pnewlane->AddWidthRecord(0,pcdalane->lanewidth(),0,0,0);
  697. pmark = xcdadraw.mutable_mlanemarkline(j+1);
  698. if(pmark != NULL)
  699. {
  700. pnewlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  701. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  702. if(pmark->lanemarktype() == 0)
  703. {
  704. LaneRoadMark * pLaneRoadMark = pnewlane->GetLastAddedLaneRoadMark();
  705. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  706. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  707. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  708. }
  709. }
  710. pLS->AddLane(1,(j+1)*(1),cda_lanetype_sel[pcdalane->lanetype()],false,true);
  711. pnewlane = pLS->GetLastAddedLane();
  712. pnewlane->AddWidthRecord(0,pcdalane->lanewidth(),0,0,0);
  713. pnewlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  714. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  715. if(pmark->lanemarktype() == 0)
  716. {
  717. LaneRoadMark * pLaneRoadMark = pnewlane->GetLastAddedLaneRoadMark();
  718. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  719. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  720. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  721. }
  722. }
  723. }
  724. if(pgeo->geotype() == 1)
  725. {
  726. nroadid++;
  727. char strroadid[256];
  728. snprintf(strroadid,256,"%d",nroadid);
  729. pxodr->AddRoad("wd",pgeo->geolen(),strroadid,"-1");
  730. Road * pRoad = pxodr->GetLastAddedRoad();
  731. pRoad->AddGeometryBlock();
  732. GeometryBlock * pgeob = pRoad->GetLastAddedGeometryBlock();
  733. pgeob->AddGeometryArc(0,xnow,ynow,hdgnow,pgeo->geolen(),1.0/pgeo->georadius());
  734. pRoad->GetGeometryCoords(pgeo->geolen(),xnow,ynow,hdgnow);
  735. pRoad->AddLaneSection(0);
  736. LaneSection * pLS = pRoad->GetLaneSection(0);
  737. pLS->AddLane(0,0,"none",false);
  738. Lane * pcenterlane = pLS->GetLastAddedLane();
  739. iv::map::cdalanemarkline * pmark = xcdadraw.mutable_mlanemarkline(0);
  740. if(pmark == NULL)
  741. pcenterlane->AddRoadMarkRecord(0,"solid solid","standard","yellow",0.15,"none");
  742. else
  743. {
  744. pcenterlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  745. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  746. if(pmark->lanemarktype() == 0)
  747. {
  748. LaneRoadMark * pLaneRoadMark = pcenterlane->GetLastAddedLaneRoadMark();
  749. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  750. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  751. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  752. }
  753. }
  754. int j;
  755. iv::map::cdadraw * pcdadraw = &xcdadraw;
  756. int nlanecount = pcdadraw->mlanes_size();
  757. for(j=0;j<nlanecount;j++)
  758. {
  759. iv::map::cdalane * pcdalane = pcdadraw->mutable_mlanes(j);
  760. pLS->AddLane(-1,(j+1)*(-1),cda_lanetype_sel[pcdalane->lanetype()],false,true);
  761. Lane * pnewlane = pLS->GetLastAddedLane();
  762. pnewlane->AddWidthRecord(0,pcdalane->lanewidth(),0,0,0);
  763. pmark = xcdadraw.mutable_mlanemarkline(j+1);
  764. if(pmark != NULL)
  765. {
  766. pnewlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  767. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  768. if(pmark->lanemarktype() == 0)
  769. {
  770. LaneRoadMark * pLaneRoadMark = pnewlane->GetLastAddedLaneRoadMark();
  771. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  772. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  773. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  774. }
  775. }
  776. pLS->AddLane(1,(j+1)*(1),cda_lanetype_sel[pcdalane->lanetype()],false,true);
  777. pnewlane = pLS->GetLastAddedLane();
  778. pnewlane->AddWidthRecord(0,pcdalane->lanewidth(),0,0,0);
  779. pmark = xcdadraw.mutable_mlanemarkline(j+1);
  780. if(pmark != NULL)
  781. {
  782. pnewlane->AddRoadMarkRecord(0,cda_lanemarktype_sel[pmark->lanemarktype()],"standard",
  783. cda_lanemarkcolor_sel[pmark->lanemarkcolor()],pmark->lanemarkwidth(),"none");
  784. if(pmark->lanemarktype() == 0)
  785. {
  786. LaneRoadMark * pLaneRoadMark = pnewlane->GetLastAddedLaneRoadMark();
  787. LaneRoadMarkType laneRoadMarkType(cda_lanemarktype_sel[pmark->lanemarktype()],pmark->lanemarkwidth());
  788. laneRoadMarkType.AddLaneRoadMarkLine(pmark->lanemarklinelength(),pmark->lanemarklinespace(),0,0);
  789. pLaneRoadMark->SetLaneRoadMarkType(laneRoadMarkType);
  790. }
  791. }
  792. }
  793. }
  794. if(pgeo->geotype() == 2)
  795. {
  796. ProcIntersectionRoad(pxodr,&xcdadraw,i,nroadid,xnow,ynow,hdgnow);
  797. }
  798. }
  799. // for(i=0;i<pxodr->GetRoadCount();i++)
  800. // {
  801. // Road * pRoad = pxodr->GetRoad(i);
  802. // pRoad->AddLaneSection(0);
  803. // LaneSection * pLS = pRoad->GetLaneSection(0);
  804. // pLS->AddLane(0,0,"none",false);
  805. // Lane * pcenterlane = pLS->GetLastAddedLane();
  806. // pcenterlane->AddRoadMarkRecord(0,"solid","standard","yellow",0.15,"none");
  807. // int i;
  808. // for(i=0;i<2;i++)
  809. // {
  810. // pLS->AddLane(-1,(i+1)*(-1),"driving",false,true);
  811. // Lane * pnewlane = pLS->GetLastAddedLane();
  812. // pnewlane->AddWidthRecord(0,3.5,0,0,0);
  813. // pnewlane->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"none");
  814. // }
  815. // }
  816. return 0;
  817. }