globalplan.cpp 87 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288228922902291229222932294229522962297229822992300230123022303230423052306230723082309231023112312231323142315231623172318231923202321232223232324232523262327232823292330233123322333233423352336233723382339234023412342234323442345234623472348234923502351235223532354235523562357235823592360236123622363236423652366236723682369237023712372237323742375237623772378237923802381238223832384238523862387238823892390239123922393239423952396239723982399240024012402240324042405240624072408240924102411241224132414241524162417241824192420242124222423242424252426242724282429243024312432243324342435243624372438243924402441244224432444244524462447244824492450245124522453245424552456245724582459246024612462246324642465246624672468246924702471247224732474247524762477247824792480248124822483248424852486248724882489249024912492249324942495249624972498249925002501250225032504250525062507250825092510251125122513251425152516251725182519252025212522252325242525252625272528252925302531253225332534253525362537253825392540254125422543254425452546254725482549255025512552255325542555255625572558255925602561256225632564256525662567256825692570257125722573257425752576257725782579258025812582258325842585258625872588258925902591259225932594259525962597259825992600260126022603260426052606260726082609261026112612261326142615261626172618261926202621262226232624262526262627262826292630263126322633263426352636263726382639264026412642264326442645264626472648264926502651265226532654265526562657265826592660266126622663266426652666266726682669267026712672267326742675267626772678267926802681268226832684268526862687268826892690269126922693269426952696269726982699270027012702270327042705270627072708270927102711271227132714271527162717271827192720272127222723272427252726272727282729273027312732273327342735273627372738273927402741274227432744274527462747274827492750275127522753275427552756275727582759276027612762276327642765276627672768276927702771277227732774277527762777277827792780278127822783278427852786278727882789279027912792279327942795279627972798279928002801280228032804280528062807280828092810281128122813281428152816281728182819282028212822282328242825282628272828282928302831283228332834283528362837283828392840284128422843284428452846284728482849285028512852285328542855285628572858285928602861286228632864286528662867286828692870287128722873287428752876287728782879288028812882288328842885288628872888288928902891289228932894289528962897289828992900290129022903290429052906290729082909291029112912291329142915291629172918291929202921292229232924292529262927292829292930293129322933293429352936293729382939294029412942294329442945294629472948294929502951295229532954295529562957295829592960296129622963296429652966296729682969297029712972297329742975297629772978297929802981298229832984298529862987298829892990299129922993299429952996299729982999300030013002300330043005300630073008300930103011301230133014301530163017301830193020302130223023302430253026302730283029303030313032303330343035303630373038303930403041304230433044304530463047304830493050305130523053305430553056305730583059306030613062306330643065306630673068306930703071307230733074307530763077307830793080308130823083308430853086308730883089309030913092309330943095309630973098309931003101310231033104310531063107310831093110311131123113311431153116311731183119312031213122312331243125312631273128312931303131313231333134313531363137313831393140
  1. #include "globalplan.h"
  2. #include "limits"
  3. #include <iostream>
  4. #include <Eigen/Dense>
  5. #include <Eigen/Cholesky>
  6. #include <Eigen/LU>
  7. #include <Eigen/QR>
  8. #include <Eigen/SVD>
  9. #include <QDebug>
  10. #include <QPointF>
  11. using namespace Eigen;
  12. extern "C"
  13. {
  14. #include "dubins.h"
  15. }
  16. static void AddSignalMark(Road * pRoad, int nlane,std::vector<PlanPoint> & xvectorPP);
  17. /**
  18. * @brief GetLineDis 获得点到直线Geometry的距离。
  19. * @param pline
  20. * @param x
  21. * @param y
  22. * @param nearx
  23. * @param neary
  24. * @param nearhead
  25. * @return
  26. */
  27. static double GetLineDis(GeometryLine * pline,const double x,const double y,double & nearx,
  28. double & neary,double & nearhead)
  29. {
  30. double fRtn = 1000.0;
  31. double a1,a2,a3,a4,b1,b2;
  32. double ratio = pline->GetHdg();
  33. while(ratio >= 2.0* M_PI)ratio = ratio-2.0*M_PI;
  34. while(ratio<0)ratio = ratio+2.0*M_PI;
  35. double dis1,dis2,dis3;
  36. double x1,x2,x3,y1,y2,y3;
  37. x1 = pline->GetX();y1=pline->GetY();
  38. if((ratio == 0)||(ratio == M_PI))
  39. {
  40. a1 = 0;a4=0;
  41. a2 = 1;b1= pline->GetY();
  42. a3 = 1;b2= x;
  43. }
  44. else
  45. {
  46. if((ratio == 0.5*M_PI)||(ratio == 1.5*M_PI))
  47. {
  48. a2=0;a3=0;
  49. a1=1,b1=pline->GetX();
  50. a4 = 1;b2 = y;
  51. }
  52. else
  53. {
  54. a1 = tan(ratio) *(-1.0);
  55. a2 = 1;
  56. a3 = tan(ratio+M_PI/2.0)*(-1.0);
  57. a4 = 1;
  58. b1 = a1*pline->GetX() + a2 * pline->GetY();
  59. b2 = a3*x+a4*y;
  60. }
  61. }
  62. y2 = y1 + pline->GetLength() * sin(ratio);
  63. x2 = x1 + pline->GetLength() * cos(ratio);
  64. Eigen::Matrix2d A;
  65. A<<a1,a2,
  66. a3,a4;
  67. Eigen::Vector2d B(b1,b2);
  68. Eigen::Vector2d opoint = A.lu().solve(B);
  69. // std::cout<<opoint<<std::endl;
  70. x3 = opoint(0);
  71. y3 = opoint(1);
  72. dis1 = sqrt(pow(x1-x,2)+pow(y1-y,2));
  73. dis2 = sqrt(pow(x2-x,2)+pow(y2-y,2));
  74. dis3 = sqrt(pow(x3-x,2)+pow(y3-y,2));
  75. // std::cout<<" dis 1 is "<<dis1<<std::endl;
  76. // std::cout<<" dis 2 is "<<dis2<<std::endl;
  77. // std::cout<<" dis 3 is "<<dis3<<std::endl;
  78. if((dis1>pline->GetLength())||(dis2>pline->GetLength())) //Outoff line
  79. {
  80. // std::cout<<" out line"<<std::endl;
  81. if(dis1<dis2)
  82. {
  83. fRtn = dis1;
  84. nearx = x1;neary=y1;nearhead = pline->GetHdg();
  85. }
  86. else
  87. {
  88. fRtn = dis2;
  89. nearx = x2;neary=y2;nearhead = pline->GetHdg();
  90. }
  91. }
  92. else
  93. {
  94. fRtn = dis3;
  95. nearx = x3;neary=y3;nearhead = pline->GetHdg();
  96. }
  97. // std::cout<<"dis is "<<fRtn<<" x is "<<nearx<<" y is "<<neary<<" head is "<<nearhead<<std::endl;
  98. return fRtn;
  99. }
  100. static int getcirclecrosspoint(QPointF startPos, QPointF endPos, QPointF agvPos, double R,QPointF & point1,QPointF & point2 )
  101. {
  102. double m=0;
  103. double k;
  104. double b;
  105. //计算分子
  106. m=startPos.x()-endPos.x();
  107. //求直线的方程
  108. if(0==m)
  109. {
  110. k=100000;
  111. b=startPos.y()-k*startPos.x();
  112. }
  113. else
  114. {
  115. k=(endPos.y()-startPos.y())/(endPos.x()-startPos.x());
  116. b=startPos.y()-k*startPos.x();
  117. }
  118. // qDebug()<<k<<b;
  119. double temp = fabs(k*agvPos.x()-agvPos.y()+b)/sqrt(k*k+b*b);
  120. //求直线与圆的交点 前提是圆需要与直线有交点
  121. if(fabs(k*agvPos.x()-agvPos.y()+b)/sqrt(k*k+b*b)<R)
  122. {
  123. point1.setX((2*agvPos.x()-2*k*(b-agvPos.y())+sqrt(pow((2*k*(b-agvPos.y())-2*agvPos.x()),2)-4*(k*k+1)*((b-agvPos.y())*(b-agvPos.y())+agvPos.x()*agvPos.x()-R*R)))/(2*k*k+2));
  124. point2.setX((2*agvPos.x()-2*k*(b-agvPos.y())-sqrt(pow((2*k*(b-agvPos.y())-2*agvPos.x()),2)-4*(k*k+1)*((b-agvPos.y())*(b-agvPos.y())+agvPos.x()*agvPos.x()-R*R)))/(2*k*k+2));
  125. point1.setY(k*point1.x()+b);
  126. point2.setY(k*point2.x()+b);
  127. return 0;
  128. }
  129. return -1;
  130. }
  131. /**
  132. * @brief CalcHdg
  133. * 计算点0到点1的航向
  134. * @param p0 Point 0
  135. * @param p1 Point 1
  136. **/
  137. static double CalcHdg(QPointF p0, QPointF p1)
  138. {
  139. double x0,y0,x1,y1;
  140. x0 = p0.x();
  141. y0 = p0.y();
  142. x1 = p1.x();
  143. y1 = p1.y();
  144. if(x0 == x1)
  145. {
  146. if(y0 < y1)
  147. {
  148. return M_PI/2.0;
  149. }
  150. else
  151. return M_PI*3.0/2.0;
  152. }
  153. double ratio = (y1-y0)/(x1-x0);
  154. double hdg = atan(ratio);
  155. if(ratio > 0)
  156. {
  157. if(y1 > y0)
  158. {
  159. }
  160. else
  161. {
  162. hdg = hdg + M_PI;
  163. }
  164. }
  165. else
  166. {
  167. if(y1 > y0)
  168. {
  169. hdg = hdg + M_PI;
  170. }
  171. else
  172. {
  173. hdg = hdg + 2.0*M_PI;
  174. }
  175. }
  176. return hdg;
  177. }
  178. static bool pointinarc(GeometryArc * parc,QPointF poingarc,QPointF point1)
  179. {
  180. double hdg = CalcHdg(poingarc,point1);
  181. if(parc->GetCurvature() >0)hdg = hdg + M_PI/2.0;
  182. else hdg = hdg - M_PI/2.0;
  183. if(hdg >= 2.0*M_PI)hdg = hdg - 2.0*M_PI;
  184. if(hdg < 0)hdg = hdg + 2.0*M_PI;
  185. double hdgrange = parc->GetLength()/(1.0/parc->GetCurvature());
  186. double hdgdiff = hdg - parc->GetHdg();
  187. if(hdgrange >= 0 )
  188. {
  189. if(hdgdiff < 0)hdgdiff = hdgdiff + M_PI*2.0;
  190. }
  191. else
  192. {
  193. if(hdgdiff > 0)hdgdiff = hdgdiff - M_PI*2.0;
  194. }
  195. if(fabs(hdgdiff ) < fabs(hdgrange))return true;
  196. return false;
  197. }
  198. static inline double calcpointdis(QPointF p1,QPointF p2)
  199. {
  200. return sqrt(pow(p1.x()-p2.x(),2)+pow(p1.y()-p2.y(),2));
  201. }
  202. /**
  203. * @brief GetArcDis
  204. * 计算点到圆弧的最短距离,首先用点和圆弧中心点的直线与圆的交点,计算点到交点的距离,如果交点在圆弧上,则最短距离是交点之一,否则计算点到圆弧两个端点的距离。
  205. * @param parc pointer to a arc geomery
  206. * @param x current x
  207. * @param y current y
  208. * @param nearx near x
  209. * @param neary near y
  210. * @param nearhead nearhead
  211. **/
  212. static double GetArcDis(GeometryArc * parc,double x,double y,double & nearx,
  213. double & neary,double & nearhead)
  214. {
  215. // double fRtn = 1000.0;
  216. if(parc->GetCurvature() == 0.0)return 1000.0;
  217. double R = fabs(1.0/parc->GetCurvature());
  218. // if(parc->GetX() == 4.8213842690322309e+01)
  219. // {
  220. // int a = 1;
  221. // a = 3;
  222. // }
  223. // if(parc->GetCurvature() == -0.0000110203)
  224. // {
  225. // int a = 1;
  226. // a = 3;
  227. // }
  228. //calculate arc center
  229. double x_center,y_center;
  230. if(parc->GetCurvature() > 0)
  231. {
  232. x_center = parc->GetX() + R * cos(parc->GetHdg() + M_PI/2.0);
  233. y_center = parc->GetY() + R * sin(parc->GetHdg()+ M_PI/2.0);
  234. }
  235. else
  236. {
  237. x_center = parc->GetX() + R * cos(parc->GetHdg() - M_PI/2.0);
  238. y_center = parc->GetY() + R * sin(parc->GetHdg() - M_PI/2.0);
  239. }
  240. double hdgltoa = CalcHdg(QPointF(x,y),QPointF(x_center,y_center));
  241. QPointF arcpoint;
  242. arcpoint.setX(x_center);arcpoint.setY(y_center);
  243. QPointF pointnow;
  244. pointnow.setX(x);pointnow.setY(y);
  245. QPointF point1,point2;
  246. point1.setX(x_center + (R * cos(hdgltoa)));
  247. point1.setY(y_center + (R * sin(hdgltoa)));
  248. point2.setX(x_center + (R * cos(hdgltoa + M_PI)));
  249. point2.setY(y_center + (R * sin(hdgltoa + M_PI)));
  250. //calculat dis
  251. bool bp1inarc,bp2inarc;
  252. bp1inarc =pointinarc(parc,arcpoint,point1);
  253. bp2inarc =pointinarc(parc,arcpoint,point2);
  254. double fdis[4];
  255. fdis[0] = calcpointdis(pointnow,point1);
  256. fdis[1] = calcpointdis(pointnow,point2);
  257. fdis[2] = calcpointdis(pointnow,QPointF(parc->GetX(),parc->GetY()));
  258. QPointF pointend;
  259. double hdgrange = parc->GetLength()*parc->GetCurvature();
  260. double hdgend = parc->GetHdg() + hdgrange;
  261. while(hdgend <0.0)hdgend = hdgend + 2.0 *M_PI;
  262. while(hdgend >= 2.0*M_PI) hdgend = hdgend -2.0*M_PI;
  263. if(parc->GetCurvature() >0)
  264. {
  265. pointend.setX(arcpoint.x() + R*cos(hdgend -M_PI/2.0 ));
  266. pointend.setY(arcpoint.y() + R*sin(hdgend -M_PI/2.0) );
  267. }
  268. else
  269. {
  270. pointend.setX(arcpoint.x() + R*cos(hdgend +M_PI/2.0 ));
  271. pointend.setY(arcpoint.y() + R*sin(hdgend +M_PI/2.0) );
  272. }
  273. fdis[3] = calcpointdis(pointnow,pointend);
  274. int indexmin = -1;
  275. double fdismin = 1000000.0;
  276. if(bp1inarc)
  277. {
  278. indexmin = 0;fdismin = fdis[0];
  279. }
  280. if(bp2inarc)
  281. {
  282. if(indexmin == -1)
  283. {
  284. indexmin = 1;fdismin = fdis[1];
  285. }
  286. else
  287. {
  288. if(fdis[1]<fdismin)
  289. {
  290. indexmin = 1;fdismin = fdis[1];
  291. }
  292. }
  293. }
  294. if(indexmin == -1)
  295. {
  296. indexmin = 2;fdismin = fdis[2];
  297. }
  298. else
  299. {
  300. if(fdis[2]<fdismin)
  301. {
  302. indexmin = 2;fdismin = fdis[2];
  303. }
  304. }
  305. if(fdis[3]<fdismin)
  306. {
  307. indexmin = 3;fdismin = fdis[3];
  308. }
  309. switch (indexmin) {
  310. case 0:
  311. nearx = point1.x();
  312. neary = point1.y();
  313. if(parc->GetCurvature()<0)
  314. {
  315. nearhead = CalcHdg(arcpoint,point1) - M_PI/2.0;
  316. }
  317. else
  318. {
  319. nearhead = CalcHdg(arcpoint,point1) + M_PI/2.0;
  320. }
  321. break;
  322. case 1:
  323. nearx = point2.x();
  324. neary = point2.y();
  325. if(parc->GetCurvature()<0)
  326. {
  327. nearhead = CalcHdg(arcpoint,point2) - M_PI/2.0;
  328. }
  329. else
  330. {
  331. nearhead = CalcHdg(arcpoint,point2) + M_PI/2.0;
  332. }
  333. break;
  334. case 2:
  335. nearx = parc->GetX();
  336. neary = parc->GetY();
  337. nearhead = parc->GetHdg();
  338. break;
  339. case 3:
  340. nearx = pointend.x();
  341. neary = pointend.y();
  342. nearhead = hdgend;
  343. break;
  344. default:
  345. std::cout<<"error in arcdis "<<std::endl;
  346. break;
  347. }
  348. while(nearhead>2.0*M_PI)nearhead = nearhead -2.0*M_PI;
  349. while(nearhead<0)nearhead = nearhead + 2.0*M_PI;
  350. return fdismin;
  351. }
  352. static double GetSpiralDis(GeometrySpiral * pspiral,double xnow,double ynow,double & nearx,
  353. double & neary,double & nearhead)
  354. {
  355. double x,y,hdg;
  356. double s = 0.0;
  357. double fdismin = 100000.0;
  358. double s0 = pspiral->GetS();
  359. while(s<pspiral->GetLength())
  360. {
  361. pspiral->GetCoords(s0+s,x,y,hdg);
  362. s = s+0.1;
  363. double fdis = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
  364. if(fdis<fdismin)
  365. {
  366. fdismin = fdis;
  367. nearhead = hdg;
  368. nearx = x;
  369. neary = y;
  370. }
  371. }
  372. return fdismin;
  373. }
  374. /**
  375. * @brief GetParamPoly3Dis 获得点到贝塞尔曲线的距离。
  376. * @param parc
  377. * @param xnow
  378. * @param ynow
  379. * @param nearx
  380. * @param neary
  381. * @param nearhead
  382. * @return
  383. */
  384. static double GetParamPoly3Dis(GeometryParamPoly3 * parc,double xnow,double ynow,double & nearx,
  385. double & neary,double & nearhead)
  386. {
  387. double s = 0.1;
  388. double fdismin = 100000.0;
  389. double xold,yold;
  390. xold = parc->GetX();
  391. yold = parc->GetY();
  392. double fdis = calcpointdis(QPointF(parc->GetX(),parc->GetY()),QPointF(xnow,ynow));
  393. if(fdis<fdismin)
  394. {
  395. fdismin = fdis;
  396. nearhead = parc->GetHdg();
  397. nearx = parc->GetX();
  398. neary = parc->GetY();
  399. }
  400. double s_start = parc->GetS();
  401. while(s < parc->GetLength())
  402. {
  403. double x, y,hdg;//xtem,ytem;
  404. parc->GetCoords(s_start+s,x,y,hdg);
  405. if(fdis<fdismin)
  406. {
  407. fdismin = fdis;
  408. nearhead = hdg;
  409. nearx = x;
  410. neary = y;
  411. }
  412. // xold = x;
  413. // yold = y;
  414. s = s+ 0.1;
  415. }
  416. return fdismin;
  417. }
  418. static double GetPoly3Dis(GeometryPoly3 * ppoly,double xnow,double ynow,double & nearx,
  419. double & neary,double & nearhead)
  420. {
  421. double x,y,hdg;
  422. // double s = 0.0;
  423. double fdismin = 100000.0;
  424. // double s0 = ppoly->GetS();
  425. x = ppoly->GetX();
  426. y = ppoly->GetY();
  427. double A,B,C,D;
  428. A = ppoly->GetA();
  429. B = ppoly->GetB();
  430. C = ppoly->GetC();
  431. D = ppoly->GetD();
  432. const double steplim = 0.3;
  433. double du = steplim;
  434. double u = 0;
  435. double v = 0;
  436. double oldx,oldy;
  437. oldx = x;
  438. oldy = y;
  439. double xstart,ystart;
  440. xstart = x;
  441. ystart = y;
  442. double hdgstart = ppoly->GetHdg();
  443. double flen = 0;
  444. u = u+du;
  445. while(flen < ppoly->GetLength())
  446. {
  447. double fdis = 0;
  448. v = A + B*u + C*u*u + D*u*u*u;
  449. x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
  450. y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
  451. fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
  452. if(fdis>(steplim*2.0))du = du/2.0;
  453. flen = flen + fdis;
  454. u = u + du;
  455. hdg = CalcHdg(QPointF(oldx,oldy),QPointF(x,y));
  456. double fdisnow = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
  457. if(fdisnow<fdismin)
  458. {
  459. fdismin = fdisnow;
  460. nearhead = hdg;
  461. nearx = x;
  462. neary = y;
  463. }
  464. oldx = x;
  465. oldy = y;
  466. }
  467. return fdismin;
  468. }
  469. /**
  470. * @brief GetNearPoint
  471. * 计算点到圆弧的最短距离,首先用点和圆弧中心点的直线与圆的交点,计算点到交点的距离,如果交点在圆弧上,则最短距离是交点之一,否则计算点到圆弧两个端点的距离。
  472. * @param x current x
  473. * @param y current y
  474. * @param pxodr OpenDrive
  475. * @param pObjRoad Road
  476. * @param pgeo Geometry of road
  477. * @param nearx near x
  478. * @param neary near y
  479. * @param nearhead nearhead
  480. * @param nearthresh near threshhold
  481. * @retval if == 0 successfull <0 fail.
  482. **/
  483. int GetNearPoint(const double x,const double y,OpenDrive * pxodr,Road ** pObjRoad,GeometryBlock ** pgeo, double & s,double & nearx,
  484. double & neary,double & nearhead,const double nearthresh,double &froads)
  485. {
  486. double dismin = std::numeric_limits<double>::infinity();
  487. s = dismin;
  488. int i;
  489. double frels;
  490. for(i=0;i<pxodr->GetRoadCount();i++)
  491. {
  492. int j;
  493. Road * proad = pxodr->GetRoad(i);
  494. double nx,ny,nh;
  495. for(j=0;j<proad->GetGeometryBlockCount();j++)
  496. {
  497. GeometryBlock * pgb = proad->GetGeometryBlock(j);
  498. double dis;
  499. RoadGeometry * pg;
  500. pg = pgb->GetGeometryAt(0);
  501. switch (pg->GetGeomType()) {
  502. case 0: //line
  503. dis = xodrfunc::GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh,frels);
  504. // dis = GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh);
  505. break;
  506. case 1:
  507. dis = xodrfunc::GetSpiralDis((GeometrySpiral *)pg,x,y,nx,ny,nh,frels);
  508. break;
  509. case 2: //arc
  510. dis = xodrfunc::GetArcDis((GeometryArc *)pg,x,y,nx,ny,nh,frels);
  511. break;
  512. case 3:
  513. dis = xodrfunc::GetPoly3Dis((GeometryPoly3 *)pg,x,y,nx,ny,nh,frels);
  514. break;
  515. case 4:
  516. dis = xodrfunc::GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh,frels);
  517. break;
  518. default:
  519. dis = 100000.0;
  520. break;
  521. }
  522. if(dis < dismin)
  523. {
  524. dismin = dis;
  525. nearx = nx;
  526. neary = ny;
  527. nearhead = nh;
  528. s = dis;
  529. froads = frels;
  530. *pObjRoad = proad;
  531. *pgeo = pgb;
  532. }
  533. // if(pgb->CheckIfLine())
  534. // {
  535. // GeometryLine * pline = (GeometryLine *)pgb->GetGeometryAt(0);
  536. // double dis = GetLineDis(pline,x,y,nx,ny,nh);
  537. // if(dis < dismin)
  538. // {
  539. // dismin = dis;
  540. // nearx = nx;
  541. // neary = ny;
  542. // nearhead = nh;
  543. // s = dis;
  544. // *pObjRoad = proad;
  545. // *pgeo = pgb;
  546. // }
  547. // }
  548. // else
  549. // {
  550. // GeometryLine * pline1 = (GeometryLine *)pgb->GetGeometryAt(0);
  551. // double dis = GetLineDis(pline1,x,y,nx,ny,nh);
  552. // if(dis < dismin)
  553. // {
  554. // dismin = dis;
  555. // nearx = nx;
  556. // neary = ny;
  557. // nearhead = nh;
  558. // s = dis;
  559. // *pObjRoad = proad;
  560. // *pgeo = pgb;
  561. // }
  562. // GeometryArc * parc = (GeometryArc *)pgb->GetGeometryAt(1);
  563. // dis = GetArcDis(parc,x,y,nx,ny,nh);
  564. // if(dis < dismin)
  565. // {
  566. // dismin = dis;
  567. // nearx = nx;
  568. // neary = ny;
  569. // nearhead = nh;
  570. // s = dis;
  571. // *pObjRoad = proad;
  572. // *pgeo = pgb;
  573. // }
  574. // pline1 = (GeometryLine *)pgb->GetGeometryAt(2);
  575. // dis = GetLineDis(pline1,x,y,nx,ny,nh);
  576. // if(dis < dismin)
  577. // {
  578. // dismin = dis;
  579. // nearx = nx;
  580. // neary = ny;
  581. // nearhead = nh;
  582. // s = dis;
  583. // *pObjRoad = proad;
  584. // *pgeo = pgb;
  585. // }
  586. // }
  587. }
  588. }
  589. if(s > nearthresh)return -1;
  590. return 0;
  591. }
  592. int GetNearPointWithHead(const double x,const double y,const double hdg,OpenDrive * pxodr,std::vector<iv::nearroad> & xvectornear,
  593. const double nearthresh,bool bhdgvalid = true)
  594. {
  595. std::cout<<" near thresh "<<nearthresh<<std::endl;
  596. int i;
  597. double frels;
  598. int nminmode = 6;
  599. for(i=0;i<pxodr->GetRoadCount();i++)
  600. {
  601. int j;
  602. Road * proad = pxodr->GetRoad(i);
  603. double nx,ny,nh;
  604. bool bchange = false;
  605. double localdismin = std::numeric_limits<double>::infinity();
  606. double localnearx = 0;
  607. double localneary = 0;
  608. double localnearhead = 0;
  609. double locals = 0;
  610. double localfrels = 0;
  611. GeometryBlock * pgeolocal;
  612. localdismin = std::numeric_limits<double>::infinity();
  613. for(j=0;j<proad->GetGeometryBlockCount();j++)
  614. {
  615. GeometryBlock * pgb = proad->GetGeometryBlock(j);
  616. double dis;
  617. RoadGeometry * pg;
  618. pg = pgb->GetGeometryAt(0);
  619. switch (pg->GetGeomType()) {
  620. case 0: //line
  621. dis = xodrfunc::GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh,frels);
  622. break;
  623. case 1:
  624. dis = xodrfunc::GetSpiralDis((GeometrySpiral *)pg,x,y,nx,ny,nh,frels);
  625. break;
  626. case 2: //arc
  627. dis = xodrfunc::GetArcDis((GeometryArc *)pg,x,y,nx,ny,nh,frels);
  628. break;
  629. case 3:
  630. dis = xodrfunc::GetPoly3Dis((GeometryPoly3 *)pg,x,y,nx,ny,nh,frels);
  631. break;
  632. case 4:
  633. dis = xodrfunc::GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh,frels);
  634. break;
  635. default:
  636. dis = 100000.0;
  637. break;
  638. }
  639. if(dis<localdismin)
  640. {
  641. localdismin = dis;
  642. localnearx = nx;
  643. localneary = ny;
  644. localnearhead = nh;
  645. locals = dis;
  646. localfrels = frels;
  647. pgeolocal = pgb;
  648. bchange = true;
  649. }
  650. }
  651. std::cout<<" local dismin "<<localdismin<<std::endl;
  652. if(localdismin < nearthresh)
  653. {
  654. iv::nearroad xnear;
  655. xnear.pObjRoad = proad;
  656. xnear.pgeob = pgeolocal;
  657. xnear.nearx = localnearx;
  658. xnear.neary = localneary;
  659. xnear.fdis = localdismin;
  660. xnear.nearhead = localnearhead;
  661. xnear.frels = localfrels;
  662. if((xnear.fdis>0)&&(xnear.frels>0.00001)&&(xnear.frels<(proad->GetRoadLength()-0.00001)))
  663. {
  664. double fcalhdg = xodrfunc::CalcHdg(QPointF(xnear.nearx,xnear.neary),QPointF(x,y));
  665. double fhdgdiff = fcalhdg - xnear.nearhead;
  666. while(fhdgdiff<0)fhdgdiff = fhdgdiff + 2.0*M_PI;
  667. while(fhdgdiff>= 2.0*M_PI)fhdgdiff = fhdgdiff - 2.0*M_PI;
  668. if(fhdgdiff<M_PI)
  669. {
  670. double fdisroad = proad->GetRoadLeftWidth(xnear.frels);
  671. if(fdisroad>xnear.fdis)
  672. {
  673. xnear.fdis = 0;
  674. }
  675. else
  676. {
  677. xnear.fdis = xnear.fdis - fdisroad;
  678. }
  679. xnear.lr = 1;
  680. }
  681. else
  682. {
  683. double fdisroad = proad->GetRoadRightWidth(xnear.frels);
  684. if(fdisroad>xnear.fdis)
  685. {
  686. xnear.fdis = 0;
  687. }
  688. else
  689. {
  690. xnear.fdis = xnear.fdis - fdisroad;
  691. }
  692. xnear.lr = 2;
  693. }
  694. }
  695. else
  696. {
  697. if(bhdgvalid == false)
  698. {
  699. if(xnear.pObjRoad->GetLaneSectionCount()>0)
  700. {
  701. LaneSection * pLS = xnear.pObjRoad->GetLaneSection(0);
  702. if(pLS->GetRightLaneCount()>0)
  703. {
  704. xnear.lr = 2;
  705. }
  706. else
  707. {
  708. xnear.lr = 1;
  709. }
  710. }
  711. else
  712. {
  713. xnear.lr = 2;
  714. }
  715. }
  716. }
  717. LaneSection * pLS = xnear.pObjRoad->GetLaneSection(0);
  718. if(pLS != NULL)
  719. {
  720. if(xnear.fdis < 0.00001)
  721. {
  722. if(bhdgvalid == false)
  723. {
  724. xnear.nmode = 0;
  725. }
  726. else
  727. {
  728. double headdiff = hdg - xnear.nearhead;
  729. while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
  730. while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
  731. if(((headdiff <M_PI/2.0)||(headdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
  732. {
  733. xnear.nmode = 0;
  734. }
  735. else
  736. {
  737. xnear.nmode = 1;
  738. }
  739. }
  740. }
  741. else
  742. {
  743. if(xnear.fdis<5)
  744. {
  745. if(bhdgvalid == false)
  746. {
  747. xnear.nmode = 2;
  748. }
  749. else
  750. {
  751. double headdiff = hdg - xnear.nearhead;
  752. while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
  753. while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
  754. if(((headdiff <M_PI/2.0)||(headdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
  755. {
  756. xnear.nmode = 2;
  757. }
  758. else
  759. {
  760. xnear.nmode = 3;
  761. }
  762. }
  763. }
  764. else
  765. {
  766. if(bhdgvalid == false)
  767. {
  768. xnear.nmode = 4;
  769. }
  770. else
  771. {
  772. double headdiff = hdg - xnear.nearhead;
  773. while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
  774. while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
  775. if(((headdiff <M_PI/2.0)||(headdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
  776. {
  777. xnear.nmode = 4;
  778. }
  779. else
  780. {
  781. xnear.nmode = 5;
  782. }
  783. }
  784. }
  785. }
  786. if(xnear.nmode < nminmode)nminmode = xnear.nmode;
  787. if(xnear.pObjRoad->GetLaneSectionCount()>0)
  788. {
  789. LaneSection * pLS = xnear.pObjRoad->GetLaneSection(0);
  790. if((pLS->GetRightLaneCount()>0)&& ((pLS->GetLeftLaneCount()==0)) && (xnear.lr == 1))
  791. {
  792. xnear.lr = 2;
  793. }
  794. if((pLS->GetRightLaneCount() == 0)&& ((pLS->GetLeftLaneCount()>0)) && (xnear.lr == 2))
  795. {
  796. xnear.lr = 1;
  797. }
  798. }
  799. xvectornear.push_back(xnear);
  800. }
  801. }
  802. }
  803. if(xvectornear.size() == 0)
  804. {
  805. std::cout<<" no near. "<<std::endl;
  806. return -1;
  807. }
  808. // std::cout<<" near size: "<<xvectornear.size()<<std::endl;
  809. if(xvectornear.size() > 1)
  810. {
  811. int i;
  812. for(i=0;i<(int)xvectornear.size();i++)
  813. {
  814. if(xvectornear[i].nmode > nminmode)
  815. {
  816. xvectornear.erase(xvectornear.begin() + i);
  817. i = i-1;
  818. }
  819. }
  820. }
  821. // std::cout<<" after size: "<<xvectornear.size()<<std::endl;
  822. if((xvectornear.size()>1)&&(nminmode>=4)) //if dis > 5 select small dis
  823. {
  824. int i;
  825. while(xvectornear.size()>1)
  826. {
  827. if(xvectornear[1].fdis < xvectornear[0].fdis)
  828. {
  829. xvectornear.erase(xvectornear.begin());
  830. }
  831. else
  832. {
  833. xvectornear.erase(xvectornear.begin()+1);
  834. }
  835. }
  836. }
  837. return 0;
  838. }
  839. /**
  840. * @brief SelectRoadLeftRight
  841. * 选择左侧道路或右侧道路
  842. * 1.选择角度差小于90度的道路一侧,即同侧道路
  843. * 2.单行路,选择存在的那一侧道路。
  844. * @param pRoad 道路
  845. * @param head1 车的航向或目标点的航向
  846. * @param head_road 目标点的航向
  847. * @retval 1 left 2 right
  848. **/
  849. static int SelectRoadLeftRight(Road * pRoad,const double head1,const double head_road)
  850. {
  851. int nrtn = 2;
  852. double headdiff = head1 - head_road;
  853. while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
  854. while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
  855. bool bSel = false;
  856. if((headdiff >=M_PI/2.0)&&(headdiff <= M_PI*3.0/2.0)) //if diff is
  857. {
  858. if(pRoad->GetLaneSection(0)->GetLeftLaneCount()>0)
  859. {
  860. nrtn = 1;
  861. bSel = true;
  862. }
  863. }
  864. else
  865. {
  866. if(pRoad->GetLaneSection(0)->GetRightLaneCount()>0)
  867. {
  868. nrtn = 2;
  869. bSel = true;
  870. }
  871. }
  872. if(bSel == false)
  873. {
  874. if(pRoad->GetLaneSection(0)->GetLeftLaneCount() >0)
  875. {
  876. nrtn = 1;
  877. }
  878. else
  879. {
  880. nrtn = 2;
  881. }
  882. }
  883. return nrtn;
  884. }
  885. //static double getlinereldis(GeometryLine * pline,double x,double y)
  886. //{
  887. // double x0,y0;
  888. // x0 = pline->GetX();
  889. // y0 = pline->GetY();
  890. // double dis = sqrt(pow(x-x0,2) + pow(y-y0,2));
  891. // if(dis > pline->GetS())
  892. // {
  893. // std::cout<<"getlinereldis exceed s S is "<<pline->GetS()<<" dis is "<<dis<<std::endl;
  894. // return dis;
  895. // }
  896. // return dis;
  897. //}
  898. //static double getarcreldis(GeometryArc * parc,double x,double y)
  899. //{
  900. // double x0,y0;
  901. // x0 = parc->GetX();
  902. // y0 = parc->GetY();
  903. // double dis = sqrt(pow(x-x0,2) + pow(y-y0,2));
  904. // double R = fabs(1.0/parc->GetCurvature());
  905. // double ang = 2.0* asin(dis/(2.0*R));
  906. // double frtn = ang * R;
  907. // return frtn;
  908. //}
  909. //static double getparampoly3reldis(GeometryParamPoly3 *parc, double xnow, double ynow)
  910. //{
  911. // double s = 0.1;
  912. // double xold,yold;
  913. // xold = parc->GetX();
  914. // yold = parc->GetY();
  915. // while(s < parc->GetLength())
  916. // {
  917. // double x, y,xtem,ytem;
  918. // xtem = parc->GetuA() + parc->GetuB() * s + parc->GetuC() * s*s + parc->GetuD() * s*s*s;
  919. // ytem = parc->GetvA() + parc->GetvB() * s + parc->GetvC() * s*s + parc->GetvD() * s*s*s;
  920. // x = xtem*cos(parc->GetHdg()) - ytem * sin(parc->GetHdg()) + parc->GetX();
  921. // y = xtem*sin(parc->GetHdg()) + ytem * cos(parc->GetHdg()) + parc->GetY();
  922. // if(sqrt(pow(xnow - x,2) + pow(ynow -y,2))<0.3)
  923. // {
  924. // break;
  925. // }
  926. // xold = x;
  927. // yold = y;
  928. // s = s+ 0.1;
  929. // }
  930. // return s;
  931. //}
  932. //static double getreldis(RoadGeometry * prg,double x,double y)
  933. //{
  934. // int ngeotype = prg->GetGeomType();
  935. // double frtn = 0;
  936. // switch (ngeotype) {
  937. // case 0:
  938. // frtn = getlinereldis((GeometryLine *)prg,x,y);
  939. // break;
  940. // case 1:
  941. // break;
  942. // case 2:
  943. // frtn = getarcreldis((GeometryArc *)prg,x,y);
  944. // break;
  945. // case 3:
  946. // break;
  947. // case 4:
  948. // frtn = getparampoly3reldis((GeometryParamPoly3 *)prg,x,y);
  949. // break;
  950. // default:
  951. // break;
  952. // }
  953. // return frtn;
  954. //}
  955. //static double getposinroad(Road * pRoad,GeometryBlock * pgeob,double x,double y)
  956. //{
  957. // RoadGeometry* prg = pgeob->GetGeometryAt(0);
  958. // double s1 = prg->GetS();
  959. // double srtn = s1;
  960. // return s1 + getreldis(prg,x,y);
  961. //}
  962. static std::vector<PlanPoint> getlinepoint(GeometryLine * pline,const double fspace = 0.1)
  963. {
  964. std::vector<PlanPoint> xvectorPP;
  965. int i;
  966. double s = pline->GetLength();
  967. int nsize = s/fspace;
  968. if(nsize ==0)nsize = 1;
  969. for(i=0;i<nsize;i++)
  970. {
  971. double x,y;
  972. x = pline->GetX() + i *fspace * cos(pline->GetHdg());
  973. y = pline->GetY() + i *fspace * sin(pline->GetHdg());
  974. PlanPoint pp;
  975. pp.x = x;
  976. pp.y = y;
  977. pp.dis = i*fspace;
  978. pp.hdg = pline->GetHdg();
  979. pp.mS = pline->GetS() + i*fspace;
  980. xvectorPP.push_back(pp);
  981. }
  982. return xvectorPP;
  983. }
  984. static std::vector<PlanPoint> getarcpoint(GeometryArc * parc,const double fspace = 0.1)
  985. {
  986. std::vector<PlanPoint> xvectorPP;
  987. // double fRtn = 1000.0;
  988. if(parc->GetCurvature() == 0.0)return xvectorPP;
  989. double R = fabs(1.0/parc->GetCurvature());
  990. //calculate arc center
  991. double x_center = parc->GetX() + (1.0/parc->GetCurvature()) * cos(parc->GetHdg() + M_PI/2.0);
  992. double y_center = parc->GetY() + (1.0/parc->GetCurvature()) * sin(parc->GetHdg()+ M_PI/2.0);
  993. double arcdiff = fspace/R;
  994. int nsize = parc->GetLength()/fspace;
  995. if(nsize == 0)nsize = 1;
  996. int i;
  997. for(i=0;i<nsize;i++)
  998. {
  999. double x,y;
  1000. PlanPoint pp;
  1001. if(parc->GetCurvature() > 0)
  1002. {
  1003. x = x_center + R * cos(parc->GetHdg() + i*arcdiff - M_PI/2.0);
  1004. y = y_center + R * sin(parc->GetHdg() + i*arcdiff - M_PI/2.0);
  1005. pp.hdg = parc->GetHdg() + i*arcdiff;
  1006. }
  1007. else
  1008. {
  1009. x = x_center + R * cos(parc->GetHdg() -i*arcdiff + M_PI/2.0);
  1010. y = y_center + R * sin(parc->GetHdg() -i*arcdiff + M_PI/2.0);
  1011. pp.hdg = parc->GetHdg() - i*arcdiff;
  1012. }
  1013. pp.x = x;
  1014. pp.y = y;
  1015. pp.dis = i*fspace;
  1016. pp.mS = parc->GetS() + i*fspace;
  1017. xvectorPP.push_back(pp);
  1018. }
  1019. return xvectorPP;
  1020. }
  1021. static std::vector<PlanPoint> getspiralpoint(GeometrySpiral * pspiral,const double fspace = 0.1)
  1022. {
  1023. double x,y,hdg;
  1024. double s = 0.0;
  1025. double s0 = pspiral->GetS();
  1026. std::vector<PlanPoint> xvectorPP;
  1027. PlanPoint pp;
  1028. while(s<pspiral->GetLength())
  1029. {
  1030. pspiral->GetCoords(s0+s,x,y,hdg);
  1031. pp.x = x;
  1032. pp.y = y;
  1033. pp.hdg = hdg;
  1034. pp.dis = s;
  1035. pp.mS = pspiral->GetS() + s;
  1036. xvectorPP.push_back(pp);
  1037. s = s+fspace;
  1038. }
  1039. return xvectorPP;
  1040. }
  1041. static std::vector<PlanPoint> getpoly3dpoint(GeometryPoly3 * ppoly,const double fspace = 0.1)
  1042. {
  1043. double x,y;
  1044. x = ppoly->GetX();
  1045. y = ppoly->GetY();
  1046. double A,B,C,D;
  1047. A = ppoly->GetA();
  1048. B = ppoly->GetB();
  1049. C = ppoly->GetC();
  1050. D = ppoly->GetD();
  1051. const double steplim = fspace;
  1052. double du = steplim;
  1053. double u = 0;
  1054. double v = 0;
  1055. double oldx,oldy;
  1056. oldx = x;
  1057. oldy = y;
  1058. double xstart,ystart;
  1059. xstart = x;
  1060. ystart = y;
  1061. double hdgstart = ppoly->GetHdg();
  1062. double flen = 0;
  1063. std::vector<PlanPoint> xvectorPP;
  1064. PlanPoint pp;
  1065. pp.x = xstart;
  1066. pp.y = ystart;
  1067. pp.hdg = hdgstart;
  1068. pp.dis = 0;
  1069. pp.mS = ppoly->GetS();
  1070. xvectorPP.push_back(pp);
  1071. u = du;
  1072. while(flen < ppoly->GetLength())
  1073. {
  1074. double fdis = 0;
  1075. v = A + B*u + C*u*u + D*u*u*u;
  1076. x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
  1077. y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
  1078. fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
  1079. double hdg = CalcHdg(QPointF(oldx,oldy),QPointF(x,y));
  1080. oldx = x;
  1081. oldy = y;
  1082. if(fdis>(steplim*2.0))du = du/2.0;
  1083. flen = flen + fdis;
  1084. u = u + du;
  1085. pp.x = x;
  1086. pp.y = y;
  1087. pp.hdg = hdg;
  1088. // s = s+ dt;
  1089. pp.dis = flen;;
  1090. pp.mS = ppoly->GetS() + flen;
  1091. xvectorPP.push_back(pp);
  1092. }
  1093. return xvectorPP;
  1094. }
  1095. static std::vector<PlanPoint> getparampoly3dpoint(GeometryParamPoly3 * parc,const double fspace = 0.1)
  1096. {
  1097. double s = 0.1;
  1098. std::vector<PlanPoint> xvectorPP;
  1099. PlanPoint pp;
  1100. double xold,yold;
  1101. xold = parc->GetX();
  1102. yold = parc->GetY();
  1103. double hdg0 = parc->GetHdg();
  1104. pp.x = xold;
  1105. pp.y = yold;
  1106. pp.hdg = hdg0;
  1107. pp.dis = 0;
  1108. // xvectorPP.push_back(pp);
  1109. double dt = 1.0;
  1110. double tcount = parc->GetLength()/0.1;
  1111. if(tcount > 0)
  1112. {
  1113. dt = 1.0/tcount;
  1114. }
  1115. double t;
  1116. s = dt;
  1117. s = 0;
  1118. double ua,ub,uc,ud,va,vb,vc,vd;
  1119. ua = parc->GetuA();ub= parc->GetuB();uc= parc->GetuC();ud = parc->GetuD();
  1120. va = parc->GetvA();vb= parc->GetvB();vc= parc->GetvC();vd = parc->GetvD();
  1121. double s_start = parc->GetS();
  1122. while(s < parc->GetLength())
  1123. {
  1124. double x, y,hdg;
  1125. parc->GetCoords(s_start+s,x,y,hdg);
  1126. pp.x = x;
  1127. pp.y = y;
  1128. pp.hdg = hdg;
  1129. pp.dis = pp.dis + fspace;;
  1130. pp.mS = s_start + s;
  1131. xvectorPP.push_back(pp);
  1132. s = s+ fspace;
  1133. }
  1134. return xvectorPP;
  1135. }
  1136. std::vector<PlanPoint> GetPoint(pathsection xpath,const double fspace = 0.1)
  1137. {
  1138. Road * pRoad = xpath.mpRoad;
  1139. //s_start s_end for select now section data.
  1140. double s_start,s_end;
  1141. LaneSection * pLS = pRoad->GetLaneSection(xpath.msectionid);
  1142. s_start = pLS->GetS();
  1143. if(xpath.msectionid == (pRoad->GetLaneSectionCount()-1))s_end = pRoad->GetRoadLength();
  1144. else
  1145. {
  1146. s_end = pRoad->GetLaneSection(xpath.msectionid+1)->GetS();
  1147. }
  1148. // if(xpath.mroadid == 10190)
  1149. // {
  1150. // int a = 1;
  1151. // a++;
  1152. // }
  1153. std::vector<PlanPoint> xvectorPPS;
  1154. double s = 0;
  1155. int i;
  1156. for(i=0;i<pRoad->GetGeometryBlockCount();i++)
  1157. {
  1158. GeometryBlock * pgb = pRoad->GetGeometryBlock(i);
  1159. RoadGeometry * prg = pgb->GetGeometryAt(0);
  1160. std::vector<PlanPoint> xvectorPP;
  1161. if(i<(pRoad->GetGeometryBlockCount() -0))
  1162. {
  1163. if(prg->GetS()>s_end)
  1164. {
  1165. continue;
  1166. }
  1167. if((prg->GetS() + prg->GetLength())<s_start)
  1168. {
  1169. continue;
  1170. }
  1171. }
  1172. double s1 = prg->GetLength();
  1173. switch (prg->GetGeomType()) {
  1174. case 0:
  1175. xvectorPP = getlinepoint((GeometryLine *)prg,fspace);
  1176. break;
  1177. case 1:
  1178. xvectorPP = getspiralpoint((GeometrySpiral *)prg,fspace);
  1179. break;
  1180. case 2:
  1181. xvectorPP = getarcpoint((GeometryArc *)prg,fspace);
  1182. break;
  1183. case 3:
  1184. xvectorPP = getpoly3dpoint((GeometryPoly3 *)prg,fspace);
  1185. break;
  1186. case 4:
  1187. xvectorPP = getparampoly3dpoint((GeometryParamPoly3 *)prg,fspace);
  1188. break;
  1189. default:
  1190. break;
  1191. }
  1192. int j;
  1193. if(prg->GetS()<s_start)
  1194. {
  1195. s1 = prg->GetLength() -(s_start - prg->GetS());
  1196. }
  1197. if((prg->GetS() + prg->GetLength())>s_end)
  1198. {
  1199. s1 = s_end - prg->GetS();
  1200. }
  1201. for(j=0;j<xvectorPP.size();j++)
  1202. {
  1203. PlanPoint pp = xvectorPP.at(j);
  1204. // double foffset = pRoad->GetLaneOffsetValue(pp.mS);
  1205. // if(fabs(foffset)>0.001)
  1206. // {
  1207. // pp.x = pp.x + foffset * cos(pp.hdg + M_PI/2.0);
  1208. // pp.y = pp.y + foffset * sin(pp.hdg + M_PI/2.0);
  1209. // }
  1210. pp.mfCurvature = pRoad->GetRoadCurvature(pp.mS);
  1211. if(((pp.dis+prg->GetS()) >= s_start) &&((pp.dis+prg->GetS()) <= s_end))
  1212. {
  1213. if(s_start > prg->GetS())
  1214. {
  1215. pp.dis = s + pp.dis -(s_start - prg->GetS());
  1216. }
  1217. else
  1218. {
  1219. pp.dis = s+ pp.dis;
  1220. }
  1221. pp.nRoadID = atoi(pRoad->GetRoadId().data());
  1222. xvectorPPS.push_back(pp);
  1223. }
  1224. // if((prg->GetS()>s_start)&&((prg->GetS() + prg->GetLength())<s_end))
  1225. // {
  1226. // pp.dis = s + pp.dis;
  1227. // pp.nRoadID = atoi(pRoad->GetRoadId().data());
  1228. // xvectorPPS.push_back(pp);
  1229. // }
  1230. // else
  1231. // {
  1232. // if(prg->GetS()<s_start)
  1233. // {
  1234. // }
  1235. // else
  1236. // {
  1237. // if(pp.dis<(s_end -prg->GetS()))
  1238. // {
  1239. // pp.dis = s + pp.dis;
  1240. // pp.nRoadID = atoi(pRoad->GetRoadId().data());
  1241. // xvectorPPS.push_back(pp);
  1242. // }
  1243. // }
  1244. // }
  1245. }
  1246. s = s+ s1;
  1247. }
  1248. return xvectorPPS;
  1249. }
  1250. std::vector<PlanPoint> GetPoint(Road * pRoad)
  1251. {
  1252. std::vector<PlanPoint> xvectorPPS;
  1253. double s = 0;
  1254. int i;
  1255. for(i=0;i<pRoad->GetGeometryBlockCount();i++)
  1256. {
  1257. GeometryBlock * pgb = pRoad->GetGeometryBlock(i);
  1258. RoadGeometry * prg = pgb->GetGeometryAt(0);
  1259. std::vector<PlanPoint> xvectorPP;
  1260. double s1 = prg->GetLength();
  1261. switch (prg->GetGeomType()) {
  1262. case 0:
  1263. xvectorPP = getlinepoint((GeometryLine *)prg);
  1264. break;
  1265. case 1:
  1266. xvectorPP = getspiralpoint((GeometrySpiral *)prg);
  1267. break;
  1268. case 2:
  1269. xvectorPP = getarcpoint((GeometryArc *)prg);
  1270. break;
  1271. case 3:
  1272. xvectorPP = getpoly3dpoint((GeometryPoly3 *)prg);
  1273. break;
  1274. case 4:
  1275. xvectorPP = getparampoly3dpoint((GeometryParamPoly3 *)prg);
  1276. break;
  1277. default:
  1278. break;
  1279. }
  1280. int j;
  1281. for(j=0;j<xvectorPP.size();j++)
  1282. {
  1283. PlanPoint pp = xvectorPP.at(j);
  1284. pp.dis = s + pp.dis;
  1285. pp.nRoadID = atoi(pRoad->GetRoadId().data());
  1286. xvectorPPS.push_back(pp);
  1287. }
  1288. s = s+ s1;
  1289. }
  1290. unsigned int j;
  1291. for(j=0;j<xvectorPPS.size();j++)
  1292. {
  1293. xvectorPPS.at(j).mfCurvature = pRoad->GetRoadCurvature(xvectorPPS.at(j).mS);
  1294. }
  1295. return xvectorPPS;
  1296. }
  1297. int indexinroadpoint(std::vector<PlanPoint> xvectorPP,double x,double y)
  1298. {
  1299. int nrtn = 0;
  1300. int i;
  1301. int dismin = 1000;
  1302. for(i=0;i<xvectorPP.size();i++)
  1303. {
  1304. double dis = sqrt(pow(xvectorPP.at(i).x - x,2) + pow(xvectorPP.at(i).y -y,2));
  1305. if(dis <dismin)
  1306. {
  1307. dismin = dis;
  1308. nrtn = i;
  1309. }
  1310. }
  1311. if(dismin > 10.0)
  1312. {
  1313. std::cout<<"indexinroadpoint near point is error. dis is "<<dismin<<std::endl;
  1314. }
  1315. return nrtn;
  1316. }
  1317. double getwidth(Road * pRoad, int nlane)
  1318. {
  1319. double frtn = 0;
  1320. int i;
  1321. int nlanecount = pRoad->GetLaneSection(0)->GetLaneCount();
  1322. for(i=0;i<nlanecount;i++)
  1323. {
  1324. if(nlane == pRoad->GetLaneSection(0)->GetLane(i)->GetId())
  1325. {
  1326. LaneWidth* pLW = pRoad->GetLaneSection(0)->GetLane(i)->GetLaneWidth(0);
  1327. if(pLW != 0)
  1328. {
  1329. frtn = pRoad->GetLaneSection(0)->GetLane(i)->GetLaneWidth(0)->GetA();
  1330. break;
  1331. }
  1332. }
  1333. }
  1334. return frtn;
  1335. }
  1336. double getoff(Road * pRoad,int nlane)
  1337. {
  1338. double off = getwidth(pRoad,nlane)/2.0;
  1339. if(nlane < 0)off = off * (-1.0);
  1340. // int nlanecount = pRoad->GetLaneSection(0)->GetLaneCount();
  1341. int i;
  1342. if(nlane > 0)
  1343. off = off + getwidth(pRoad,0)/2.0;
  1344. else
  1345. off = off - getwidth(pRoad,0)/2.0;
  1346. if(nlane > 0)
  1347. {
  1348. for(i=1;i<nlane;i++)
  1349. {
  1350. off = off + getwidth(pRoad,i);
  1351. }
  1352. }
  1353. else
  1354. {
  1355. for(i=-1;i>nlane;i--)
  1356. {
  1357. off = off - getwidth(pRoad,i);
  1358. }
  1359. }
  1360. // return 0;
  1361. return off;
  1362. }
  1363. namespace iv {
  1364. struct lanewidthabcd
  1365. {
  1366. int nlane;
  1367. double A;
  1368. double B;
  1369. double C;
  1370. double D;
  1371. };
  1372. }
  1373. double getwidth(Road * pRoad, int nlane,std::vector<iv::lanewidthabcd> xvectorlwa,double s)
  1374. {
  1375. if(nlane == 0)return 0;
  1376. double frtn = 0;
  1377. std::vector<double> xvectorlanewidth;
  1378. if(nlane<0)
  1379. xvectorlanewidth = pRoad->GetLaneWidthVector(s,2);
  1380. else
  1381. xvectorlanewidth = pRoad->GetLaneWidthVector(s,1);
  1382. if(abs(nlane)<=xvectorlanewidth.size())
  1383. {
  1384. return xvectorlanewidth[abs(nlane)-1];
  1385. }
  1386. else
  1387. {
  1388. std::cout<<" Warning: getwidth get lane width fault."<<std::endl;
  1389. return 0;
  1390. }
  1391. // int i;
  1392. // int nlanecount = xvectorlwa.size();
  1393. // for(i=0;i<nlanecount;i++)
  1394. // {
  1395. // if(nlane == xvectorlwa.at(i).nlane)
  1396. // {
  1397. // iv::lanewidthabcd * plwa = &xvectorlwa.at(i);
  1398. // frtn = plwa->A + plwa->B*s + plwa->C *s*s + plwa->D *s*s*s;
  1399. // break;
  1400. // }
  1401. // }
  1402. return frtn;
  1403. }
  1404. std::vector<iv::lanewidthabcd> GetLaneWidthABCD(Road * pRoad)
  1405. {
  1406. std::vector<iv::lanewidthabcd> xvectorlwa;
  1407. if(pRoad->GetLaneSectionCount()<1)return xvectorlwa;
  1408. int i;
  1409. LaneSection * pLS = pRoad->GetLaneSection(0);
  1410. // if(pRoad->GetLaneSectionCount() > 1)
  1411. // {
  1412. // for(i=0;i<(pRoad->GetLaneSectionCount()-1);i++)
  1413. // {
  1414. // if(s>pRoad->GetLaneSection(i+1)->GetS())
  1415. // {
  1416. // pLS = pRoad->GetLaneSection(i+1);
  1417. // }
  1418. // else
  1419. // {
  1420. // break;
  1421. // }
  1422. // }
  1423. // }
  1424. int nlanecount = pLS->GetLaneCount();
  1425. for(i=0;i<nlanecount;i++)
  1426. {
  1427. iv::lanewidthabcd xlwa;
  1428. LaneWidth* pLW = pLS->GetLane(i)->GetLaneWidth(0);
  1429. xlwa.nlane = pLS->GetLane(i)->GetId();
  1430. if(pLW != 0)
  1431. {
  1432. xlwa.A = pLW->GetA();
  1433. xlwa.B = pLW->GetB();
  1434. xlwa.C = pLW->GetC();
  1435. xlwa.D = pLW->GetD();
  1436. }
  1437. else
  1438. {
  1439. xlwa.A = 0;
  1440. xlwa.B = 0;
  1441. xlwa.C = 0;
  1442. xlwa.D = 0;
  1443. }
  1444. // if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
  1445. xvectorlwa.push_back(xlwa); //Calculate Road Width, not driving need add in.
  1446. }
  1447. return xvectorlwa;
  1448. }
  1449. inline double getoff(int nlane,double s,std::vector<iv::lanewidthabcd> xvectorLWA,std::vector<int> xvectorIndex)
  1450. {
  1451. int i;
  1452. double off = 0;
  1453. double a,b,c,d;
  1454. if(xvectorIndex.size() == 0)return off;
  1455. for(i=0;i<(xvectorIndex.size()-1);i++)
  1456. {
  1457. a = xvectorLWA[xvectorIndex[i]].A;
  1458. b = xvectorLWA[xvectorIndex[i]].B;
  1459. c = xvectorLWA[xvectorIndex[i]].C;
  1460. d = xvectorLWA[xvectorIndex[i]].D;
  1461. if(xvectorLWA[xvectorIndex[i]].nlane != 0)
  1462. {
  1463. off = off + a + b*s + c*s*s + d*s*s*s;
  1464. }
  1465. else
  1466. {
  1467. off = off + (a + b*s + c*s*s + d*s*s*s)/2.0;
  1468. }
  1469. }
  1470. i = xvectorIndex.size()-1;
  1471. a = xvectorLWA[xvectorIndex[i]].A;
  1472. b = xvectorLWA[xvectorIndex[i]].B;
  1473. c = xvectorLWA[xvectorIndex[i]].C;
  1474. d = xvectorLWA[xvectorIndex[i]].D;
  1475. off = off + (a + b*s + c*s*s + d*s*s*s)/2.0;
  1476. if(nlane < 0) off = off*(-1.0);
  1477. // std::cout<<"s is "<<s<<std::endl;
  1478. // std::cout<<" off is "<<off<<std::endl;
  1479. return off;
  1480. }
  1481. double GetRoadWidth(Road * pRoad,int nlane,double s)
  1482. {
  1483. if(nlane<0)return pRoad->GetRightRoadWidth(s);
  1484. return pRoad->GetLeftRoadWidth(s);
  1485. }
  1486. //double GetRoadWidth(std::vector<iv::lanewidthabcd> xvectorLWA,int nlane,double s)
  1487. //{
  1488. // double fwidth = 0;
  1489. // int i;
  1490. // double a,b,c,d;
  1491. // int nsize = xvectorLWA.size();
  1492. // for(i=0;i<nsize;i++)
  1493. // {
  1494. // if(nlane*(xvectorLWA[i].nlane)>0)
  1495. // {
  1496. // a = xvectorLWA[i].A;
  1497. // b = xvectorLWA[i].B;
  1498. // c = xvectorLWA[i].C;
  1499. // d = xvectorLWA[i].D;
  1500. // fwidth = fwidth + a + b*s +c*s*s + d*s*s*s;
  1501. // }
  1502. // }
  1503. // return fwidth;
  1504. //}
  1505. int GetLaneOriTotal(Road * pRoad, int nlane,double s,int & nori, int & ntotal,double & fSpeed,bool & bNoavoid)
  1506. {
  1507. if(pRoad->GetLaneSectionCount() < 1)return -1;
  1508. LaneSection * pLS = pRoad->GetLaneSection(0);
  1509. int i;
  1510. if(pRoad->GetLaneSectionCount() > 1)
  1511. {
  1512. for(i=0;i<(pRoad->GetLaneSectionCount()-1);i++)
  1513. {
  1514. if(s>pRoad->GetLaneSection(i+1)->GetS())
  1515. {
  1516. pLS = pRoad->GetLaneSection(i+1);
  1517. }
  1518. else
  1519. {
  1520. break;
  1521. }
  1522. }
  1523. }
  1524. nori = 0;
  1525. ntotal = 0;
  1526. fSpeed = -1; //if -1 no speedlimit for map
  1527. pRoad->GetRoadSpeedMax(s,fSpeed); //Get Road Speed Limit.
  1528. pRoad->GetRoadNoavoid(s,bNoavoid);
  1529. int nlanecount = pLS->GetLaneCount();
  1530. for(i=0;i<nlanecount;i++)
  1531. {
  1532. int nlaneid = pLS->GetLane(i)->GetId();
  1533. if(nlaneid == nlane)
  1534. {
  1535. Lane * pLane = pLS->GetLane(i);
  1536. if(pLane->GetLaneSpeedCount() > 0)
  1537. {
  1538. LaneSpeed * pLSpeed = pLane->GetLaneSpeed(0);
  1539. int j;
  1540. int nspeedcount = pLane->GetLaneSpeedCount();
  1541. for(j=0;j<(nspeedcount -1);j++)
  1542. {
  1543. if((s-pLS->GetS())>=pLane->GetLaneSpeed(j+1)->GetS())
  1544. {
  1545. pLSpeed = pLane->GetLaneSpeed(j+1);
  1546. }
  1547. else
  1548. {
  1549. break;
  1550. }
  1551. }
  1552. if(pLSpeed->GetS()<=(s-pLS->GetS()))fSpeed = pLSpeed->GetMax();
  1553. }
  1554. }
  1555. if(nlane<0)
  1556. {
  1557. if(nlaneid < 0)
  1558. {
  1559. if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
  1560. {
  1561. ntotal++;
  1562. if(nlaneid<nlane)nori++;
  1563. }
  1564. }
  1565. }
  1566. else
  1567. {
  1568. if(nlaneid > 0)
  1569. {
  1570. if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
  1571. {
  1572. ntotal++;
  1573. if(nlaneid > nlane)nori++;
  1574. }
  1575. }
  1576. }
  1577. }
  1578. return 0;
  1579. }
  1580. std::vector<int> GetLWIndex(std::vector<iv::lanewidthabcd> xvectorLWA,int nlane)
  1581. {
  1582. std::vector<int> xvectorindex;
  1583. int i;
  1584. if(nlane >= 0)
  1585. {
  1586. for(i=0;i<=nlane;i++)
  1587. {
  1588. int j;
  1589. int nsize = xvectorLWA.size();
  1590. for(j=0;j<nsize;j++)
  1591. {
  1592. if(i == xvectorLWA.at(j).nlane )
  1593. {
  1594. xvectorindex.push_back(j);
  1595. break;
  1596. }
  1597. }
  1598. }
  1599. }
  1600. else
  1601. {
  1602. for(i=0;i>=nlane;i--)
  1603. {
  1604. int j;
  1605. int nsize = xvectorLWA.size();
  1606. for(j=0;j<nsize;j++)
  1607. {
  1608. if(i == xvectorLWA.at(j).nlane )
  1609. {
  1610. xvectorindex.push_back(j);
  1611. break;
  1612. }
  1613. }
  1614. }
  1615. }
  1616. return xvectorindex;
  1617. }
  1618. void CalcBorringRoad(pathsection xps,std::vector<PlanPoint> & xvectorPP)
  1619. {
  1620. if(xps.mpRoad->GetRoadBorrowCount() == 0)
  1621. {
  1622. return;
  1623. }
  1624. Road * pRoad = xps.mpRoad;
  1625. unsigned int nborrowsize = pRoad->GetRoadBorrowCount();
  1626. unsigned int i;
  1627. unsigned int nPPCount = xvectorPP.size();
  1628. for(i=0;i<nborrowsize;i++)
  1629. {
  1630. RoadBorrow * pborrow = pRoad->GetRoadBorrow(i);
  1631. if(pborrow == NULL)
  1632. {
  1633. std::cout<<"warning:can't get borrow"<<std::endl;
  1634. continue;
  1635. }
  1636. if((pborrow->GetMode() == "All")||((pborrow->GetMode()=="R2L")&&(xps.mainsel<0))||((pborrow->GetMode()=="L2R")&&(xps.mainsel>0)))
  1637. {
  1638. unsigned int j;
  1639. double soffset = pborrow->GetS();
  1640. double borrowlen = pborrow->GetLength();
  1641. for(j=0;j<xvectorPP.size();j++)
  1642. {
  1643. if((xvectorPP[j].mS>=soffset)&&(xvectorPP[j].mS<=(soffset + borrowlen)))
  1644. {
  1645. xvectorPP[j].mbBoringRoad = true;
  1646. }
  1647. }
  1648. }
  1649. }
  1650. }
  1651. void CalcInLaneAvoid(pathsection xps,std::vector<PlanPoint> & xvectorPP,const double fvehiclewidth,
  1652. const int nchang1,const int nchang2,const int nchangpoint)
  1653. {
  1654. if(xvectorPP.size()<2)return;
  1655. bool bInlaneavoid = false;
  1656. int i;
  1657. if((xps.mbStartToMainChange == false) && (xps.mbMainToEndChange == false))
  1658. {
  1659. if(xps.mpRoad->GetRoadLength()<30)
  1660. {
  1661. double hdgdiff = xvectorPP.at(xvectorPP.size()-1).hdg - xvectorPP.at(0).hdg;
  1662. if(hdgdiff<0)hdgdiff = hdgdiff + 2.0*M_PI;
  1663. if(hdgdiff>(M_PI/3.0)&&(hdgdiff<(5.0*M_PI/3.0)))
  1664. bInlaneavoid = false;
  1665. else
  1666. bInlaneavoid = true;
  1667. }
  1668. else
  1669. {
  1670. bInlaneavoid = true;
  1671. }
  1672. }
  1673. else
  1674. {
  1675. if(xps.mpRoad->GetRoadLength()>100)bInlaneavoid = true;
  1676. }
  1677. if(bInlaneavoid == false)
  1678. {
  1679. int nvpsize = xvectorPP.size();
  1680. for(i=0;i<nvpsize;i++)
  1681. {
  1682. xvectorPP.at(i).bInlaneAvoid = false;
  1683. xvectorPP.at(i).mx_left = xvectorPP.at(i).x;
  1684. xvectorPP.at(i).my_left = xvectorPP.at(i).y;
  1685. xvectorPP.at(i).mx_right = xvectorPP.at(i).x;
  1686. xvectorPP.at(i).my_right = xvectorPP.at(i).y;
  1687. }
  1688. }
  1689. else
  1690. {
  1691. int nvpsize = xvectorPP.size();
  1692. for(i=0;i<nvpsize;i++)xvectorPP.at(i).bInlaneAvoid = true;
  1693. if((xps.mbStartToMainChange == true)||(xps.mbMainToEndChange == true))
  1694. {
  1695. if(xps.mbStartToMainChange == true)
  1696. {
  1697. for(i=(nchang1 - nchangpoint/2);i<(nchang1 + nchangpoint/2);i++)
  1698. {
  1699. if((i>=0)&&(i<nvpsize))
  1700. xvectorPP.at(i).bInlaneAvoid = false;
  1701. }
  1702. }
  1703. if(xps.mbMainToEndChange)
  1704. {
  1705. for(i=(nchang2 - nchangpoint/2);i<(nchang2 + nchangpoint/2);i++)
  1706. {
  1707. if((i>=0)&&(i<nvpsize))
  1708. xvectorPP.at(i).bInlaneAvoid = false;
  1709. }
  1710. }
  1711. }
  1712. for(i=0;i<nvpsize;i++)
  1713. {
  1714. if(xvectorPP.at(i).bInlaneAvoid)
  1715. {
  1716. double foff = xvectorPP.at(i).mfDisToLaneLeft -0.3-fvehiclewidth*0.5; //30cm + 0.5vehcilewidth
  1717. if(foff < 0.3)
  1718. {
  1719. xvectorPP.at(i).bInlaneAvoid = false;
  1720. xvectorPP.at(i).mx_left = xvectorPP.at(i).x;
  1721. xvectorPP.at(i).my_left = xvectorPP.at(i).y;
  1722. xvectorPP.at(i).mx_right = xvectorPP.at(i).x;
  1723. xvectorPP.at(i).my_right = xvectorPP.at(i).y;
  1724. }
  1725. else
  1726. {
  1727. xvectorPP.at(i).mx_left = xvectorPP.at(i).x + foff * cos(xvectorPP.at(i).hdg + M_PI/2.0);
  1728. xvectorPP.at(i).my_left = xvectorPP.at(i).y + foff * sin(xvectorPP.at(i).hdg + M_PI/2.0);
  1729. xvectorPP.at(i).mx_right = xvectorPP.at(i).x + foff * cos(xvectorPP.at(i).hdg - M_PI/2.0);
  1730. xvectorPP.at(i).my_right = xvectorPP.at(i).y + foff * sin(xvectorPP.at(i).hdg - M_PI/2.0);
  1731. }
  1732. }
  1733. }
  1734. }
  1735. }
  1736. double getoff(Road * pRoad,int nlane,const double s)
  1737. {
  1738. int i;
  1739. int nLSCount = pRoad->GetLaneSectionCount();
  1740. double s_section = 0;
  1741. double foff = 0;
  1742. for(i=0;i<nLSCount;i++)
  1743. {
  1744. LaneSection * pLS = pRoad->GetLaneSection(i);
  1745. if(i<(nLSCount -1))
  1746. {
  1747. if(pRoad->GetLaneSection(i+1)->GetS()<s)
  1748. {
  1749. continue;
  1750. }
  1751. }
  1752. s_section = pLS->GetS();
  1753. int nlanecount = pLS->GetLaneCount();
  1754. int j;
  1755. for(j=0;j<nlanecount;j++)
  1756. {
  1757. Lane * pLane = pLS->GetLane(j);
  1758. int k;
  1759. double s_lane = s-s_section;
  1760. if(pLane->GetId() != 0)
  1761. {
  1762. for(k=0;k<pLane->GetLaneWidthCount();k++)
  1763. {
  1764. if(k<(pLane->GetLaneWidthCount()-1))
  1765. {
  1766. if((pLane->GetLaneWidth(k+1)->GetS()+s_section)<s)
  1767. {
  1768. continue;
  1769. }
  1770. }
  1771. s_lane = pLane->GetLaneWidth(k)->GetS();
  1772. break;
  1773. }
  1774. LaneWidth * pLW = pLane->GetLaneWidth(k);
  1775. if(pLW == 0)
  1776. {
  1777. std::cout<<"not find LaneWidth"<<std::endl;
  1778. break;
  1779. }
  1780. double fds = s - s_lane - s_section;
  1781. double fwidth= pLW->GetA() + pLW->GetB() * fds
  1782. +pLW->GetC() * pow(fds,2) + pLW->GetD() * pow(fds,3);
  1783. // if((pRoad->GetRoadId() == "211210") &&(nlane == -1) &&(pLane->GetId() == -1))
  1784. // {
  1785. // qDebug("fs is %f width is %f",fds,fwidth);
  1786. // }
  1787. if(nlane == pLane->GetId())
  1788. {
  1789. foff = foff + fwidth/2.0;
  1790. }
  1791. if((nlane*(pLane->GetId())>0)&&(abs(nlane)>abs(pLane->GetId())))
  1792. {
  1793. foff = foff + fwidth;
  1794. }
  1795. }
  1796. }
  1797. break;
  1798. }
  1799. if(pRoad->GetLaneOffsetCount()>0)
  1800. {
  1801. int nLOCount = pRoad->GetLaneOffsetCount();
  1802. int isel = -1;
  1803. for(i=0;i<(nLOCount-1);i++)
  1804. {
  1805. if(pRoad->GetLaneOffset(i+1)->GetS()>s)
  1806. {
  1807. isel = i;
  1808. break;
  1809. }
  1810. }
  1811. if(isel < 0)isel = nLOCount-1;
  1812. LaneOffset * pLO = pRoad->GetLaneOffset(isel);
  1813. double s_off = s - pLO->GetS();
  1814. double off1 = pLO->Geta() + pLO->Getb()*s_off + pLO->Getc() * s_off * s_off
  1815. +pLO->Getd() * s_off * s_off * s_off;
  1816. foff = foff - off1;
  1817. }
  1818. if(nlane<0)foff = foff*(-1);
  1819. return foff;
  1820. }
  1821. std::vector<PlanPoint> GetLanePoint(pathsection xps,std::vector<PlanPoint> xvPP,const double fvehiclewidth)
  1822. {
  1823. std::vector<PlanPoint> xvectorPP;
  1824. std::vector<iv::lanewidthabcd> xvectorLWA = GetLaneWidthABCD(xps.mpRoad);
  1825. std::vector<int> xvectorindex1,xvectorindex2,xvectorindex3;
  1826. int nchange1,nchange2;
  1827. int nlane1,nlane2,nlane3;
  1828. if(xps.mnStartLaneSel == xps.mnEndLaneSel)
  1829. {
  1830. xps.mainsel = xps.mnStartLaneSel;
  1831. xps.mbStartToMainChange = false;
  1832. xps.mbMainToEndChange = false;
  1833. }
  1834. else
  1835. {
  1836. if(xps.mpRoad->GetRoadLength() < 100)
  1837. {
  1838. xps.mainsel = xps.mnEndLaneSel;
  1839. xps.mbStartToMainChange = true;
  1840. xps.mbMainToEndChange = false;
  1841. }
  1842. }
  1843. double off1,off2,off3;
  1844. if(xps.mnStartLaneSel < 0)
  1845. {
  1846. off1 = getoff(xps.mpRoad,xps.mnStartLaneSel);
  1847. off2 = getoff(xps.mpRoad,xps.mainsel);
  1848. off3 = getoff(xps.mpRoad,xps.mnEndLaneSel);
  1849. xvectorindex1 = GetLWIndex(xvectorLWA,xps.mnStartLaneSel);
  1850. xvectorindex2 = GetLWIndex(xvectorLWA,xps.mainsel);
  1851. xvectorindex3 = GetLWIndex(xvectorLWA,xps.mnEndLaneSel);
  1852. nlane1 = xps.mnStartLaneSel;
  1853. nlane2 = xps.mainsel;
  1854. nlane3 = xps.mnEndLaneSel;
  1855. }
  1856. else
  1857. {
  1858. off3 = getoff(xps.mpRoad,xps.mnStartLaneSel);
  1859. off2 = getoff(xps.mpRoad,xps.mainsel);
  1860. off1 = getoff(xps.mpRoad,xps.mnEndLaneSel);
  1861. xvectorindex3 = GetLWIndex(xvectorLWA,xps.mnStartLaneSel);
  1862. xvectorindex2 = GetLWIndex(xvectorLWA,xps.mainsel);
  1863. xvectorindex1 = GetLWIndex(xvectorLWA,xps.mnEndLaneSel);
  1864. nlane3 = xps.mnStartLaneSel;
  1865. nlane2 = xps.mainsel;
  1866. nlane1 = xps.mnEndLaneSel;
  1867. }
  1868. int nchangepoint = 300;
  1869. if((nchangepoint * 3) > xvPP.size())
  1870. {
  1871. nchangepoint = xvPP.size()/3;
  1872. }
  1873. int nsize = xvPP.size();
  1874. nchange1 = nsize/3;
  1875. if(nchange1>500)nchange1 = 500;
  1876. nchange2 = nsize*2/3;
  1877. if( (nsize-nchange2)>500)nchange2 = nsize-500;
  1878. // if(nsize < 1000)
  1879. // {
  1880. // std::cout<<"GetLanePoint Error. road id is "<<xps.mpRoad->GetRoadId()<<std::endl;
  1881. // return xvectorPP;
  1882. // }
  1883. double x,y;
  1884. int i;
  1885. if(xps.mainsel < 0)
  1886. {
  1887. for(i=0;i<nsize;i++)
  1888. {
  1889. PlanPoint pp = xvPP.at(i);
  1890. // off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
  1891. off1 = getoff(xps.mpRoad,nlane2,pp.mS);
  1892. pp.x = pp.x + off1 *cos(pp.hdg + M_PI/2.0);
  1893. pp.y = pp.y + off1 *sin(pp.hdg + M_PI/2.0);
  1894. pp.nlrchange = 0;
  1895. if(xps.mainsel != xps.secondsel)
  1896. {
  1897. off1 = getoff(xps.mpRoad,xps.secondsel,pp.mS);
  1898. pp.mfSecx = xvPP.at(i).x + off1 *cos(pp.hdg + M_PI/2.0);
  1899. pp.mfSecy = xvPP.at(i).y + off1 *sin(pp.hdg + M_PI/2.0);
  1900. if(xps.mainsel >xps.secondsel)
  1901. {
  1902. pp.nlrchange = 1;
  1903. }
  1904. else
  1905. {
  1906. pp.nlrchange = 2;
  1907. }
  1908. }
  1909. else
  1910. {
  1911. pp.mfSecx = pp.x ;
  1912. pp.mfSecy = pp.y ;
  1913. }
  1914. pp.mWidth = getwidth(xps.mpRoad,xps.mainsel,xvectorLWA,pp.mS);
  1915. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1916. pp.lanmp = 0;
  1917. pp.mfDisToRoadLeft = off1*(-1);
  1918. pp.mfRoadWidth = GetRoadWidth(xps.mpRoad,xps.mainsel,pp.mS);
  1919. GetLaneOriTotal(xps.mpRoad,xps.mainsel,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed,pp.mbNoavoid);
  1920. xvectorPP.push_back(pp);
  1921. }
  1922. }
  1923. else
  1924. {
  1925. for(i=0;i<nsize;i++)
  1926. {
  1927. PlanPoint pp = xvPP.at(i);
  1928. // off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
  1929. off1 = getoff(xps.mpRoad,nlane2,pp.mS);
  1930. pp.x = pp.x + off1 *cos(pp.hdg + M_PI/2.0);
  1931. pp.y = pp.y + off1 *sin(pp.hdg + M_PI/2.0);
  1932. pp.nlrchange = 0;
  1933. if(xps.mainsel != xps.secondsel)
  1934. {
  1935. off1 = getoff(xps.mpRoad,xps.secondsel,pp.mS);
  1936. pp.mfSecx = xvPP.at(i).x + off1 *cos(pp.hdg + M_PI/2.0);
  1937. pp.mfSecy = xvPP.at(i).y + off1 *sin(pp.hdg + M_PI/2.0);
  1938. if(xps.mainsel >xps.secondsel)
  1939. {
  1940. pp.nlrchange = 2;
  1941. }
  1942. else
  1943. {
  1944. pp.nlrchange = 1;
  1945. }
  1946. }
  1947. else
  1948. {
  1949. pp.mfSecx = pp.x ;
  1950. pp.mfSecy = pp.y ;
  1951. }
  1952. pp.mWidth = getwidth(xps.mpRoad,xps.mainsel,xvectorLWA,pp.mS);
  1953. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1954. pp.lanmp = 0;
  1955. pp.mfDisToRoadLeft = off1;
  1956. pp.mfRoadWidth = GetRoadWidth(xps.mpRoad,xps.mainsel,pp.mS);
  1957. GetLaneOriTotal(xps.mpRoad,xps.mainsel,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed,pp.mbNoavoid);
  1958. pp.hdg = pp.hdg + M_PI;
  1959. xvectorPP.push_back(pp);
  1960. }
  1961. // for(i=0;i<(nchange1- nchangepoint/2);i++)
  1962. // {
  1963. // PlanPoint pp = xvPP.at(i);
  1964. // off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
  1965. // pp.x = pp.x + off1 *cos(pp.hdg + M_PI/2.0);
  1966. // pp.y = pp.y + off1 *sin(pp.hdg + M_PI/2.0);
  1967. // pp.hdg = pp.hdg + M_PI;
  1968. // pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  1969. // pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1970. // pp.lanmp = 0;
  1971. // pp.mfDisToRoadLeft = off1;
  1972. // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
  1973. // GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1974. // xvectorPP.push_back(pp);
  1975. // }
  1976. // for(i=(nchange1 - nchangepoint/2);i<(nchange1+nchangepoint/2);i++)
  1977. // {
  1978. // PlanPoint pp = xvPP.at(i);
  1979. // off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
  1980. // off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  1981. // double offx = off1 + (off2 - off1) *(i-nchange1 + nchangepoint/2)/nchangepoint;
  1982. // pp.x = pp.x + offx *cos(pp.hdg + M_PI/2.0);
  1983. // pp.y = pp.y + offx *sin(pp.hdg + M_PI/2.0);
  1984. // pp.hdg = pp.hdg + M_PI;
  1985. // double flanewidth1 = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  1986. // pp.mfDisToRoadLeft = offx;
  1987. // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
  1988. // if(nlane1 == nlane2)
  1989. // {
  1990. // pp.mWidth = flanewidth1;
  1991. // pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1992. // pp.lanmp = 0;
  1993. // GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1994. // }
  1995. // else
  1996. // {
  1997. // if(nlane1 < nlane2)
  1998. // {
  1999. // pp.lanmp = -1;
  2000. // }
  2001. // else
  2002. // {
  2003. // pp.lanmp = 1;
  2004. // }
  2005. // if(i<nchange1)
  2006. // {
  2007. // pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  2008. // double fmove = pp.mWidth * (i-(nchange1 - nchangepoint/2))/nchangepoint;
  2009. // if(nlane1<nlane2)pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  2010. // else pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  2011. // GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  2012. // }
  2013. // else
  2014. // {
  2015. // pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  2016. // double fmove = pp.mWidth * (nchange1+nchangepoint/2 -i)/nchangepoint;
  2017. // if(nlane1<nlane2)pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  2018. // else pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  2019. // GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  2020. // }
  2021. // }
  2022. // xvectorPP.push_back(pp);
  2023. // }
  2024. // for(i=(nchange1 + nchangepoint/2);i<(nchange2-nchangepoint/2);i++)
  2025. // {
  2026. // PlanPoint pp = xvPP.at(i);
  2027. // off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  2028. // pp.x = pp.x + off2 *cos(pp.hdg + M_PI/2.0);
  2029. // pp.y = pp.y + off2 *sin(pp.hdg + M_PI/2.0);
  2030. // pp.hdg = pp.hdg + M_PI;
  2031. // pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  2032. // pp.mfDisToLaneLeft = pp.mWidth/2.0;
  2033. // pp.lanmp = 0;
  2034. // pp.mfDisToRoadLeft = off2;
  2035. // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane2,pp.mS);
  2036. // GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  2037. // xvectorPP.push_back(pp);
  2038. // }
  2039. // for(i=(nchange2 - nchangepoint/2);i<(nchange2+nchangepoint/2);i++)
  2040. // {
  2041. // PlanPoint pp = xvPP.at(i);
  2042. // off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  2043. // off3 = getoff(nlane3,pp.mS,xvectorLWA,xvectorindex3);
  2044. // double offx = off2 + (off3 - off2) *(i-nchange2 + nchangepoint/2)/nchangepoint;
  2045. // pp.x = pp.x + offx *cos(pp.hdg + M_PI/2.0);
  2046. // pp.y = pp.y + offx *sin(pp.hdg + M_PI/2.0);
  2047. // pp.hdg = pp.hdg + M_PI;
  2048. // double flanewidth1 = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  2049. // pp.mfDisToRoadLeft = offx;
  2050. // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane2,pp.mS);
  2051. // if(nlane2 == nlane3)
  2052. // {
  2053. // pp.mWidth = flanewidth1;
  2054. // pp.mfDisToLaneLeft = pp.mWidth/2.0;
  2055. // pp.lanmp = 0;
  2056. // GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  2057. // }
  2058. // else
  2059. // {
  2060. // if(nlane2 < nlane3)
  2061. // {
  2062. // pp.lanmp = -1;
  2063. // }
  2064. // else
  2065. // {
  2066. // pp.lanmp = 1;
  2067. // }
  2068. // if(i<nchange2)
  2069. // {
  2070. // pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  2071. // double fmove = pp.mWidth * (i-(nchange2 - nchangepoint/2))/nchangepoint;
  2072. // if(nlane2<nlane3)pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  2073. // else pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  2074. // GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  2075. // }
  2076. // else
  2077. // {
  2078. // pp.mWidth = getwidth(xps.mpRoad,nlane3,xvectorLWA,pp.mS);
  2079. // double fmove = pp.mWidth * (nchange2+nchangepoint/2 -i)/nchangepoint;
  2080. // if(nlane2<nlane3)pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  2081. // else pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  2082. // GetLaneOriTotal(xps.mpRoad,nlane3,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  2083. // }
  2084. // }
  2085. // xvectorPP.push_back(pp);
  2086. // }
  2087. // for(i=(nchange2+ nchangepoint/2);i<nsize;i++)
  2088. // {
  2089. // PlanPoint pp = xvPP.at(i);
  2090. // off3 = getoff(nlane3,pp.mS,xvectorLWA,xvectorindex3);
  2091. // pp.x = pp.x + off3 *cos(pp.hdg + M_PI/2.0);
  2092. // pp.y = pp.y + off3 *sin(pp.hdg + M_PI/2.0);
  2093. // pp.hdg = pp.hdg + M_PI;
  2094. // pp.mWidth = getwidth(xps.mpRoad,nlane3,xvectorLWA,pp.mS);
  2095. // pp.mfDisToLaneLeft = pp.mWidth/2.0;
  2096. // pp.lanmp = 0;
  2097. // pp.mfDisToRoadLeft = off3;
  2098. // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane3,pp.mS);
  2099. // GetLaneOriTotal(xps.mpRoad,nlane3,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  2100. // xvectorPP.push_back(pp);
  2101. // }
  2102. }
  2103. CalcInLaneAvoid(xps,xvectorPP,fvehiclewidth,nchange1,nchange2,nchangepoint);
  2104. if(xps.mpRoad->GetRoadBorrowCount()>0)
  2105. {
  2106. CalcBorringRoad(xps,xvectorPP);
  2107. }
  2108. if(xps.mnStartLaneSel > 0)
  2109. {
  2110. std::vector<PlanPoint> xvvPP;
  2111. int nvsize = xvectorPP.size();
  2112. for(i=0;i<nvsize;i++)
  2113. {
  2114. xvvPP.push_back(xvectorPP.at(nvsize-1-i));
  2115. }
  2116. AddSignalMark(xps.mpRoad,xps.mainsel,xvvPP);
  2117. return xvvPP;
  2118. }
  2119. // pRoad->GetLaneSection(xps.msectionid)
  2120. AddSignalMark(xps.mpRoad,xps.mainsel,xvectorPP);
  2121. return xvectorPP;
  2122. }
  2123. static void AddSignalMark(Road * pRoad, int nlane,std::vector<PlanPoint> & xvectorPP)
  2124. {
  2125. if(pRoad->GetSignalCount() == 0)return;
  2126. int nsigcount = pRoad->GetSignalCount();
  2127. int i;
  2128. for(i=0;i<nsigcount;i++)
  2129. {
  2130. Signal * pSig = pRoad->GetSignal(i);
  2131. int nfromlane = -100;
  2132. int ntolane = 100;
  2133. if(pSig->GetlaneValidityCount()>0)
  2134. {
  2135. bool bValid = false;
  2136. unsigned int j;
  2137. std::vector<signal_laneValidity> * pvectorlanevalid = pSig->GetlaneValidityVector();
  2138. unsigned int nsize = static_cast<unsigned int>(pvectorlanevalid->size());
  2139. for(j=0;j<nsize;j++)
  2140. {
  2141. signal_laneValidity * pSig_laneValidity = &pvectorlanevalid->at(j);
  2142. nfromlane = pSig_laneValidity->GetfromLane();
  2143. ntolane = pSig_laneValidity->GettoLane();
  2144. if((nlane >= nfromlane)&&(nlane<=ntolane))
  2145. {
  2146. bValid = true;
  2147. break;
  2148. }
  2149. }
  2150. if(bValid == false)continue;
  2151. }
  2152. // signal_laneValidity * pSig_laneValidity = pSig->GetlaneValidity();
  2153. // if(pSig_laneValidity != 0)
  2154. // {
  2155. // nfromlane = pSig_laneValidity->GetfromLane();
  2156. // ntolane = pSig_laneValidity->GettoLane();
  2157. // }
  2158. // if((nlane < 0)&&(nfromlane >= 0))
  2159. // {
  2160. // continue;
  2161. // }
  2162. // if((nlane > 0)&&(ntolane<=0))
  2163. // {
  2164. // continue;
  2165. // }
  2166. double s = pSig->Gets();
  2167. double fpos = s/pRoad->GetRoadLength();
  2168. if(nlane > 0)fpos = 1.0 -fpos;
  2169. int npos = fpos *xvectorPP.size();
  2170. if(npos <0)npos = 0;
  2171. if(npos>=xvectorPP.size())npos = xvectorPP.size()-1;
  2172. while(xvectorPP.at(npos).nSignal != -1)
  2173. {
  2174. if(npos > 0)npos--;
  2175. else break;
  2176. }
  2177. while(xvectorPP.at(npos).nSignal != -1)
  2178. {
  2179. if(npos < (xvectorPP.size()-1))npos++;
  2180. else break;
  2181. }
  2182. xvectorPP.at(npos).nSignal = atoi(pSig->Gettype().data());
  2183. }
  2184. }
  2185. static std::vector<PlanPoint> GetPlanPoint(std::vector<pathsection> xpathsection,Road * pRoad,GeometryBlock * pgeob,
  2186. Road * pRoad_obj,GeometryBlock * pgeob_obj,
  2187. const double x_now,const double y_now,const double head,
  2188. double nearx,double neary, double nearhead,
  2189. double nearx_obj,double neary_obj,const double fvehiclewidth,const double flen = 1000)
  2190. {
  2191. std::vector<PlanPoint> xvectorPPs;
  2192. double fspace = 0.1;
  2193. if(flen<2000)fspace = 0.1;
  2194. else
  2195. {
  2196. if(flen<5000)fspace = 0.3;
  2197. else
  2198. {
  2199. if(flen<10000)fspace = 0.5;
  2200. else
  2201. fspace = 1.0;
  2202. }
  2203. }
  2204. int i;
  2205. // std::vector<PlanPoint> xvectorPP = GetPoint( xpathsection[0].mpRoad);
  2206. std::vector<PlanPoint> xvectorPP = GetPoint( xpathsection[0],fspace);
  2207. int indexstart = indexinroadpoint(xvectorPP,nearx,neary);
  2208. std::vector<PlanPoint> xvPP = GetLanePoint(xpathsection[0],xvectorPP,fvehiclewidth);
  2209. if(xpathsection[0].mainsel < 0)
  2210. {
  2211. for(i=indexstart;i<xvPP.size();i++)
  2212. {
  2213. xvectorPPs.push_back(xvPP.at(i));
  2214. }
  2215. }
  2216. else
  2217. {
  2218. for(i=(xvPP.size() -indexstart);i<xvPP.size();i++)
  2219. {
  2220. PlanPoint pp;
  2221. pp = xvPP.at(i);
  2222. // pp.hdg = pp.hdg +M_PI;
  2223. xvectorPPs.push_back(pp);
  2224. }
  2225. }
  2226. int npathlast = xpathsection.size() - 1;
  2227. // while(npathlast >= 0)
  2228. // {
  2229. // if(npathlast == 0)break;
  2230. // if(xpathsection[npathlast].mpRoad != xpathsection[npathlast - 1].mpRoad)break;
  2231. // }
  2232. for(i=1;i<(npathlast);i++)
  2233. {
  2234. // if(xpathsection[i].mpRoad == xpathsection[i-1].mpRoad)
  2235. // {
  2236. // if(xpathsection[i].mainsel * xpathsection[i-1].mainsel >0)
  2237. // {
  2238. // continue;
  2239. // }
  2240. // }
  2241. // if(xpathsection[i].mpRoad == xpathsection[npathlast].mpRoad)
  2242. // {
  2243. // if(xpathsection[i].mainsel * xpathsection[npathlast].mainsel > 0)
  2244. // {
  2245. // break;
  2246. // }
  2247. // }
  2248. // xvectorPP = GetPoint( xpathsection[i].mpRoad);
  2249. xvectorPP = GetPoint( xpathsection[i],fspace);
  2250. xvPP = GetLanePoint(xpathsection[i],xvectorPP,fvehiclewidth);
  2251. // std::cout<<" road id: "<<xpathsection[i].mroadid<<" section: "
  2252. // <<xpathsection[i].msectionid<<" size is "<<xvectorPP.size()<<std::endl;
  2253. // std::cout<<" road id is "<<xpathsection[i].mpRoad->GetRoadId().data()<<" size is "<<xvPP.size()<<std::endl;
  2254. int j;
  2255. for(j=0;j<xvPP.size();j++)
  2256. {
  2257. PlanPoint pp;
  2258. pp = xvPP.at(j);
  2259. // pp.hdg = pp.hdg +M_PI;
  2260. xvectorPPs.push_back(pp);
  2261. }
  2262. }
  2263. xvectorPP = GetPoint(xpathsection[npathlast],fspace);
  2264. // xvectorPP = GetPoint(xpathsection[npathlast].mpRoad);
  2265. int indexend = indexinroadpoint(xvectorPP,nearx_obj,neary_obj);
  2266. xvPP = GetLanePoint(xpathsection[npathlast],xvectorPP,fvehiclewidth);
  2267. int nlastsize;
  2268. if(xpathsection[npathlast].mainsel<0)
  2269. {
  2270. nlastsize = indexend;
  2271. }
  2272. else
  2273. {
  2274. if(indexend>0) nlastsize = xvPP.size() - indexend;
  2275. else nlastsize = xvPP.size();
  2276. }
  2277. for(i=0;i<nlastsize;i++)
  2278. {
  2279. xvectorPPs.push_back(xvPP.at(i));
  2280. }
  2281. //Find StartPoint
  2282. // if
  2283. // int a = 1;
  2284. return xvectorPPs;
  2285. }
  2286. std::vector<PlanPoint> gTempPP;
  2287. int getPoint(double q[3], double x, void* user_data) {
  2288. // printf("%f, %f, %f, %f\n", q[0], q[1], q[2], x);
  2289. PlanPoint pp;
  2290. pp.x = q[0];
  2291. pp.y = q[1];
  2292. pp.hdg = q[2];
  2293. pp.dis = x;
  2294. pp.speed = *((double *)user_data);
  2295. gTempPP.push_back(pp);
  2296. // std::cout<<pp.x<<" "<<" "<<pp.y<<" "<<pp.hdg<<std::endl;
  2297. return 0;
  2298. }
  2299. /**
  2300. * @brief getlanesel
  2301. * @param nSel
  2302. * @param pLaneSection
  2303. * @param nlr
  2304. * @return
  2305. */
  2306. int getlanesel(int nSel,LaneSection * pLaneSection,int nlr)
  2307. {
  2308. int nlane = nSel;
  2309. int mainselindex = 0;
  2310. if(nlr == 2)nlane = nlane*(-1);
  2311. int nlanecount = pLaneSection->GetLaneCount();
  2312. int i;
  2313. int nTrueSel = nSel;
  2314. if(nTrueSel <= 1)nTrueSel= 1;
  2315. int nCurSel = 1;
  2316. if(nlr == 2)nCurSel = nCurSel *(-1);
  2317. bool bOK = false;
  2318. int nxsel = 1;
  2319. int nlasttid = 0;
  2320. bool bfindlast = false;
  2321. while(bOK == false)
  2322. {
  2323. bool bHaveDriving = false;
  2324. int ncc = 0;
  2325. for(i=0;i<nlanecount;i++)
  2326. {
  2327. Lane * pLane = pLaneSection->GetLane(i);
  2328. if(strncmp(pLane->GetType().data(),"driving",255) == 0 )
  2329. {
  2330. if((nlr == 1)&&(pLane->GetId()>0))
  2331. {
  2332. ncc++;
  2333. }
  2334. if((nlr == 2)&&(pLane->GetId()<0))
  2335. {
  2336. ncc++;
  2337. }
  2338. if(ncc == nxsel)
  2339. {
  2340. bHaveDriving = true;
  2341. bfindlast = true;
  2342. nlasttid = pLane->GetId();
  2343. break;
  2344. }
  2345. }
  2346. }
  2347. if(bHaveDriving == true)
  2348. {
  2349. if(nxsel == nTrueSel)
  2350. {
  2351. return nlasttid;
  2352. }
  2353. else
  2354. {
  2355. nxsel++;
  2356. }
  2357. }
  2358. else
  2359. {
  2360. if(bfindlast)
  2361. {
  2362. return nlasttid;
  2363. }
  2364. else
  2365. {
  2366. std::cout<<"can't find lane."<<std::endl;
  2367. return 0;
  2368. }
  2369. //Use Last
  2370. }
  2371. }
  2372. return 0;
  2373. int k;
  2374. bool bFind = false;
  2375. while(bFind == false)
  2376. {
  2377. for(k=0;k<nlanecount;k++)
  2378. {
  2379. Lane * pLane = pLaneSection->GetLane(k);
  2380. if((nlane == pLane->GetId())&&(strncmp(pLane->GetType().data(),"driving",255) == 0))
  2381. {
  2382. bFind = true;
  2383. mainselindex = k;
  2384. break;
  2385. }
  2386. }
  2387. if(bFind)continue;
  2388. if(nlr == 1)nlane--;
  2389. else nlane++;
  2390. if(nlane == 0)
  2391. {
  2392. std::cout<<" Fail. can't find lane"<<std::endl;
  2393. break;
  2394. }
  2395. }
  2396. return nlane;
  2397. }
  2398. void checktrace(std::vector<PlanPoint> & xPlan)
  2399. {
  2400. int i;
  2401. int nsize = xPlan.size();
  2402. for(i=1;i<nsize;i++)
  2403. {
  2404. double dis = sqrt(pow(xPlan.at(i).x - xPlan.at(i-1).x,2) + pow(xPlan.at(i).y - xPlan.at(i-1).y,2));
  2405. if(dis > 0.3)
  2406. {
  2407. double hdg = CalcHdg(QPointF(xPlan.at(i-1).x,xPlan.at(i-1).y),QPointF(xPlan.at(i).x,xPlan.at(i).y));
  2408. int ncount = dis/0.1;
  2409. int j;
  2410. for(j=1;j<ncount;j++)
  2411. {
  2412. double x, y;
  2413. PlanPoint pp;
  2414. pp.x = xPlan.at(i-1).x + j*0.1 *cos(hdg);
  2415. pp.y = xPlan.at(i-1).y + j*0.1 *sin(hdg);
  2416. pp.hdg = hdg;
  2417. xPlan.insert(xPlan.begin()+i+j-1,pp);
  2418. }
  2419. qDebug("dis is %f",dis);
  2420. }
  2421. }
  2422. }
  2423. void ChangeLane(std::vector<PlanPoint> & xvectorPP)
  2424. {
  2425. int i = 0;
  2426. int nsize = xvectorPP.size();
  2427. int nstart = -1;
  2428. int nend = -1;
  2429. for(i=0;i<nsize;i++)
  2430. {
  2431. if((xvectorPP[i].mfSecx == xvectorPP[i].x)&&(xvectorPP[i].mfSecy == xvectorPP[i].y))
  2432. {
  2433. }
  2434. else
  2435. {
  2436. int k;
  2437. for(k=i;k<=(nsize-1);k++)
  2438. {
  2439. if((fabs(xvectorPP[k].mfSecx - xvectorPP[k].x)<0.001)&&(fabs(xvectorPP[k].mfSecy - xvectorPP[k].y)<0.001))
  2440. {
  2441. break;
  2442. }
  2443. }
  2444. if(k>(nsize-1))k=nsize-1;
  2445. int nnum = k-i;
  2446. int nchangepoint = 300;
  2447. double froadlen = sqrt(pow(xvectorPP[k].x - xvectorPP[i].x,2)
  2448. +pow(xvectorPP[k].y - xvectorPP[i].y,2));
  2449. const double fMAXCHANGE = 50;
  2450. if(froadlen<fMAXCHANGE)
  2451. {
  2452. nchangepoint = nnum;
  2453. }
  2454. else
  2455. {
  2456. nchangepoint = (fMAXCHANGE/froadlen) * nnum;
  2457. }
  2458. qDebug(" road %d len is %f changepoint is %d nnum is %d",
  2459. xvectorPP[k-1].nRoadID,froadlen,nchangepoint,nnum);
  2460. nstart = i + nnum/2 -nchangepoint/2;
  2461. nend = i+nnum/2 + nchangepoint/2;
  2462. if(nnum<300)
  2463. {
  2464. nstart = i;
  2465. nend = k;
  2466. }
  2467. int j;
  2468. for(j=i;j<nstart;j++)
  2469. {
  2470. xvectorPP[j].x = xvectorPP[j].mfSecx;
  2471. xvectorPP[j].y = xvectorPP[j].mfSecy;
  2472. }
  2473. nnum = nend - nstart;
  2474. int nlast = k-1;
  2475. if(k==(nsize-1))nlast = k;
  2476. for(j=nstart;j<=nlast;j++)
  2477. {
  2478. double fdis = sqrt(pow(xvectorPP[j].x - xvectorPP[j].mfSecx,2)
  2479. +pow(xvectorPP[j].y - xvectorPP[j].mfSecy,2));
  2480. double foff = 0;
  2481. if(j<nend)
  2482. foff = fdis *(j-nstart)/nnum;
  2483. else
  2484. foff = fdis;
  2485. if(xvectorPP[j].nlrchange == 1)
  2486. {
  2487. // std::cout<<"foff is "<<foff<<std::endl;
  2488. xvectorPP[j].x = xvectorPP[j].mfSecx + foff *cos(xvectorPP[j].hdg + M_PI/2.0);
  2489. xvectorPP[j].y = xvectorPP[j].mfSecy + foff *sin(xvectorPP[j].hdg + M_PI/2.0);
  2490. xvectorPP[j].mfDisToRoadLeft = xvectorPP[j].mfDisToRoadLeft - foff; //+ fdis
  2491. }
  2492. else
  2493. {
  2494. xvectorPP[j].x = xvectorPP[j].mfSecx + foff *cos(xvectorPP[j].hdg - M_PI/2.0);
  2495. xvectorPP[j].y = xvectorPP[j].mfSecy + foff *sin(xvectorPP[j].hdg - M_PI/2.0);
  2496. xvectorPP[j].mfDisToRoadLeft = xvectorPP[j].mfDisToRoadLeft +foff;//- fdis
  2497. }
  2498. }
  2499. i =k;
  2500. }
  2501. }
  2502. if(nstart != -1)
  2503. {
  2504. for(i=0;i<nstart;i++)
  2505. {
  2506. xvectorPP[i].nlrchange = 0;
  2507. if(i>nsize)break;
  2508. }
  2509. }
  2510. if(nend >0)
  2511. {
  2512. for(i=nend;i<nsize;i++)
  2513. {
  2514. xvectorPP[i].nlrchange = 0;
  2515. if(i>nsize)break;
  2516. }
  2517. }
  2518. }
  2519. #include <QFile>
  2520. /**
  2521. * @brief MakePlan 全局路径规划
  2522. * @param pxd 有向图
  2523. * @param pxodr OpenDrive地图
  2524. * @param x_now 当前x坐标
  2525. * @param y_now 当前y坐标
  2526. * @param head 当前航向
  2527. * @param x_obj 目标点x坐标
  2528. * @param y_obj 目标点y坐标
  2529. * @param obj_dis 目标点到路径的距离
  2530. * @param srcnearthresh 当前点离最近路径的阈值,如果不在这个范围,寻找失败
  2531. * @param dstnearthresh 目标点离最近路径的阈值,如果不在这个范围,寻找失败
  2532. * @param nlanesel 车道偏好,1为内车道,数值越大越偏外,如果数值不满足,会选择最靠外的。
  2533. * @param xPlan 返回的轨迹点
  2534. * @return 0 成功 <0 失败
  2535. */
  2536. int MakePlan(xodrdijkstra * pxd,OpenDrive * pxodr,const double x_now,const double y_now,const double head,
  2537. const double x_obj,const double y_obj,const double & obj_dis,
  2538. const double srcnearthresh,const double dstnearthresh,
  2539. const int nlanesel,std::vector<PlanPoint> & xPlan,const double fvehiclewidth )
  2540. {
  2541. double s;double nearx;
  2542. double neary;double nearhead;
  2543. Road * pRoad;GeometryBlock * pgeob;
  2544. Road * pRoad_obj;GeometryBlock * pgeob_obj;
  2545. double s_obj;double nearx_obj;
  2546. double neary_obj;double nearhead_obj;
  2547. int lr_end = 2;
  2548. int lr_start = 2;
  2549. double fs1,fs2;
  2550. // int nfind = GetNearPoint(x_now,y_now,pxodr,&pRoad,&pgeob,s,nearx,neary,nearhead,srcnearthresh);
  2551. std::vector<iv::nearroad> xvectornearstart;
  2552. std::vector<iv::nearroad> xvectornearend;
  2553. GetNearPointWithHead(x_now,y_now,head,pxodr,xvectornearstart,srcnearthresh,true);
  2554. GetNearPointWithHead(x_obj,y_obj,0,pxodr,xvectornearend,dstnearthresh,false);
  2555. if(xvectornearstart.size()<1)
  2556. {
  2557. std::cout<<" plan fail. can't find start point."<<std::endl;
  2558. return -1;
  2559. }
  2560. if(xvectornearend.size() < 1)
  2561. {
  2562. std::cout<<" plan fail. can't find end point."<<std::endl;
  2563. return -2;
  2564. }
  2565. std::cout<<" start size: "<<xvectornearstart.size()<<std::endl;
  2566. std::cout<<" end size: "<<xvectornearend.size()<<std::endl;
  2567. std::vector<std::vector<PlanPoint>> xvectorplans;
  2568. std::vector<double> xvectorroutedis;
  2569. int i;
  2570. int j;
  2571. for(i=0;i<(int)xvectornearstart.size();i++)
  2572. {
  2573. for(j=0;j<(int)xvectornearend.size();j++)
  2574. {
  2575. iv::nearroad * pnearstart = &xvectornearstart[i];
  2576. iv::nearroad * pnearend = &xvectornearend[j];
  2577. pRoad = pnearstart->pObjRoad;
  2578. pgeob = pnearstart->pgeob;
  2579. pRoad_obj = pnearend->pObjRoad;
  2580. pgeob_obj = pnearend->pgeob;
  2581. lr_start = pnearstart->lr;
  2582. lr_end = pnearend->lr;
  2583. std::cout<<" lr start: "<<lr_start<<" lr end "<<lr_end<<std::endl;
  2584. nearx = pnearstart->nearx;
  2585. neary = pnearstart->neary;
  2586. nearx_obj = pnearend->nearx;
  2587. neary_obj = pnearend->neary;
  2588. bool bNeedDikstra = true;
  2589. if((atoi(pRoad->GetRoadId().data()) == atoi(pRoad_obj->GetRoadId().data()))&&(lr_start == lr_end) &&(pRoad->GetLaneSectionCount() == 1))
  2590. {
  2591. std::vector<PlanPoint> xvPP = GetPoint(pRoad);
  2592. int nindexstart = indexinroadpoint(xvPP,nearx,neary);
  2593. int nindexend = indexinroadpoint(xvPP,nearx_obj,neary_obj);
  2594. int nlane = getlanesel(nlanesel,pRoad->GetLaneSection(0),lr_start);
  2595. AddSignalMark(pRoad,nlane,xvPP);
  2596. if((nindexend >nindexstart)&&(lr_start == 2))
  2597. {
  2598. bNeedDikstra = false;
  2599. }
  2600. if((nindexend <nindexstart)&&(lr_start == 1))
  2601. {
  2602. bNeedDikstra = false;
  2603. }
  2604. if(bNeedDikstra == false)
  2605. {
  2606. std::vector<iv::lanewidthabcd> xvectorLWA = GetLaneWidthABCD(pRoad);
  2607. std::vector<int> xvectorindex1;
  2608. xvectorindex1 = GetLWIndex(xvectorLWA,nlane);
  2609. double foff = getoff(pRoad,nlane);
  2610. foff = foff + 0.0;
  2611. std::vector<PlanPoint> xvectorPP;
  2612. int i = nindexstart;
  2613. while(i!=nindexend)
  2614. {
  2615. if(lr_start == 2)
  2616. {
  2617. PlanPoint pp = xvPP.at(i);
  2618. foff = getoff(pRoad,nlane,pp.mS);// getoff(nlane,pp.mS,xvectorLWA,xvectorindex1);
  2619. // std::cout<<"foff: "<<foff<<std::endl;
  2620. pp.x = pp.x + foff *cos(pp.hdg + M_PI/2.0);
  2621. pp.y = pp.y + foff *sin(pp.hdg + M_PI/2.0);
  2622. pp.mWidth = getwidth(pRoad,nlane,xvectorLWA,pp.mS);
  2623. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  2624. pp.lanmp = 0;
  2625. pp.mfDisToRoadLeft = foff *(-1.0);
  2626. pp.mfRoadWidth = GetRoadWidth(pRoad,nlane,pp.mS);
  2627. pp.mLaneCur = abs(nlane);
  2628. pp.mVectorLaneWidth = pRoad->GetDrivingLaneWidthVector(pp.mS,lr_start);
  2629. pp.mLaneCount = pRoad->GetRightDrivingLaneCount(pp.mS);
  2630. GetLaneOriTotal(pRoad,nlane,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed,pp.mbNoavoid);
  2631. xvectorPP.push_back(pp);
  2632. i++;
  2633. }
  2634. else
  2635. {
  2636. PlanPoint pp = xvPP.at(i);
  2637. foff = getoff(pRoad,nlane,pp.mS);// getoff(nlane,pp.mS,xvectorLWA,xvectorindex1);
  2638. pp.x = pp.x + foff *cos(pp.hdg + M_PI/2.0);
  2639. pp.y = pp.y + foff *sin(pp.hdg + M_PI/2.0);
  2640. pp.hdg = pp.hdg + M_PI;
  2641. pp.mWidth = getwidth(pRoad,nlane,xvectorLWA,pp.mS);
  2642. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  2643. pp.lanmp = 0;
  2644. pp.mfDisToRoadLeft = foff;
  2645. pp.mfRoadWidth = GetRoadWidth(pRoad,nlane,pp.mS);
  2646. pp.mLaneCur = abs(nlane);
  2647. pp.mVectorLaneWidth = pRoad->GetDrivingLaneWidthVector(pp.mS,lr_start);
  2648. pp.mLaneCount = pRoad->GetLeftDrivingLaneCount(pp.mS);
  2649. GetLaneOriTotal(pRoad,nlane,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed,pp.mbNoavoid);
  2650. xvectorPP.push_back(pp);
  2651. i--;
  2652. }
  2653. }
  2654. for(i=0;i<(int)xvectorPP.size();i++)
  2655. {
  2656. xvectorPP[i].mfCurvature = pRoad->GetRoadCurvature(xvectorPP[i].mS);
  2657. }
  2658. pathsection xps;
  2659. xps.mbStartToMainChange = false;
  2660. xps.mbMainToEndChange = false;
  2661. // CalcInLaneAvoid(xps,xvectorPP,fvehiclewidth,0,0,0);
  2662. xPlan = xvectorPP;
  2663. xvectorplans.push_back(xvectorPP);
  2664. xvectorroutedis.push_back(xvectorPP.size() * 0.1);
  2665. }
  2666. }
  2667. if(bNeedDikstra)
  2668. {
  2669. bool bSuc = false;
  2670. std::vector<int> xpath = pxd->getpath(atoi(pRoad->GetRoadId().data()),lr_start,atoi(pRoad_obj->GetRoadId().data()),lr_end,bSuc,fs1,fs2);
  2671. if(xpath.size()<1)
  2672. {
  2673. continue;
  2674. }
  2675. if(bSuc == false)
  2676. {
  2677. continue;
  2678. }
  2679. double flen = pxd->getpathlength(xpath);
  2680. std::vector<pathsection> xpathsection = pxd->getgpspoint(atoi(pRoad->GetRoadId().data()),lr_start,atoi(pRoad_obj->GetRoadId().data()),lr_end,xpath,nlanesel);
  2681. std::vector<PlanPoint> xvectorPP = GetPlanPoint(xpathsection,pRoad,pgeob,pRoad_obj,pgeob_obj,x_now,y_now,
  2682. head,nearx,neary,nearhead,nearx_obj,neary_obj,fvehiclewidth,flen);
  2683. ChangeLane(xvectorPP);
  2684. xvectorplans.push_back(xvectorPP);
  2685. xvectorroutedis.push_back(flen);
  2686. }
  2687. }
  2688. }
  2689. if(xvectorplans.size() > 0)
  2690. {
  2691. if(xvectorplans.size() == 1)
  2692. {
  2693. xPlan = xvectorplans[0];
  2694. }
  2695. else
  2696. {
  2697. int nsel = 0;
  2698. double fdismin = xvectorroutedis[0];
  2699. for(i=1;i<(int)xvectorroutedis.size();i++)
  2700. {
  2701. if(xvectorroutedis[i]<fdismin)
  2702. {
  2703. nsel = i;
  2704. }
  2705. }
  2706. xPlan = xvectorplans[nsel];
  2707. }
  2708. return 0;
  2709. }
  2710. std::cout<<" plan fail. can't find path."<<std::endl;
  2711. return -1000;
  2712. }