globalplan.cpp 87 KB

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