autoroadcontact.cpp 42 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340
  1. #include "autoroadcontact.h"
  2. #include "mainwindow.h"
  3. #include <math.h>
  4. #include <iostream>
  5. extern MainWindow * gw;
  6. #include "xodrfunc.h"
  7. #include "xodrdijkstra.h"
  8. AutoRoadContact::AutoRoadContact()
  9. {
  10. }
  11. /**
  12. * @brief AutoRoadContact::CalcContact
  13. * @param pRoad1
  14. * @param pRoad2
  15. * @param contacttype 0:start to start 1:start to end 2:end to start 3:end to end
  16. * @param turnstraight 0: turn 1:straight 2:u-turn
  17. * @param xARCLane right lane contact
  18. * @param xARCOpLane left lane contact
  19. * @param fDisTolerance distance must below this value
  20. * @return
  21. */
  22. int AutoRoadContact::CalcContact(Road *pRoad1, Road *pRoad2,int & contacttype,int & turnstraight,
  23. std::vector<iv::ARC> & xARCLane,std::vector<iv::ARC> & xARCOpLane, const double fDisTolerance)
  24. {
  25. double road1_start_x,road1_start_y,road1_end_x,road1_end_y,road1_start_hdg,road1_end_hdg;
  26. double road2_start_x,road2_start_y,road2_end_x,road2_end_y,road2_start_hdg,road2_end_hdg;
  27. int ngeo = pRoad1->GetGeometryCoords(0,road1_start_x,road1_start_y,road1_start_hdg);
  28. ngeo+=pRoad1->GetGeometryCoords(pRoad1->GetRoadLength(),road1_end_x,road1_end_y,road1_end_hdg);
  29. ngeo+=pRoad2->GetGeometryCoords(0,road2_start_x,road2_start_y,road2_start_hdg);
  30. ngeo+=pRoad2->GetGeometryCoords(pRoad2->GetRoadLength(),road2_end_x,road2_end_y,road2_end_hdg);
  31. if(ngeo<0)
  32. {
  33. return -1;
  34. }
  35. double dis_1s_2s = sqrt(pow(road1_start_x-road2_start_x,2)
  36. +pow(road1_start_y-road2_start_y,2));
  37. double dis_1s_2e = sqrt(pow(road1_start_x-road2_end_x,2)
  38. +pow(road1_start_y-road2_end_y,2));
  39. double dis_1e_2s = sqrt(pow(road1_end_x-road2_start_x,2)
  40. +pow(road1_end_y-road2_start_y,2));
  41. double dis_1e_2e = sqrt(pow(road1_end_x-road2_end_x,2)
  42. +pow(road1_end_y-road2_end_y,2));
  43. double fdis[4];
  44. fdis[0] = dis_1s_2s;
  45. fdis[1] = dis_1s_2e;
  46. fdis[2] = dis_1e_2s;
  47. fdis[3] = dis_1e_2e;
  48. double fdismin = 100000;
  49. int index = -1;
  50. unsigned int i;
  51. for(i=0;i<4;i++)
  52. {
  53. if(fdismin>fdis[i])
  54. {
  55. fdismin = fdis[i];
  56. index = i;
  57. }
  58. }
  59. if(fdismin > fDisTolerance)
  60. {
  61. std::cout<<"dis is grater than Distance Tolerance. Tolerance is "<<fDisTolerance<<std::endl;
  62. return -3;
  63. }
  64. if(fdismin < 0.1)
  65. {
  66. std::cout<<"dis is less than 0.1"<<std::endl;
  67. return -4;
  68. }
  69. contacttype = index;
  70. if(contacttype == -1)
  71. {
  72. return -2;
  73. }
  74. LaneSection * pLS1 = 0;
  75. LaneSection * pLS2 = 0;
  76. double from_x,from_y,from_hdg,to_x,to_y,to_hdg;
  77. switch (contacttype) {
  78. case 0:
  79. from_x = road1_start_x;
  80. from_y = road1_start_y;
  81. to_x = road2_start_x;
  82. to_y = road2_start_y;
  83. from_hdg = road1_start_hdg + M_PI;
  84. to_hdg = road2_start_hdg;
  85. pLS1 = pRoad1->GetLaneSection(0);
  86. pLS2 = pRoad2->GetLaneSection(0);
  87. break;
  88. case 1:
  89. from_x = road1_start_x;
  90. from_y = road1_start_y;
  91. to_x = road2_end_x;
  92. to_y = road2_end_y;
  93. from_hdg = road1_start_hdg + M_PI;
  94. to_hdg = road2_end_hdg+ M_PI;
  95. pLS1 = pRoad1->GetLaneSection(0);
  96. pLS2 = pRoad2->GetLastLaneSection();
  97. break;
  98. case 2:
  99. from_x = road1_end_x;
  100. from_y = road1_end_y;
  101. to_x = road2_start_x;
  102. to_y = road2_start_y;
  103. from_hdg = road1_end_hdg ;
  104. to_hdg = road2_start_hdg;
  105. pLS1 = pRoad1->GetLastLaneSection();
  106. pLS2 = pRoad2->GetLaneSection(0);
  107. break;
  108. case 3:
  109. from_x = road1_end_x;
  110. from_y = road1_end_y;
  111. to_x = road2_end_x;
  112. to_y = road2_end_y;
  113. from_hdg = road1_end_hdg ;
  114. to_hdg = road2_end_hdg + M_PI;
  115. pLS1 = pRoad1->GetLastLaneSection();
  116. pLS2 = pRoad2->GetLastLaneSection();
  117. break;
  118. default:
  119. break;
  120. }
  121. if(from_hdg >= 2.0*M_PI)from_hdg = from_hdg - 2.0*M_PI;
  122. if(to_hdg >= 2.0*M_PI)to_hdg = to_hdg - 2.0*M_PI;
  123. double hdgdiff = to_hdg - from_hdg;
  124. while(hdgdiff>=2.0*M_PI)hdgdiff = hdgdiff - 2.0*M_PI;
  125. while(hdgdiff<0)hdgdiff = hdgdiff + 2.0*M_PI;
  126. bool bTurnRight = true;
  127. if((hdgdiff<0.5)||(hdgdiff>(2.0*M_PI-0.5)))
  128. {
  129. turnstraight = 1;
  130. }
  131. else
  132. {
  133. if((hdgdiff>(M_PI-0.3))&&(hdgdiff<(M_PI+0.3)))
  134. {
  135. turnstraight = 2;
  136. }
  137. else
  138. {
  139. if(hdgdiff>M_PI)
  140. {
  141. std::cout<<"turn right"<<std::endl;
  142. bTurnRight = true;
  143. }
  144. else
  145. {
  146. std::cout<<"turn left"<<std::endl;
  147. bTurnRight = false;
  148. }
  149. turnstraight = 0;
  150. }
  151. }
  152. vector<Lane *> xroad1lane1,xroad1lane2;
  153. vector<Lane *> xroad2lane1,xroad2lane2;
  154. for(i=0;i<pLS1->GetLeftLaneCount();i++)
  155. {
  156. Lane * pLane = pLS1->GetLeftLaneAt(i+1);
  157. if(pLane == NULL)
  158. {
  159. std::cout<<"GetLeftLaneError i:"<<i<<std::endl;
  160. break;
  161. }
  162. xroad1lane1.push_back(pLane);
  163. }
  164. for(i=0;i<pLS1->GetRightLaneCount();i++)
  165. {
  166. Lane * pLane = pLS1->GetRightLaneAt(i+1);
  167. if(pLane == NULL)
  168. {
  169. std::cout<<"GetRightLaneAt i:"<<i<<std::endl;
  170. break;
  171. }
  172. xroad1lane2.push_back(pLane);
  173. }
  174. for(i=0;i<pLS2->GetLeftLaneCount();i++)
  175. {
  176. Lane * pLane = pLS2->GetLeftLaneAt(i+1);
  177. if(pLane == NULL)
  178. {
  179. std::cout<<"GetLeftLaneError i:"<<i<<std::endl;
  180. break;
  181. }
  182. xroad2lane1.push_back(pLane);
  183. }
  184. for(i=0;i<pLS2->GetRightLaneCount();i++)
  185. {
  186. Lane * pLane = pLS2->GetRightLaneAt(i+1);
  187. if(pLane == NULL)
  188. {
  189. std::cout<<"GetRightLaneAt i:"<<i<<std::endl;
  190. break;
  191. }
  192. xroad2lane2.push_back(pLane);
  193. }
  194. vector<Lane *> xroad1leftlane,xroad1rightlane;
  195. vector<Lane *> xroad2leftlane,xroad2rightlane;
  196. if((contacttype == 0)||(contacttype == 1))
  197. {
  198. xroad1leftlane = xroad1lane2;
  199. xroad1rightlane = xroad1lane1;
  200. }
  201. else
  202. {
  203. xroad1leftlane = xroad1lane1;
  204. xroad1rightlane = xroad1lane2;
  205. }
  206. if((contacttype == 1)||(contacttype == 3))
  207. {
  208. xroad2leftlane = xroad2lane2;
  209. xroad2rightlane = xroad2lane1;
  210. }
  211. else
  212. {
  213. xroad2leftlane = xroad2lane1;
  214. xroad2rightlane = xroad2lane2;
  215. }
  216. if(turnstraight == 1) //
  217. {
  218. for(i=0;i<xroad1rightlane.size();i++)
  219. {
  220. Lane * pLane1 = xroad1rightlane.at(i);
  221. if(i>=xroad2rightlane.size())
  222. {
  223. break;
  224. }
  225. Lane * pLane2 = xroad2rightlane.at(i);
  226. if((pLane1 == NULL)||(pLane2 == NULL))
  227. {
  228. break;
  229. }
  230. if(pLane1->GetType() != pLane2->GetType())
  231. {
  232. break;
  233. }
  234. iv::ARC xARC;
  235. xARC.from = pLane1->GetId();
  236. xARC.to = pLane2->GetId();
  237. xARCLane.push_back(xARC);
  238. }
  239. for(i=0;i<xroad1leftlane.size();i++)
  240. {
  241. Lane * pLane1 = xroad1leftlane.at(i);
  242. if(i>=xroad2leftlane.size())
  243. {
  244. break;
  245. }
  246. Lane * pLane2 = xroad2leftlane.at(i);
  247. if((pLane1 == NULL)||(pLane2 == NULL))
  248. {
  249. break;
  250. }
  251. if(pLane1->GetType() != pLane2->GetType())
  252. {
  253. break;
  254. }
  255. iv::ARC xARC;
  256. xARC.from = pLane1->GetId();
  257. xARC.to = pLane2->GetId();
  258. xARCOpLane.push_back(xARC);
  259. }
  260. }
  261. else
  262. {
  263. if(turnstraight == 0)
  264. {
  265. int nindex1 = -1;
  266. int nindex2 = -1;
  267. for(i=0;i<xroad1rightlane.size();i++)
  268. {
  269. if(xroad1rightlane.at(i)->GetType() == "driving")
  270. {
  271. nindex1 = i;
  272. if(bTurnRight == false)
  273. {
  274. break;
  275. }
  276. }
  277. }
  278. for(i=0;i<xroad2rightlane.size();i++)
  279. {
  280. if(xroad2rightlane.at(i)->GetType() == "driving")
  281. {
  282. nindex2 = i;
  283. if(bTurnRight == false)
  284. {
  285. break;
  286. }
  287. }
  288. }
  289. if((nindex1<0)||(nindex2<0))
  290. {
  291. std::cout<<"can't find driving lane"<<std::endl;
  292. return -3;
  293. }
  294. if(bTurnRight)
  295. {
  296. for(i=nindex1;i<xroad1rightlane.size();i++)
  297. {
  298. Lane * pLane1 = xroad1rightlane.at(i);
  299. if(nindex2 >= xroad2rightlane.size())
  300. {
  301. break;
  302. }
  303. Lane * pLane2 = xroad2rightlane.at(nindex2);nindex2++;
  304. if((pLane1 == NULL)||(pLane2 == NULL))
  305. {
  306. break;
  307. }
  308. if(pLane1->GetType() != pLane2->GetType())
  309. {
  310. break;
  311. }
  312. iv::ARC xARC;
  313. xARC.from = pLane1->GetId();
  314. xARC.to = pLane2->GetId();
  315. xARCLane.push_back(xARC);
  316. }
  317. }
  318. else
  319. {
  320. Lane * pLane1 = xroad1rightlane.at(nindex1);
  321. Lane * pLane2 = xroad2rightlane.at(nindex2);
  322. if((pLane1 == NULL)||(pLane2 == NULL))
  323. {
  324. std::cout<<"Lane NULL"<<std::endl;
  325. }
  326. if(pLane1->GetType() != pLane2->GetType())
  327. {
  328. std::cout<<"Type Not Rigth"<<std::endl;
  329. }
  330. iv::ARC xARC;
  331. xARC.from = pLane1->GetId();
  332. xARC.to = pLane2->GetId();
  333. xARCLane.push_back(xARC);
  334. }
  335. }
  336. else
  337. {
  338. int nindex1 = -1;
  339. int nindex2 = -1;
  340. for(i=0;i<xroad1rightlane.size();i++)
  341. {
  342. if(xroad1rightlane.at(i)->GetType() == "driving")
  343. {
  344. nindex1 = i;
  345. break;
  346. }
  347. }
  348. for(i=0;i<xroad2rightlane.size();i++)
  349. {
  350. if(xroad2rightlane.at(i)->GetType() == "driving")
  351. {
  352. nindex2 = i;
  353. break;
  354. }
  355. }
  356. if((nindex1<0)||(nindex2<0))
  357. {
  358. std::cout<<"can't find driving lane"<<std::endl;
  359. return -3;
  360. }
  361. Lane * pLane1 = xroad1rightlane.at(nindex1);
  362. Lane * pLane2 = xroad2rightlane.at(nindex2);
  363. if((pLane1 == NULL)||(pLane2 == NULL))
  364. {
  365. std::cout<<"Lane NULL"<<std::endl;
  366. }
  367. if(pLane1->GetType() != pLane2->GetType())
  368. {
  369. std::cout<<"Type Not Rigth"<<std::endl;
  370. }
  371. iv::ARC xARC;
  372. xARC.from = pLane1->GetId();
  373. xARC.to = pLane2->GetId();
  374. xARCLane.push_back(xARC);
  375. }
  376. }
  377. std::cout<<"Lane Contact"<<std::endl;
  378. for(i=0;i<xARCLane.size();i++)
  379. {
  380. std::cout<<" From "<<xARCLane.at(i).from<<" To"<<xARCLane.at(i).to<<std::endl;
  381. }
  382. std::cout<<"OpLane Contact"<<std::endl;
  383. for(i=0;i<xARCOpLane.size();i++)
  384. {
  385. std::cout<<" From "<<xARCOpLane.at(i).from<<" To"<<xARCOpLane.at(i).to<<std::endl;
  386. }
  387. return 0;
  388. }
  389. std::vector<Road *> AutoRoadContact::GetRelaRoad(OpenDrive *pxodr, Road *pRoad)
  390. {
  391. std::vector<Road *> xvectorRoadRela;
  392. unsigned int i;
  393. if(pRoad->GetPredecessor() != 0)
  394. {
  395. if(pRoad->GetPredecessor()->GetElementType() == "road")
  396. {
  397. std::string roadid = pRoad->GetPredecessor()->GetElementId();
  398. Road * pRoadTem = xodrfunc::GetRoadByID(pxodr,roadid);
  399. if(pRoadTem != 0)
  400. {
  401. xvectorRoadRela.push_back(pRoadTem);
  402. }
  403. }
  404. if(pRoad->GetPredecessor()->GetElementType() == "junction")
  405. {
  406. std::string junctionid = pRoad->GetPredecessor()->GetElementId();
  407. Junction * pJunction = xodrfunc::GetJunctionByID(pxodr,junctionid);
  408. if(pJunction != 0)
  409. {
  410. unsigned int njucntionconcount = pJunction->GetJunctionConnectionCount();
  411. for(i=0;i<njucntionconcount;i++)
  412. {
  413. JunctionConnection * pJC = pJunction->GetJunctionConnection(i);
  414. if(pJC == NULL)continue;
  415. if(pJC->GetIncomingRoad() == pRoad->GetRoadId())
  416. {
  417. std::string roadid = pJC->GetConnectingRoad();
  418. Road * pRoadTem = xodrfunc::GetRoadByID(pxodr,roadid);
  419. if(pRoadTem != 0)
  420. {
  421. xvectorRoadRela.push_back(pRoadTem);
  422. }
  423. }
  424. else
  425. {
  426. if(pJC->GetConnectingRoad() == pRoad->GetRoadId())
  427. {
  428. std::string roadid = pJC->GetIncomingRoad();
  429. Road * pRoadTem = xodrfunc::GetRoadByID(pxodr,roadid);
  430. if(pRoadTem != 0)
  431. {
  432. xvectorRoadRela.push_back(pRoadTem);
  433. }
  434. }
  435. }
  436. }
  437. }
  438. }
  439. }
  440. if(pRoad->GetSuccessor() != 0)
  441. {
  442. if(pRoad->GetSuccessor()->GetElementType() == "road")
  443. {
  444. std::string roadid = pRoad->GetSuccessor()->GetElementId();
  445. Road * pRoadTem = xodrfunc::GetRoadByID(pxodr,roadid);
  446. if(pRoadTem != 0)
  447. {
  448. xvectorRoadRela.push_back(pRoadTem);
  449. }
  450. }
  451. if(pRoad->GetSuccessor()->GetElementType() == "junction")
  452. {
  453. std::string junctionid = pRoad->GetSuccessor()->GetElementId();
  454. Junction * pJunction = xodrfunc::GetJunctionByID(pxodr,junctionid);
  455. if(pJunction != 0)
  456. {
  457. unsigned int njucntionconcount = pJunction->GetJunctionConnectionCount();
  458. for(i=0;i<njucntionconcount;i++)
  459. {
  460. JunctionConnection * pJC = pJunction->GetJunctionConnection(i);
  461. if(pJC == NULL)continue;
  462. if(pJC->GetIncomingRoad() == pRoad->GetRoadId())
  463. {
  464. std::string roadid = pJC->GetConnectingRoad();
  465. Road * pRoadTem = xodrfunc::GetRoadByID(pxodr,roadid);
  466. if(pRoadTem != 0)
  467. {
  468. xvectorRoadRela.push_back(pRoadTem);
  469. }
  470. }
  471. else
  472. {
  473. if(pJC->GetConnectingRoad() == pRoad->GetRoadId())
  474. {
  475. std::string roadid = pJC->GetIncomingRoad();
  476. Road * pRoadTem = xodrfunc::GetRoadByID(pxodr,roadid);
  477. if(pRoadTem != 0)
  478. {
  479. xvectorRoadRela.push_back(pRoadTem);
  480. }
  481. }
  482. }
  483. }
  484. }
  485. }
  486. }
  487. return xvectorRoadRela;
  488. }
  489. bool AutoRoadContact::RoadToRoad(OpenDrive * pxodr,Road * pRoad1,bool bRoad1Start,Road * pRoad2,bool bRoad2Start,std::vector<Road *> & xvectorthroughroad)
  490. {
  491. RoadLink * pLink;
  492. if(bRoad1Start == false)
  493. {
  494. pLink = pRoad1->GetSuccessor();
  495. }
  496. else
  497. {
  498. pLink = pRoad1->GetPredecessor();
  499. }
  500. if(pLink->GetElementType() == "road")
  501. {
  502. std::string strroadid = pLink->GetElementId();
  503. Road * pcenterroad = xodrfunc::GetRoadByID(pxodr,strroadid);
  504. }
  505. return false;
  506. }
  507. bool AutoRoadContact::IsExist(OpenDrive *pxodr, iv::RoadContactUnit xRCU)
  508. {
  509. Road * pRoad1 = xRCU.mpRoad1;
  510. Road * pRoad2 = xRCU.mpRoad2;
  511. std::vector<Road *> xvectorRoad1Rela;
  512. std::vector<Road *> xvectorRoad2Rela;
  513. xvectorRoad1Rela = AutoRoadContact::GetRelaRoad(pxodr,pRoad1);
  514. xvectorRoad2Rela = AutoRoadContact::GetRelaRoad(pxodr,pRoad2);
  515. if((xRCU.mcontactype ==0)||(xRCU.mcontactype == 1))
  516. {
  517. if(pRoad1->GetPredecessor() == NULL)
  518. {
  519. return false;
  520. }
  521. RoadLink * pLink = pRoad1->GetPredecessor();
  522. if(pLink->GetElementType() == "road")
  523. {
  524. Road * pRoadCenter = xodrfunc::GetRoadByID(pxodr,pLink->GetElementId());
  525. if(pRoadCenter != 0)
  526. {
  527. if(pRoadCenter == pRoad2)
  528. {
  529. return true;
  530. }
  531. else
  532. {
  533. if(pLink->GetContactPoint() == "end")
  534. {
  535. RoadLink * pLinkCenter = pRoadCenter->GetPredecessor();
  536. if(pLinkCenter == NULL)
  537. {
  538. return false;
  539. }
  540. }
  541. }
  542. }
  543. }
  544. }
  545. //Not turn
  546. if(xRCU.mturnstraight != 0)
  547. {
  548. unsigned int i;
  549. for(i=0;i<xvectorRoad2Rela.size();i++)
  550. {
  551. if(xvectorRoad2Rela[i] == pRoad1)
  552. {
  553. return true;
  554. }
  555. }
  556. for(i=0;i<xvectorRoad1Rela.size();i++)
  557. {
  558. if(xvectorRoad1Rela[i] == pRoad2)
  559. {
  560. return true;
  561. }
  562. }
  563. }
  564. return false;
  565. }
  566. int AutoRoadContact::MakeAllContact(OpenDrive *pxodr, const double fDisTolerance)
  567. {
  568. unsigned int nRoadCount = pxodr->GetRoadCount();
  569. int i;
  570. std::vector<iv::RoadContactUnit> xvectorRCU;
  571. for(i=0;i<nRoadCount;i++)
  572. {
  573. Road * pnowRoad = pxodr->GetRoad(i);
  574. unsigned int j;
  575. for(j=0;j<nRoadCount;j++)
  576. {
  577. if(j != i)
  578. {
  579. Road * potherRoad = pxodr->GetRoad(j);
  580. int contactype;
  581. int turnstraight;
  582. std::vector<iv::ARC> xARCLane,xARCOpLane;
  583. int nARCRtn = CalcContact(pnowRoad,potherRoad,contactype,turnstraight,xARCLane,xARCOpLane);
  584. if(nARCRtn == 0)
  585. {
  586. std::cout<<" Road:"<<pnowRoad->GetRoadId()<<" Road:"<<potherRoad->GetRoadId()
  587. <<" contact type: "<<turnstraight<<std::endl;
  588. if(xARCLane.size()>0 || (xARCOpLane.size()>0))
  589. {
  590. iv::RoadContactUnit rcu;
  591. rcu.mARCLane = xARCLane;
  592. rcu.mARCOpLane = xARCOpLane;
  593. rcu.mcontactype = contactype;
  594. rcu.mturnstraight = turnstraight;
  595. rcu.mpRoad1 = pnowRoad;
  596. rcu.mpRoad2 = potherRoad;
  597. xvectorRCU.push_back(rcu);
  598. }
  599. }
  600. }
  601. }
  602. }
  603. xodrdijkstra * pxodrdj = new xodrdijkstra(pxodr);
  604. //Delete Repeate strait
  605. for(i=0;i<xvectorRCU.size();i++)
  606. {
  607. unsigned int j;
  608. for(j=(i+1);j<xvectorRCU.size();j++)
  609. {
  610. if((xvectorRCU[i].mpRoad1 == xvectorRCU[j].mpRoad2)&&(xvectorRCU[i].mpRoad2 == xvectorRCU[j].mpRoad1))
  611. {
  612. if((xvectorRCU[i].mturnstraight == 1)&&(xvectorRCU[j].mturnstraight == 1))
  613. {
  614. std::cout<<"because repeate straight.erase Road:"<<xvectorRCU[j].mpRoad1->GetRoadId()
  615. <<" Road:"<<xvectorRCU[j].mpRoad2->GetRoadId()
  616. <<" contact type: "<<xvectorRCU[j].mturnstraight<<std::endl;
  617. xvectorRCU.erase(xvectorRCU.begin()+j);
  618. j = j-1;
  619. }
  620. }
  621. }
  622. }
  623. int RCUSize = xvectorRCU.size();
  624. for(i=0;i<xvectorRCU.size();i++)
  625. {
  626. int nlr1 = 0;
  627. int nlr2 = 0;
  628. if((xvectorRCU[i].mcontactype == 0)||(xvectorRCU[i].mcontactype == 1))
  629. {
  630. nlr1 = 1;
  631. }
  632. else
  633. {
  634. nlr1 = 2;
  635. }
  636. if((xvectorRCU[i].mcontactype == 1)||(xvectorRCU[i].mcontactype == 3))
  637. {
  638. nlr2 = 1;
  639. }
  640. else
  641. {
  642. nlr2 = 2;
  643. }
  644. bool bPath;
  645. Road * pRoad1 = xvectorRCU[i].mpRoad1;
  646. Road * pRoad2 = xvectorRCU[i].mpRoad2;
  647. std::vector<int> xvectorpath = pxodrdj->getpath(atoi(pRoad1->GetRoadId().data()),nlr1,
  648. atoi(pRoad2->GetRoadId().data()),nlr2,
  649. bPath);
  650. if(bPath)
  651. {
  652. if((xvectorpath.size()==2)||(xvectorpath.size() == 3))
  653. {
  654. std::vector<pathsection> xvp = pxodrdj->getgpspoint(atoi(pRoad1->GetRoadId().data()),nlr1,
  655. atoi(pRoad2->GetRoadId().data()),nlr2,
  656. xvectorpath,1);
  657. unsigned int j;
  658. std::cout<<"path have ";
  659. for(j=0;j<xvp.size();j++)
  660. {
  661. std::cout<<j<<": "<<xvp[j].mroadid<<" ";
  662. }
  663. std::cout<<std::endl;
  664. xvectorRCU.erase(xvectorRCU.begin()+i);
  665. i = i-1;
  666. if(xvp.size() == 3)
  667. {
  668. int nroadid = xvp[1].mroadid;
  669. std::cout<<" found junction road . id: "<<nroadid<<std::endl;
  670. int k = 0;
  671. bool bdel = false;
  672. for(k=0;k<xvectorRCU.size();k++)
  673. {
  674. if((atoi(xvectorRCU[k].mpRoad1->GetRoadId().data()) == nroadid)||(atoi(xvectorRCU[k].mpRoad2->GetRoadId().data()) == nroadid))
  675. {
  676. xvectorRCU.erase(xvectorRCU.begin() + k);
  677. k = k-1;
  678. bdel = true;
  679. }
  680. }
  681. if(bdel)
  682. {
  683. i = -1;
  684. }
  685. }
  686. }
  687. }
  688. }
  689. std::cout<<" RCU Size is "<<xvectorRCU.size()<<std::endl;
  690. // for(i=0;i<xvectorRCU.size();i++)
  691. std::vector<std::vector<iv::roadcontact>> xvectorrcs;
  692. for(i=0;i<xvectorRCU.size();i++)
  693. {
  694. std::vector<iv::roadcontact> xvectorrc;
  695. xvectorrc.clear();
  696. iv::roadcontact rc;
  697. if((xvectorRCU[i].mcontactype == 0) ||(xvectorRCU[i].mcontactype == 1))
  698. {
  699. rc.mncon1 = 0;
  700. }
  701. else
  702. {
  703. rc.mncon1 = 1;
  704. }
  705. if((xvectorRCU[i].mcontactype == 0) ||(xvectorRCU[i].mcontactype == 2))
  706. {
  707. rc.mncon2 = 0;
  708. }
  709. else
  710. {
  711. rc.mncon2 = 1;
  712. }
  713. rc.mnroad1id = atoi(xvectorRCU[i].mpRoad1->GetRoadId().data());
  714. rc.mnroad2id = atoi(xvectorRCU[i].mpRoad2->GetRoadId().data());
  715. unsigned int j;
  716. for(j=0;j<xvectorRCU[i].mARCLane.size();j++)
  717. {
  718. iv::lanecontact lt;
  719. lt.ml1 = xvectorRCU[i].mARCLane[j].from;
  720. lt.ml2 = xvectorRCU[i].mARCLane[j].to;
  721. rc.mvectorlc.push_back(lt);
  722. }
  723. for(j=0;j<xvectorRCU[i].mARCOpLane.size();j++)
  724. {
  725. iv::lanecontact lt;
  726. lt.ml1 = xvectorRCU[i].mARCOpLane[j].from;
  727. lt.ml2 = xvectorRCU[i].mARCOpLane[j].to;
  728. rc.mvectorlcop.push_back(lt);
  729. }
  730. xvectorrc.push_back(rc);
  731. xvectorrcs.push_back(xvectorrc);
  732. // CreateContactRoad(xvectorrc,pxodr,xvectorRCU[i].mturnstraight);
  733. }
  734. for(i=0;i<xvectorrcs.size();i++)
  735. {
  736. CreateContactRoad(xvectorrcs[i],pxodr,xvectorRCU[i].mturnstraight);
  737. }
  738. return 0;
  739. }
  740. void AutoRoadContact::CreateContactRoad(std::vector<iv::roadcontact> & xvectorrc,OpenDrive * pxodr,int nConType)
  741. {
  742. if(xvectorrc.size()<1)return;
  743. Road * p1, *p2;
  744. int nroad1index;
  745. int nroad2index;
  746. int i;
  747. bool bhavep1 = false;
  748. bool bhavep2 = false;
  749. for(i=0;i<pxodr->GetRoadCount();i++)
  750. {
  751. if(xvectorrc[0].mnroad1id == atoi(pxodr->GetRoad(i)->GetRoadId().data()))
  752. {
  753. bhavep1 = true;
  754. p1 = pxodr->GetRoad(i);
  755. nroad1index = i;
  756. break;
  757. }
  758. }
  759. if(bhavep1 == false)
  760. {
  761. std::cout<<"Road not found"<<std::endl;
  762. return;
  763. }
  764. double off1,off2;
  765. for(i=0;i<pxodr->GetRoadCount();i++)
  766. {
  767. if(xvectorrc[0].mnroad2id == atoi(pxodr->GetRoad(i)->GetRoadId().data()))
  768. {
  769. bhavep2 = true;
  770. p2 = pxodr->GetRoad(i);
  771. nroad2index = i;
  772. break;
  773. }
  774. }
  775. if(bhavep2 == false)
  776. {
  777. std::cout<<"Road not found"<<std::endl;
  778. return;
  779. }
  780. if(xvectorrc[0].mvectorlc.size()<1)
  781. {
  782. std::cout<<"No Lane Contact."<<std::endl;;
  783. return;
  784. }
  785. double startx,starty,starthdg;
  786. double endx,endy,endhdg;
  787. double startheight,endheight;
  788. bool bFromstart,bTostart;
  789. if(xvectorrc[0].mncon1 == 0)
  790. {
  791. bFromstart = true;
  792. starthdg = p1->GetGeometryBlock(0)->GetGeometryAt(0)->GetHdg();
  793. off1 = MainWindow::getoff(p1,xvectorrc[0].mvectorlc[0].ml1,true);
  794. startx = p1->GetGeometryBlock(0)->GetGeometryAt(0)->GetX();
  795. starty = p1->GetGeometryBlock(0)->GetGeometryAt(0)->GetY();
  796. if(p1->GetLaneOffsetCount()>0)
  797. {
  798. off1 = off1 - p1->GetLaneOffset(0)->Geta();
  799. }
  800. startx = startx + off1 * cos(starthdg -M_PI/2.0);
  801. starty = starty + off1 * sin(starthdg -M_PI/2.0);
  802. startheight = 0;
  803. if(p1->GetElevationCount()>0)
  804. {
  805. startheight = p1->GetElevation(0)->GetA();
  806. }
  807. // if(mvectorrc[0].mvectorlc[0].ml1<0)
  808. starthdg = starthdg +M_PI;if(starthdg >=2.0*M_PI)starthdg = starthdg -2.0*M_PI;
  809. }
  810. else
  811. {
  812. bFromstart = false;
  813. if(GetEndPoint(p1,startx,starty,starthdg) != 0)
  814. {
  815. std::cout<<"Get End Point Error."<<std::endl;
  816. return;
  817. }
  818. off1 = MainWindow::getoff(p1,xvectorrc[0].mvectorlc[0].ml1,false);
  819. if(p1->GetLaneOffsetCount()>0)
  820. {
  821. LaneOffset * pLO = p1->GetLaneOffset(p1->GetLaneOffsetCount()-1);
  822. double froadlen = p1->GetRoadLength();
  823. double sdis = froadlen - pLO->GetS();
  824. double foffset = pLO->Geta() + pLO->Getb()*(sdis) + pLO->Getc() * sdis * sdis
  825. +pLO->Getd() * sdis * sdis * sdis;
  826. off1 = off1 - foffset;
  827. }
  828. startx = startx + off1 * cos(starthdg -M_PI/2.0);
  829. starty = starty + off1 * sin(starthdg -M_PI/2.0);
  830. startheight = 0;
  831. if(p1->GetElevationCount()>0)
  832. {
  833. startheight = p1->GetElevation(0)->GetA()
  834. +p1->GetElevation(0)->GetB() * pow(p1->GetRoadLength(),1)
  835. +p1->GetElevation(0)->GetC() * pow(p1->GetRoadLength(),2)
  836. +p1->GetElevation(0)->GetD() * pow(p1->GetRoadLength(),3);
  837. }
  838. }
  839. if(xvectorrc[0].mncon2 == 0)
  840. {
  841. bTostart = true;
  842. off2 = MainWindow::getoff(p2,xvectorrc[0].mvectorlc[0].ml2,true);
  843. endx = p2->GetGeometryBlock(0)->GetGeometryAt(0)->GetX();
  844. endy = p2->GetGeometryBlock(0)->GetGeometryAt(0)->GetY();
  845. endhdg = p2->GetGeometryBlock(0)->GetGeometryAt(0)->GetHdg();
  846. if(p2->GetLaneOffsetCount()>0)
  847. {
  848. off2 = off2 - p2->GetLaneOffset(0)->Geta();
  849. }
  850. endx = endx + off2 * cos(endhdg -M_PI/2.0);
  851. endy = endy + off2 * sin(endhdg -M_PI/2.0);
  852. endheight = 0;
  853. if(p2->GetElevationCount()>0)
  854. {
  855. endheight = p2->GetElevation(0)->GetA();
  856. }
  857. }
  858. else
  859. {
  860. bTostart = false;
  861. off2 = MainWindow::getoff(p2,xvectorrc[0].mvectorlc[0].ml2,false);
  862. if(GetEndPoint(p2,endx,endy,endhdg) != 0)
  863. {
  864. std::cout<<"get end error."<<std::endl;
  865. return;
  866. }
  867. if(p2->GetLaneOffsetCount()>0)
  868. {
  869. LaneOffset * pLO = p2->GetLaneOffset(p2->GetLaneOffsetCount()-1);
  870. double froadlen = p2->GetRoadLength();
  871. double sdis = froadlen - pLO->GetS();
  872. double foffset = pLO->Geta() + pLO->Getb()*(sdis) + pLO->Getc() * sdis * sdis
  873. +pLO->Getd() * sdis * sdis * sdis;
  874. off2 = off2 - foffset;
  875. }
  876. endx = endx + off2 * cos(endhdg -M_PI/2.0);
  877. endy = endy + off2 * sin(endhdg -M_PI/2.0);
  878. endhdg = endhdg +M_PI;if(endhdg >=2.0*M_PI)endhdg = endhdg -2.0*M_PI;
  879. endheight = 0;
  880. if(p2->GetElevationCount()>0)
  881. {
  882. endheight = p2->GetElevation(0)->GetA()
  883. +p2->GetElevation(0)->GetB() * pow(p2->GetRoadLength(),1)
  884. +p2->GetElevation(0)->GetC() * pow(p2->GetRoadLength(),2)
  885. +p2->GetElevation(0)->GetD() * pow(p2->GetRoadLength(),3);
  886. }
  887. }
  888. //Create Geo
  889. double R = 6.0;
  890. std::vector<geobase> xvectorgeo;
  891. std::vector<geobase> xvectorgeo1,xvectorgeo2;
  892. switch(nConType)
  893. {
  894. case 0:
  895. xvectorgeo = geofit::CreateTurnGeo(startx,starty,starthdg,endx,endy,endhdg,R);
  896. break;
  897. case 1:
  898. xvectorgeo = geofit::CreateLineGeo(startx,starty,starthdg,endx,endy,endhdg);
  899. break;
  900. case 2:
  901. xvectorgeo = geofit::CreateUTurnGeo(startx,starty,starthdg,endx,endy,endhdg,R);
  902. break;
  903. default:
  904. break;
  905. }
  906. if(nConType == 2)
  907. {
  908. for(i=0;i<xvectorgeo.size()/2;i++)
  909. {
  910. xvectorgeo1.push_back(xvectorgeo.at(i));
  911. }
  912. for(i=xvectorgeo.size()/2;i<xvectorgeo.size();i++)
  913. {
  914. xvectorgeo2.push_back(xvectorgeo.at(i));
  915. }
  916. }
  917. if(xvectorgeo.size() == 0)
  918. {
  919. std::cout<<"Waring Create Road Fail."<<std::endl;
  920. return;
  921. }
  922. double xroadlen = 0;
  923. if(nConType != 2)
  924. {
  925. for(i=0;i<xvectorgeo.size();i++)xroadlen = xroadlen + xvectorgeo[i].mfLen;
  926. pxodr->AddRoad("",xroadlen, QString::number(gw->CreateRoadID()).toStdString(),"-1");
  927. Road * p = pxodr->GetRoad(pxodr->GetRoadCount() - 1);
  928. p->AddElevation(0,startheight,(endheight-startheight)/xroadlen,0,0);
  929. p1 = pxodr->GetRoad(nroad1index);
  930. p2 = pxodr->GetRoad(nroad2index);
  931. double s = 0;
  932. int j;
  933. j= 0;
  934. for(j=0;j<xvectorgeo.size();j++)
  935. {
  936. p->AddGeometryBlock();
  937. GeometryBlock * pgb = p->GetGeometryBlock(j);
  938. geobase * pline;
  939. geobase * pbez;
  940. geobase * parc;
  941. switch(xvectorgeo[j].mnType)
  942. {
  943. case 0:
  944. pline = &xvectorgeo[j];
  945. pgb->AddGeometryLine(s,pline->mfX,pline->mfY,pline->mfHdg,pline->mfLen);
  946. break;
  947. case 1:
  948. parc = &xvectorgeo[j];
  949. pgb->AddGeometryArc(s,parc->mfX,parc->mfY,parc->mfHdgStart,parc->mfLen,1.0/parc->mR);
  950. break;
  951. case 2:
  952. pbez = &xvectorgeo[j];
  953. std::cout<<"u0:"<<pbez->mfu[0]<<std::endl;
  954. pgb->AddGeometryParamPoly3(s,pbez->mfX,pbez->mfY,
  955. pbez->mfHdg,pbez->mfLen,pbez->mfu[0],
  956. pbez->mfu[1],pbez->mfu[2],pbez->mfu[3],pbez->mfv[0],
  957. pbez->mfv[1],pbez->mfv[2],pbez->mfv[3]);
  958. break;
  959. }
  960. s = s + xvectorgeo[j].mfLen;
  961. }
  962. p->AddLaneSection(0);
  963. LaneSection * pLS = p->GetLaneSection(0);
  964. pLS->SetS(0);
  965. pLS->AddLane(0,0,"none",false);
  966. double * pswidth,*pewidth;
  967. std::vector<std::string> strvectorlanetype;
  968. int nlanecount = xvectorrc[0].mvectorlc.size();
  969. pswidth = new double[nlanecount];
  970. pewidth = new double[nlanecount];
  971. std::shared_ptr<double> ppswidth,ppewidth;
  972. ppswidth.reset(pswidth);
  973. ppewidth.reset(pewidth);
  974. for(i=0;i<nlanecount;i++)
  975. {
  976. pswidth[i] = gw->getlanewidth(p1,xvectorrc[0].mvectorlc.at(i).ml1,bFromstart);
  977. strvectorlanetype.push_back(gw->getlanetype(p1,xvectorrc[0].mvectorlc.at(i).ml1,bFromstart));
  978. }
  979. for(i=0;i<nlanecount;i++)
  980. {
  981. pewidth[i] = gw->getlanewidth(p2,xvectorrc[0].mvectorlc.at(i).ml2,bTostart);
  982. }
  983. double * pa,*pb;
  984. pa = new double[nlanecount];
  985. pb = new double[nlanecount];
  986. std::shared_ptr<double> ppa,ppb;
  987. ppa.reset(pa);
  988. ppb.reset(pb);
  989. for(i=0;i<nlanecount;i++)
  990. {
  991. pa[i] = pswidth[i];
  992. pb[i] = (pewidth[i] - pa[i])/xroadlen;
  993. }
  994. for(i=0;i<nlanecount;i++)
  995. {
  996. pLS->AddLane(-1,(i+1)*(-1),strvectorlanetype[i],false,false);
  997. Lane * pLL = pLS->GetLane(pLS->GetLaneCount() - 1);
  998. pLL->AddWidthRecord(0,pa[i],pb[i],
  999. 0,0);
  1000. pLL->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"false");
  1001. }
  1002. int noplanecount = xvectorrc[0].mvectorlcop.size();
  1003. if(noplanecount > 0)
  1004. {
  1005. pswidth = new double[noplanecount];
  1006. pewidth = new double[noplanecount];
  1007. ppswidth.reset(pswidth);
  1008. ppewidth.reset(pewidth);
  1009. strvectorlanetype.clear();
  1010. for(i=0;i<noplanecount;i++)
  1011. {
  1012. pswidth[i] = gw->getlanewidth(p1,xvectorrc[0].mvectorlcop.at(i).ml1,bFromstart);
  1013. strvectorlanetype.push_back(gw->getlanetype(p1,xvectorrc[0].mvectorlcop.at(i).ml1,bFromstart));
  1014. }
  1015. for(i=0;i<noplanecount;i++)
  1016. {
  1017. pewidth[i] = gw->getlanewidth(p2,xvectorrc[0].mvectorlcop.at(i).ml2,bTostart);
  1018. }
  1019. pa = new double[noplanecount];
  1020. pb = new double[noplanecount];
  1021. ppa.reset(pa);
  1022. ppb.reset(pb);
  1023. for(i=0;i<noplanecount;i++)
  1024. {
  1025. pa[i] = pswidth[i];
  1026. pb[i] = (pewidth[i] - pa[i])/xroadlen;
  1027. }
  1028. for(i=0;i<noplanecount;i++)
  1029. {
  1030. pLS->AddLane(1,(i+1),strvectorlanetype[i],false,false);
  1031. Lane * pLL = pLS->GetLane(pLS->GetLaneCount() - 1);
  1032. pLL->AddWidthRecord(0,pa[i],pb[i],
  1033. 0,0);
  1034. pLL->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"false");
  1035. }
  1036. }
  1037. }
  1038. else
  1039. {
  1040. double xroadlen1 = 0;
  1041. double xroadlen2 = 0;
  1042. for(i=0;i<xvectorgeo1.size();i++)xroadlen1 = xroadlen1 + xvectorgeo1[i].mfLen;
  1043. for(i=0;i<xvectorgeo2.size();i++)xroadlen2 = xroadlen2 + xvectorgeo2[i].mfLen;
  1044. int index1 = pxodr->AddRoad("",xroadlen1, QString::number(gw->CreateRoadID()).toStdString(),"-1");
  1045. int index2 = pxodr->AddRoad("",xroadlen2, QString::number(gw->CreateRoadID()).toStdString(),"-1");
  1046. Road * proad2 = pxodr->GetRoad(index2);
  1047. Road * proad1 = pxodr->GetRoad(index1);
  1048. proad1->AddElevation(0,startheight,(endheight-startheight)/(xroadlen1+xroadlen2),0,0);
  1049. proad2->AddElevation(0,startheight+xroadlen1*(endheight-startheight)/(xroadlen1+xroadlen2),
  1050. (endheight-startheight)/(xroadlen1+xroadlen2),
  1051. 0,0);
  1052. p1 = pxodr->GetRoad(nroad1index);
  1053. p2 = pxodr->GetRoad(nroad2index);
  1054. // OpenDrive * px = &mxodr;
  1055. double s = 0;
  1056. int j;
  1057. j= 0;
  1058. for(j=0;j<xvectorgeo1.size();j++)
  1059. {
  1060. proad1->AddGeometryBlock();
  1061. GeometryBlock * pgb = proad1->GetGeometryBlock(j);
  1062. geobase * pline;
  1063. geobase * pbez;
  1064. geobase * parc;
  1065. switch(xvectorgeo1[j].mnType)
  1066. {
  1067. case 0:
  1068. pline = &xvectorgeo1[j];
  1069. pgb->AddGeometryLine(s,pline->mfX,pline->mfY,pline->mfHdg,pline->mfLen);
  1070. break;
  1071. case 1:
  1072. parc = &xvectorgeo1[j];
  1073. pgb->AddGeometryArc(s,parc->mfX,parc->mfY,parc->mfHdgStart,parc->mfLen,1.0/parc->mR);
  1074. break;
  1075. case 2:
  1076. pbez = &xvectorgeo1[j];
  1077. std::cout<<"u0:"<<pbez->mfu[0]<<std::endl;
  1078. pgb->AddGeometryParamPoly3(s,pbez->mfX,pbez->mfY,
  1079. pbez->mfHdg,pbez->mfLen,pbez->mfu[0],
  1080. pbez->mfu[1],pbez->mfu[2],pbez->mfu[3],pbez->mfv[0],
  1081. pbez->mfv[1],pbez->mfv[2],pbez->mfv[3]);
  1082. break;
  1083. }
  1084. s = s + xvectorgeo1[j].mfLen;
  1085. }
  1086. s=0.0;
  1087. for(j=0;j<xvectorgeo2.size();j++)
  1088. {
  1089. proad2->AddGeometryBlock();
  1090. GeometryBlock * pgb = proad2->GetGeometryBlock(j);
  1091. geobase * pline;
  1092. geobase * pbez;
  1093. geobase * parc;
  1094. switch(xvectorgeo2[j].mnType)
  1095. {
  1096. case 0:
  1097. pline = &xvectorgeo2[j];
  1098. pgb->AddGeometryLine(s,pline->mfX,pline->mfY,pline->mfHdg,pline->mfLen);
  1099. break;
  1100. case 1:
  1101. parc = &xvectorgeo2[j];
  1102. pgb->AddGeometryArc(s,parc->mfX,parc->mfY,parc->mfHdgStart,parc->mfLen,1.0/parc->mR);
  1103. break;
  1104. case 2:
  1105. pbez = &xvectorgeo2[j];
  1106. std::cout<<"u0:"<<pbez->mfu[0]<<std::endl;
  1107. pgb->AddGeometryParamPoly3(s,pbez->mfX,pbez->mfY,
  1108. pbez->mfHdg,pbez->mfLen,pbez->mfu[0],
  1109. pbez->mfu[1],pbez->mfu[2],pbez->mfu[3],pbez->mfv[0],
  1110. pbez->mfv[1],pbez->mfv[2],pbez->mfv[3]);
  1111. break;
  1112. }
  1113. s = s + xvectorgeo2[j].mfLen;
  1114. }
  1115. proad1->AddLaneSection(0);
  1116. LaneSection * pLS1 = proad1->GetLaneSection(0);
  1117. pLS1->SetS(0);
  1118. pLS1->AddLane(0,0,"none",false);
  1119. proad2->AddLaneSection(0);
  1120. LaneSection * pLS2 = proad2->GetLaneSection(0);
  1121. pLS2->SetS(0);
  1122. pLS2->AddLane(0,0,"none",false);
  1123. double * pswidth,*pewidth;
  1124. int nlanecount = xvectorrc[0].mvectorlc.size();
  1125. std::vector<std::string> strvectorlanetype;
  1126. pswidth = new double[nlanecount];
  1127. pewidth = new double[nlanecount];
  1128. std::shared_ptr<double> ppswidth,ppewidth;
  1129. ppswidth.reset(pswidth);
  1130. ppewidth.reset(pewidth);
  1131. for(i=0;i<nlanecount;i++)
  1132. {
  1133. pswidth[i] = gw->getlanewidth(p1,xvectorrc[0].mvectorlc.at(i).ml1,bFromstart);
  1134. strvectorlanetype.push_back(gw->getlanetype(p1,xvectorrc[0].mvectorlc.at(i).ml1,bFromstart));
  1135. }
  1136. for(i=0;i<nlanecount;i++)
  1137. {
  1138. pewidth[i] = gw->getlanewidth(p2,xvectorrc[0].mvectorlc.at(i).ml2,bTostart);
  1139. }
  1140. double * pa,*pb;
  1141. pa = new double[nlanecount];
  1142. pb = new double[nlanecount];
  1143. std::shared_ptr<double> ppa,ppb;
  1144. ppa.reset(pa);
  1145. ppb.reset(pb);
  1146. for(i=0;i<nlanecount;i++)
  1147. {
  1148. pa[i] = pswidth[i];
  1149. pb[i] = (pewidth[i] - pa[i])/(xroadlen1+xroadlen2);
  1150. }
  1151. for(i=0;i<nlanecount;i++)
  1152. {
  1153. pLS1->AddLane(-1,(i+1)*(-1),strvectorlanetype[i],false,false);
  1154. Lane * pLL = pLS1->GetLane(pLS1->GetLaneCount() - 1);
  1155. pLL->AddWidthRecord(0,pa[i],pb[i],
  1156. 0,0);
  1157. pLL->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"false");
  1158. pLS2->AddLane(-1,(i+1)*(-1),strvectorlanetype[i],false,false);
  1159. pLL = pLS2->GetLane(pLS2->GetLaneCount() - 1);
  1160. pLL->AddWidthRecord(0,pa[i]+pb[i]*xroadlen1 ,pb[i],
  1161. 0,0);
  1162. pLL->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"false");
  1163. }
  1164. int noplanecount = xvectorrc[0].mvectorlcop.size();
  1165. if(noplanecount > 0)
  1166. {
  1167. pswidth = new double[noplanecount];
  1168. pewidth = new double[noplanecount];
  1169. ppswidth.reset(pswidth);
  1170. ppewidth.reset(pewidth);
  1171. strvectorlanetype.clear();
  1172. for(i=0;i<noplanecount;i++)
  1173. {
  1174. pswidth[i] = gw->getlanewidth(p1,xvectorrc[0].mvectorlcop.at(i).ml1,bFromstart);
  1175. strvectorlanetype.push_back(gw->getlanetype(p1,xvectorrc[0].mvectorlcop.at(i).ml1,bFromstart));
  1176. }
  1177. for(i=0;i<noplanecount;i++)
  1178. {
  1179. pewidth[i] = gw->getlanewidth(p2,xvectorrc[0].mvectorlcop.at(i).ml2,bTostart);
  1180. }
  1181. pa = new double[noplanecount];
  1182. pb = new double[noplanecount];
  1183. ppa.reset(pa);
  1184. ppb.reset(pb);
  1185. for(i=0;i<noplanecount;i++)
  1186. {
  1187. pa[i] = pswidth[i];
  1188. pb[i] = (pewidth[i] - pa[i])/xroadlen;
  1189. }
  1190. for(i=0;i<noplanecount;i++)
  1191. {
  1192. pLS1->AddLane(1,(i+1),strvectorlanetype[i],false,false);
  1193. Lane * pLL = pLS1->GetLane(pLS1->GetLaneCount() - 1);
  1194. pLL->AddWidthRecord(0,pa[i],pb[i],
  1195. 0,0);
  1196. pLL->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"false");
  1197. pLS2->AddLane(1,(i+1),strvectorlanetype[i],false,false);
  1198. pLL = pLS2->GetLane(pLS2->GetLaneCount() - 1);
  1199. pLL->AddWidthRecord(0,pa[i]+pb[i]*xroadlen1 ,pb[i],
  1200. 0,0);
  1201. pLL->AddRoadMarkRecord(0,"solid","standard","standard",0.15,"false");
  1202. }
  1203. }
  1204. }
  1205. }