globalplan.cpp 87 KB

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