globalplan.cpp 73 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262226322642265226622672268226922702271227222732274227522762277227822792280228122822283228422852286228722882289229022912292229322942295229622972298229923002301230223032304230523062307230823092310231123122313231423152316231723182319232023212322232323242325232623272328232923302331233223332334233523362337233823392340234123422343234423452346234723482349235023512352235323542355235623572358235923602361236223632364236523662367236823692370237123722373237423752376237723782379238023812382238323842385238623872388238923902391239223932394239523962397239823992400240124022403240424052406240724082409241024112412241324142415241624172418241924202421242224232424242524262427242824292430243124322433243424352436243724382439244024412442244324442445244624472448244924502451245224532454245524562457245824592460246124622463246424652466246724682469247024712472247324742475247624772478247924802481248224832484248524862487248824892490249124922493249424952496249724982499250025012502250325042505250625072508250925102511251225132514251525162517251825192520252125222523252425252526252725282529253025312532253325342535253625372538253925402541254225432544254525462547254825492550255125522553255425552556255725582559256025612562256325642565256625672568256925702571257225732574257525762577257825792580258125822583258425852586258725882589259025912592259325942595259625972598259926002601
  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. /**
  17. * @brief GetLineDis 获得点到直线Geometry的距离。
  18. * @param pline
  19. * @param x
  20. * @param y
  21. * @param nearx
  22. * @param neary
  23. * @param nearhead
  24. * @return
  25. */
  26. static double GetLineDis(GeometryLine * pline,const double x,const double y,double & nearx,
  27. double & neary,double & nearhead)
  28. {
  29. double fRtn = 1000.0;
  30. double a1,a2,a3,a4,b1,b2;
  31. double ratio = pline->GetHdg();
  32. while(ratio >= 2.0* M_PI)ratio = ratio-2.0*M_PI;
  33. while(ratio<0)ratio = ratio+2.0*M_PI;
  34. double dis1,dis2,dis3;
  35. double x1,x2,x3,y1,y2,y3;
  36. x1 = pline->GetX();y1=pline->GetY();
  37. if((ratio == 0)||(ratio == M_PI))
  38. {
  39. a1 = 0;a4=0;
  40. a2 = 1;b1= pline->GetY();
  41. a3 = 1;b2= x;
  42. }
  43. else
  44. {
  45. if((ratio == 0.5*M_PI)||(ratio == 1.5*M_PI))
  46. {
  47. a2=0;a3=0;
  48. a1=1,b1=pline->GetX();
  49. a4 = 1;b2 = y;
  50. }
  51. else
  52. {
  53. a1 = tan(ratio) *(-1.0);
  54. a2 = 1;
  55. a3 = tan(ratio+M_PI/2.0)*(-1.0);
  56. a4 = 1;
  57. b1 = a1*pline->GetX() + a2 * pline->GetY();
  58. b2 = a3*x+a4*y;
  59. }
  60. }
  61. y2 = y1 + pline->GetLength() * sin(ratio);
  62. x2 = x1 + pline->GetLength() * cos(ratio);
  63. Eigen::Matrix2d A;
  64. A<<a1,a2,
  65. a3,a4;
  66. Eigen::Vector2d B(b1,b2);
  67. Eigen::Vector2d opoint = A.lu().solve(B);
  68. // std::cout<<opoint<<std::endl;
  69. x3 = opoint(0);
  70. y3 = opoint(1);
  71. dis1 = sqrt(pow(x1-x,2)+pow(y1-y,2));
  72. dis2 = sqrt(pow(x2-x,2)+pow(y2-y,2));
  73. dis3 = sqrt(pow(x3-x,2)+pow(y3-y,2));
  74. // std::cout<<" dis 1 is "<<dis1<<std::endl;
  75. // std::cout<<" dis 2 is "<<dis2<<std::endl;
  76. // std::cout<<" dis 3 is "<<dis3<<std::endl;
  77. if((dis1>pline->GetLength())||(dis2>pline->GetLength())) //Outoff line
  78. {
  79. // std::cout<<" out line"<<std::endl;
  80. if(dis1<dis2)
  81. {
  82. fRtn = dis1;
  83. nearx = x1;neary=y1;nearhead = pline->GetHdg();
  84. }
  85. else
  86. {
  87. fRtn = dis2;
  88. nearx = x2;neary=y2;nearhead = pline->GetHdg();
  89. }
  90. }
  91. else
  92. {
  93. fRtn = dis3;
  94. nearx = x3;neary=y3;nearhead = pline->GetHdg();
  95. }
  96. // std::cout<<"dis is "<<fRtn<<" x is "<<nearx<<" y is "<<neary<<" head is "<<nearhead<<std::endl;
  97. return fRtn;
  98. }
  99. static int getcirclecrosspoint(QPointF startPos, QPointF endPos, QPointF agvPos, double R,QPointF & point1,QPointF & point2 )
  100. {
  101. double m=0;
  102. double k;
  103. double b;
  104. //计算分子
  105. m=startPos.x()-endPos.x();
  106. //求直线的方程
  107. if(0==m)
  108. {
  109. k=100000;
  110. b=startPos.y()-k*startPos.x();
  111. }
  112. else
  113. {
  114. k=(endPos.y()-startPos.y())/(endPos.x()-startPos.x());
  115. b=startPos.y()-k*startPos.x();
  116. }
  117. // qDebug()<<k<<b;
  118. double temp = fabs(k*agvPos.x()-agvPos.y()+b)/sqrt(k*k+b*b);
  119. //求直线与圆的交点 前提是圆需要与直线有交点
  120. if(fabs(k*agvPos.x()-agvPos.y()+b)/sqrt(k*k+b*b)<R)
  121. {
  122. 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));
  123. 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));
  124. point1.setY(k*point1.x()+b);
  125. point2.setY(k*point2.x()+b);
  126. return 0;
  127. }
  128. return -1;
  129. }
  130. /**
  131. * @brief CalcHdg
  132. * 计算点0到点1的航向
  133. * @param p0 Point 0
  134. * @param p1 Point 1
  135. **/
  136. static double CalcHdg(QPointF p0, QPointF p1)
  137. {
  138. double x0,y0,x1,y1;
  139. x0 = p0.x();
  140. y0 = p0.y();
  141. x1 = p1.x();
  142. y1 = p1.y();
  143. if(x0 == x1)
  144. {
  145. if(y0 < y1)
  146. {
  147. return M_PI/2.0;
  148. }
  149. else
  150. return M_PI*3.0/2.0;
  151. }
  152. double ratio = (y1-y0)/(x1-x0);
  153. double hdg = atan(ratio);
  154. if(ratio > 0)
  155. {
  156. if(y1 > y0)
  157. {
  158. }
  159. else
  160. {
  161. hdg = hdg + M_PI;
  162. }
  163. }
  164. else
  165. {
  166. if(y1 > y0)
  167. {
  168. hdg = hdg + M_PI;
  169. }
  170. else
  171. {
  172. hdg = hdg + 2.0*M_PI;
  173. }
  174. }
  175. return hdg;
  176. }
  177. static bool pointinarc(GeometryArc * parc,QPointF poingarc,QPointF point1)
  178. {
  179. double hdg = CalcHdg(poingarc,point1);
  180. if(parc->GetCurvature() >0)hdg = hdg + M_PI/2.0;
  181. else hdg = hdg - M_PI/2.0;
  182. if(hdg >= 2.0*M_PI)hdg = hdg - 2.0*M_PI;
  183. if(hdg < 0)hdg = hdg + 2.0*M_PI;
  184. double hdgrange = parc->GetLength()/(1.0/parc->GetCurvature());
  185. double hdgdiff = hdg - parc->GetHdg();
  186. if(hdgrange >= 0 )
  187. {
  188. if(hdgdiff < 0)hdgdiff = hdgdiff + M_PI*2.0;
  189. }
  190. else
  191. {
  192. if(hdgdiff > 0)hdgdiff = hdgdiff - M_PI*2.0;
  193. }
  194. if(fabs(hdgdiff ) < fabs(hdgrange))return true;
  195. return false;
  196. }
  197. static inline double calcpointdis(QPointF p1,QPointF p2)
  198. {
  199. return sqrt(pow(p1.x()-p2.x(),2)+pow(p1.y()-p2.y(),2));
  200. }
  201. /**
  202. * @brief GetArcDis
  203. * 计算点到圆弧的最短距离,首先用点和圆弧中心点的直线与圆的交点,计算点到交点的距离,如果交点在圆弧上,则最短距离是交点之一,否则计算点到圆弧两个端点的距离。
  204. * @param parc pointer to a arc geomery
  205. * @param x current x
  206. * @param y current y
  207. * @param nearx near x
  208. * @param neary near y
  209. * @param nearhead nearhead
  210. **/
  211. static double GetArcDis(GeometryArc * parc,double x,double y,double & nearx,
  212. double & neary,double & nearhead)
  213. {
  214. // double fRtn = 1000.0;
  215. if(parc->GetCurvature() == 0.0)return 1000.0;
  216. double R = fabs(1.0/parc->GetCurvature());
  217. // if(parc->GetX() == 4.8213842690322309e+01)
  218. // {
  219. // int a = 1;
  220. // a = 3;
  221. // }
  222. // if(parc->GetCurvature() == -0.0000110203)
  223. // {
  224. // int a = 1;
  225. // a = 3;
  226. // }
  227. //calculate arc center
  228. double x_center,y_center;
  229. if(parc->GetCurvature() > 0)
  230. {
  231. x_center = parc->GetX() + R * cos(parc->GetHdg() + M_PI/2.0);
  232. y_center = parc->GetY() + R * sin(parc->GetHdg()+ M_PI/2.0);
  233. }
  234. else
  235. {
  236. x_center = parc->GetX() + R * cos(parc->GetHdg() - M_PI/2.0);
  237. y_center = parc->GetY() + R * sin(parc->GetHdg() - M_PI/2.0);
  238. }
  239. double hdgltoa = CalcHdg(QPointF(x,y),QPointF(x_center,y_center));
  240. QPointF arcpoint;
  241. arcpoint.setX(x_center);arcpoint.setY(y_center);
  242. QPointF pointnow;
  243. pointnow.setX(x);pointnow.setY(y);
  244. QPointF point1,point2;
  245. point1.setX(x_center + (R * cos(hdgltoa)));
  246. point1.setY(y_center + (R * sin(hdgltoa)));
  247. point2.setX(x_center + (R * cos(hdgltoa + M_PI)));
  248. point2.setY(y_center + (R * sin(hdgltoa + M_PI)));
  249. //calculat dis
  250. bool bp1inarc,bp2inarc;
  251. bp1inarc =pointinarc(parc,arcpoint,point1);
  252. bp2inarc =pointinarc(parc,arcpoint,point2);
  253. double fdis[4];
  254. fdis[0] = calcpointdis(pointnow,point1);
  255. fdis[1] = calcpointdis(pointnow,point2);
  256. fdis[2] = calcpointdis(pointnow,QPointF(parc->GetX(),parc->GetY()));
  257. QPointF pointend;
  258. double hdgrange = parc->GetLength()*parc->GetCurvature();
  259. double hdgend = parc->GetHdg() + hdgrange;
  260. while(hdgend <0.0)hdgend = hdgend + 2.0 *M_PI;
  261. while(hdgend >= 2.0*M_PI) hdgend = hdgend -2.0*M_PI;
  262. if(parc->GetCurvature() >0)
  263. {
  264. pointend.setX(arcpoint.x() + R*cos(hdgend -M_PI/2.0 ));
  265. pointend.setY(arcpoint.y() + R*sin(hdgend -M_PI/2.0) );
  266. }
  267. else
  268. {
  269. pointend.setX(arcpoint.x() + R*cos(hdgend +M_PI/2.0 ));
  270. pointend.setY(arcpoint.y() + R*sin(hdgend +M_PI/2.0) );
  271. }
  272. fdis[3] = calcpointdis(pointnow,pointend);
  273. int indexmin = -1;
  274. double fdismin = 1000000.0;
  275. if(bp1inarc)
  276. {
  277. indexmin = 0;fdismin = fdis[0];
  278. }
  279. if(bp2inarc)
  280. {
  281. if(indexmin == -1)
  282. {
  283. indexmin = 1;fdismin = fdis[1];
  284. }
  285. else
  286. {
  287. if(fdis[1]<fdismin)
  288. {
  289. indexmin = 1;fdismin = fdis[1];
  290. }
  291. }
  292. }
  293. if(indexmin == -1)
  294. {
  295. indexmin = 2;fdismin = fdis[2];
  296. }
  297. else
  298. {
  299. if(fdis[2]<fdismin)
  300. {
  301. indexmin = 2;fdismin = fdis[2];
  302. }
  303. }
  304. if(fdis[3]<fdismin)
  305. {
  306. indexmin = 3;fdismin = fdis[3];
  307. }
  308. switch (indexmin) {
  309. case 0:
  310. nearx = point1.x();
  311. neary = point1.y();
  312. if(parc->GetCurvature()<0)
  313. {
  314. nearhead = CalcHdg(arcpoint,point1) - M_PI/2.0;
  315. }
  316. else
  317. {
  318. nearhead = CalcHdg(arcpoint,point1) + M_PI/2.0;
  319. }
  320. break;
  321. case 1:
  322. nearx = point2.x();
  323. neary = point2.y();
  324. if(parc->GetCurvature()<0)
  325. {
  326. nearhead = CalcHdg(arcpoint,point2) - M_PI/2.0;
  327. }
  328. else
  329. {
  330. nearhead = CalcHdg(arcpoint,point2) + M_PI/2.0;
  331. }
  332. break;
  333. case 2:
  334. nearx = parc->GetX();
  335. neary = parc->GetY();
  336. nearhead = parc->GetHdg();
  337. break;
  338. case 3:
  339. nearx = pointend.x();
  340. neary = pointend.y();
  341. nearhead = hdgend;
  342. break;
  343. default:
  344. std::cout<<"error in arcdis "<<std::endl;
  345. break;
  346. }
  347. while(nearhead>2.0*M_PI)nearhead = nearhead -2.0*M_PI;
  348. while(nearhead<0)nearhead = nearhead + 2.0*M_PI;
  349. return fdismin;
  350. }
  351. static double GetSpiralDis(GeometrySpiral * pspiral,double xnow,double ynow,double & nearx,
  352. double & neary,double & nearhead)
  353. {
  354. double x,y,hdg;
  355. double s = 0.0;
  356. double fdismin = 100000.0;
  357. double s0 = pspiral->GetS();
  358. while(s<pspiral->GetLength())
  359. {
  360. pspiral->GetCoords(s0+s,x,y,hdg);
  361. s = s+0.1;
  362. double fdis = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
  363. if(fdis<fdismin)
  364. {
  365. fdismin = fdis;
  366. nearhead = hdg;
  367. nearx = x;
  368. neary = y;
  369. }
  370. }
  371. return fdismin;
  372. }
  373. /**
  374. * @brief GetParamPoly3Dis 获得点到贝塞尔曲线的距离。
  375. * @param parc
  376. * @param xnow
  377. * @param ynow
  378. * @param nearx
  379. * @param neary
  380. * @param nearhead
  381. * @return
  382. */
  383. static double GetParamPoly3Dis(GeometryParamPoly3 * parc,double xnow,double ynow,double & nearx,
  384. double & neary,double & nearhead)
  385. {
  386. double s = 0.1;
  387. double fdismin = 100000.0;
  388. double xold,yold;
  389. xold = parc->GetX();
  390. yold = parc->GetY();
  391. double fdis = calcpointdis(QPointF(parc->GetX(),parc->GetY()),QPointF(xnow,ynow));
  392. if(fdis<fdismin)
  393. {
  394. fdismin = fdis;
  395. nearhead = parc->GetHdg();
  396. nearx = parc->GetX();
  397. neary = parc->GetY();
  398. }
  399. while(s < parc->GetLength())
  400. {
  401. double x, y,xtem,ytem;
  402. xtem = parc->GetuA() + parc->GetuB() * s + parc->GetuC() * s*s + parc->GetuD() * s*s*s;
  403. ytem = parc->GetvA() + parc->GetvB() * s + parc->GetvC() * s*s + parc->GetvD() * s*s*s;
  404. x = xtem*cos(parc->GetHdg()) - ytem * sin(parc->GetHdg()) + parc->GetX();
  405. y = xtem*sin(parc->GetHdg()) + ytem * cos(parc->GetHdg()) + parc->GetY();
  406. double hdg = CalcHdg(QPointF(xold,yold),QPointF(x,y));
  407. double fdis = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
  408. if(fdis<fdismin)
  409. {
  410. fdismin = fdis;
  411. nearhead = hdg;
  412. nearx = x;
  413. neary = y;
  414. }
  415. xold = x;
  416. yold = y;
  417. s = s+ 0.1;
  418. }
  419. return fdismin;
  420. }
  421. /**
  422. * @brief GetNearPoint
  423. * 计算点到圆弧的最短距离,首先用点和圆弧中心点的直线与圆的交点,计算点到交点的距离,如果交点在圆弧上,则最短距离是交点之一,否则计算点到圆弧两个端点的距离。
  424. * @param x current x
  425. * @param y current y
  426. * @param pxodr OpenDrive
  427. * @param pObjRoad Road
  428. * @param pgeo Geometry of road
  429. * @param nearx near x
  430. * @param neary near y
  431. * @param nearhead nearhead
  432. * @param nearthresh near threshhold
  433. * @retval if == 0 successfull <0 fail.
  434. **/
  435. int GetNearPoint(const double x,const double y,OpenDrive * pxodr,Road ** pObjRoad,GeometryBlock ** pgeo, double & s,double & nearx,
  436. double & neary,double & nearhead,const double nearthresh)
  437. {
  438. double dismin = std::numeric_limits<double>::infinity();
  439. s = dismin;
  440. int i;
  441. for(i=0;i<pxodr->GetRoadCount();i++)
  442. {
  443. int j;
  444. Road * proad = pxodr->GetRoad(i);
  445. double nx,ny,nh;
  446. for(j=0;j<proad->GetGeometryBlockCount();j++)
  447. {
  448. GeometryBlock * pgb = proad->GetGeometryBlock(j);
  449. double dis;
  450. RoadGeometry * pg;
  451. pg = pgb->GetGeometryAt(0);
  452. switch (pg->GetGeomType()) {
  453. case 0: //line
  454. dis = GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh);
  455. break;
  456. case 1:
  457. dis = GetSpiralDis((GeometrySpiral *)pg,x,y,nx,ny,nh);
  458. break;
  459. case 2: //arc
  460. dis = GetArcDis((GeometryArc *)pg,x,y,nx,ny,nh);
  461. break;
  462. case 3:
  463. dis = 100000.0;
  464. break;
  465. case 4:
  466. dis = GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh);
  467. break;
  468. default:
  469. dis = 100000.0;
  470. break;
  471. }
  472. if(dis < dismin)
  473. {
  474. dismin = dis;
  475. nearx = nx;
  476. neary = ny;
  477. nearhead = nh;
  478. s = dis;
  479. *pObjRoad = proad;
  480. *pgeo = pgb;
  481. }
  482. // if(pgb->CheckIfLine())
  483. // {
  484. // GeometryLine * pline = (GeometryLine *)pgb->GetGeometryAt(0);
  485. // double dis = GetLineDis(pline,x,y,nx,ny,nh);
  486. // if(dis < dismin)
  487. // {
  488. // dismin = dis;
  489. // nearx = nx;
  490. // neary = ny;
  491. // nearhead = nh;
  492. // s = dis;
  493. // *pObjRoad = proad;
  494. // *pgeo = pgb;
  495. // }
  496. // }
  497. // else
  498. // {
  499. // GeometryLine * pline1 = (GeometryLine *)pgb->GetGeometryAt(0);
  500. // double dis = GetLineDis(pline1,x,y,nx,ny,nh);
  501. // if(dis < dismin)
  502. // {
  503. // dismin = dis;
  504. // nearx = nx;
  505. // neary = ny;
  506. // nearhead = nh;
  507. // s = dis;
  508. // *pObjRoad = proad;
  509. // *pgeo = pgb;
  510. // }
  511. // GeometryArc * parc = (GeometryArc *)pgb->GetGeometryAt(1);
  512. // dis = GetArcDis(parc,x,y,nx,ny,nh);
  513. // if(dis < dismin)
  514. // {
  515. // dismin = dis;
  516. // nearx = nx;
  517. // neary = ny;
  518. // nearhead = nh;
  519. // s = dis;
  520. // *pObjRoad = proad;
  521. // *pgeo = pgb;
  522. // }
  523. // pline1 = (GeometryLine *)pgb->GetGeometryAt(2);
  524. // dis = GetLineDis(pline1,x,y,nx,ny,nh);
  525. // if(dis < dismin)
  526. // {
  527. // dismin = dis;
  528. // nearx = nx;
  529. // neary = ny;
  530. // nearhead = nh;
  531. // s = dis;
  532. // *pObjRoad = proad;
  533. // *pgeo = pgb;
  534. // }
  535. // }
  536. }
  537. }
  538. if(s > nearthresh)return -1;
  539. return 0;
  540. }
  541. int GetNearPointWithHead(const double x,const double y,const double hdg,OpenDrive * pxodr,Road ** pObjRoad,GeometryBlock ** pgeo, double & s,double & nearx,
  542. double & neary,double & nearhead,const double nearthresh)
  543. {
  544. double dismin = std::numeric_limits<double>::infinity();
  545. s = dismin;
  546. int i;
  547. std::vector<Road * > xvectorroad;
  548. std::vector<double > xvectordismin;
  549. std::vector<double > xvecotrnearx;
  550. std::vector<double > xvectorneary;
  551. std::vector<double > xvectornearhead;
  552. std::vector<double > xvectors;
  553. std::vector<GeometryBlock *> xvectorgeob;
  554. double VECTORTHRESH = 5;
  555. for(i=0;i<pxodr->GetRoadCount();i++)
  556. {
  557. int j;
  558. Road * proad = pxodr->GetRoad(i);
  559. double nx,ny,nh;
  560. bool bchange = false;
  561. double localdismin = std::numeric_limits<double>::infinity();
  562. double localnearx = 0;
  563. double localneary = 0;
  564. double localnearhead = 0;
  565. double locals = 0;
  566. GeometryBlock * pgeolocal;
  567. for(j=0;j<proad->GetGeometryBlockCount();j++)
  568. {
  569. GeometryBlock * pgb = proad->GetGeometryBlock(j);
  570. double dis;
  571. RoadGeometry * pg;
  572. pg = pgb->GetGeometryAt(0);
  573. switch (pg->GetGeomType()) {
  574. case 0: //line
  575. dis = GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh);
  576. break;
  577. case 1:
  578. dis = GetSpiralDis((GeometrySpiral *)pg,x,y,nx,ny,nh);
  579. break;
  580. case 2: //arc
  581. dis = GetArcDis((GeometryArc *)pg,x,y,nx,ny,nh);
  582. break;
  583. case 3:
  584. dis = 100000.0;
  585. break;
  586. case 4:
  587. dis = GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh);
  588. break;
  589. default:
  590. dis = 100000.0;
  591. break;
  592. }
  593. if(dis < dismin)
  594. {
  595. dismin = dis;
  596. nearx = nx;
  597. neary = ny;
  598. nearhead = nh;
  599. s = dis;
  600. *pObjRoad = proad;
  601. *pgeo = pgb;
  602. }
  603. if((dis<VECTORTHRESH) &&(dis<localdismin))
  604. {
  605. localdismin = dis;
  606. localnearx = nx;
  607. localneary = ny;
  608. localnearhead = nh;
  609. locals = dis;
  610. pgeolocal = pgb;
  611. bchange = true;
  612. }
  613. }
  614. if(bchange)
  615. {
  616. xvectorroad.push_back(proad);
  617. xvecotrnearx.push_back(localnearx);
  618. xvectorneary.push_back(localneary);
  619. xvectordismin.push_back(localdismin);
  620. xvectors.push_back(locals);
  621. xvectorgeob.push_back(pgeolocal);
  622. xvectornearhead.push_back(localnearhead);
  623. }
  624. }
  625. if(s > nearthresh)return -1;
  626. if((*pObjRoad)->GetLaneSectionCount()>0)
  627. {
  628. LaneSection * pLS = (*pObjRoad)->GetLaneSection(0);
  629. if((*pObjRoad)->GetLaneSection(0)->GetLeftLaneCount()&&(*pObjRoad)->GetLaneSection(0)->GetRightLaneCount()>0)
  630. {
  631. return 0;
  632. }
  633. else
  634. {
  635. double headdiff = hdg - nearhead;
  636. while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
  637. while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
  638. if(((headdiff <M_PI/2.0)||(headdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
  639. {
  640. return 0;
  641. }
  642. else
  643. {
  644. if((headdiff >=M_PI/2.0)&&(headdiff <= M_PI*3.0/2.0)&&(pLS->GetLeftLaneCount()>0))
  645. {
  646. return 0;
  647. }
  648. else
  649. {
  650. bool bHaveSame = false;
  651. for(i=0;i<xvectorroad.size();i++)
  652. {
  653. if(xvectorroad[i]->GetLaneSectionCount()<1)continue;
  654. bool bNeedFind = false;
  655. if(bHaveSame == false)bNeedFind = true;
  656. else
  657. {
  658. if(xvectordismin[i]<dismin)bNeedFind = true;
  659. }
  660. if(bNeedFind)
  661. {
  662. double fdiff = hdg - xvectornearhead[i];
  663. while(fdiff < 2.0*M_PI) fdiff = fdiff + 2.0*M_PI;
  664. while(fdiff >= 2.0*M_PI)fdiff = fdiff - 2.0*M_PI;
  665. bool bUse = false;
  666. LaneSection * pLS = xvectorroad[i]->GetLaneSection(0);
  667. if(((fdiff <M_PI/2.0)||(fdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
  668. {
  669. bUse = true;
  670. }
  671. if(((fdiff >=M_PI/2.0)&&(fdiff <= M_PI*3.0/2.0))&&(pLS->GetLeftLaneCount()>0))
  672. {
  673. bUse = true;
  674. }
  675. if(bUse)
  676. {
  677. dismin = xvectordismin[i];
  678. nearx = xvecotrnearx[i];
  679. neary = xvectorneary[i];
  680. nearhead = xvectornearhead[i];
  681. s = xvectors[i];
  682. *pObjRoad = xvectorroad[i];
  683. *pgeo = xvectorgeob[i];
  684. bHaveSame = true;
  685. std::cout<<"change road. "<<std::endl;
  686. }
  687. }
  688. }
  689. }
  690. }
  691. }
  692. }
  693. return 0;
  694. }
  695. /**
  696. * @brief SelectRoadLeftRight
  697. * 选择左侧道路或右侧道路
  698. * 1.选择角度差小于90度的道路一侧,即同侧道路
  699. * 2.单行路,选择存在的那一侧道路。
  700. * @param pRoad 道路
  701. * @param head1 车的航向或目标点的航向
  702. * @param head_road 目标点的航向
  703. * @retval 1 left 2 right
  704. **/
  705. static int SelectRoadLeftRight(Road * pRoad,const double head1,const double head_road)
  706. {
  707. int nrtn = 2;
  708. double headdiff = head1 - head_road;
  709. while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
  710. while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
  711. bool bSel = false;
  712. if((headdiff >=M_PI/2.0)&&(headdiff <= M_PI*3.0/2.0)) //if diff is
  713. {
  714. if(pRoad->GetLaneSection(0)->GetLeftLaneCount()>0)
  715. {
  716. nrtn = 1;
  717. bSel = true;
  718. }
  719. }
  720. else
  721. {
  722. if(pRoad->GetLaneSection(0)->GetRightLaneCount()>0)
  723. {
  724. nrtn = 2;
  725. bSel = true;
  726. }
  727. }
  728. if(bSel == false)
  729. {
  730. if(pRoad->GetLaneSection(0)->GetLeftLaneCount() >0)
  731. {
  732. nrtn = 1;
  733. }
  734. else
  735. {
  736. nrtn = 2;
  737. }
  738. }
  739. return nrtn;
  740. }
  741. //static double getlinereldis(GeometryLine * pline,double x,double y)
  742. //{
  743. // double x0,y0;
  744. // x0 = pline->GetX();
  745. // y0 = pline->GetY();
  746. // double dis = sqrt(pow(x-x0,2) + pow(y-y0,2));
  747. // if(dis > pline->GetS())
  748. // {
  749. // std::cout<<"getlinereldis exceed s S is "<<pline->GetS()<<" dis is "<<dis<<std::endl;
  750. // return dis;
  751. // }
  752. // return dis;
  753. //}
  754. //static double getarcreldis(GeometryArc * parc,double x,double y)
  755. //{
  756. // double x0,y0;
  757. // x0 = parc->GetX();
  758. // y0 = parc->GetY();
  759. // double dis = sqrt(pow(x-x0,2) + pow(y-y0,2));
  760. // double R = fabs(1.0/parc->GetCurvature());
  761. // double ang = 2.0* asin(dis/(2.0*R));
  762. // double frtn = ang * R;
  763. // return frtn;
  764. //}
  765. //static double getparampoly3reldis(GeometryParamPoly3 *parc, double xnow, double ynow)
  766. //{
  767. // double s = 0.1;
  768. // double xold,yold;
  769. // xold = parc->GetX();
  770. // yold = parc->GetY();
  771. // while(s < parc->GetLength())
  772. // {
  773. // double x, y,xtem,ytem;
  774. // xtem = parc->GetuA() + parc->GetuB() * s + parc->GetuC() * s*s + parc->GetuD() * s*s*s;
  775. // ytem = parc->GetvA() + parc->GetvB() * s + parc->GetvC() * s*s + parc->GetvD() * s*s*s;
  776. // x = xtem*cos(parc->GetHdg()) - ytem * sin(parc->GetHdg()) + parc->GetX();
  777. // y = xtem*sin(parc->GetHdg()) + ytem * cos(parc->GetHdg()) + parc->GetY();
  778. // if(sqrt(pow(xnow - x,2) + pow(ynow -y,2))<0.3)
  779. // {
  780. // break;
  781. // }
  782. // xold = x;
  783. // yold = y;
  784. // s = s+ 0.1;
  785. // }
  786. // return s;
  787. //}
  788. //static double getreldis(RoadGeometry * prg,double x,double y)
  789. //{
  790. // int ngeotype = prg->GetGeomType();
  791. // double frtn = 0;
  792. // switch (ngeotype) {
  793. // case 0:
  794. // frtn = getlinereldis((GeometryLine *)prg,x,y);
  795. // break;
  796. // case 1:
  797. // break;
  798. // case 2:
  799. // frtn = getarcreldis((GeometryArc *)prg,x,y);
  800. // break;
  801. // case 3:
  802. // break;
  803. // case 4:
  804. // frtn = getparampoly3reldis((GeometryParamPoly3 *)prg,x,y);
  805. // break;
  806. // default:
  807. // break;
  808. // }
  809. // return frtn;
  810. //}
  811. //static double getposinroad(Road * pRoad,GeometryBlock * pgeob,double x,double y)
  812. //{
  813. // RoadGeometry* prg = pgeob->GetGeometryAt(0);
  814. // double s1 = prg->GetS();
  815. // double srtn = s1;
  816. // return s1 + getreldis(prg,x,y);
  817. //}
  818. static std::vector<PlanPoint> getlinepoint(GeometryLine * pline)
  819. {
  820. std::vector<PlanPoint> xvectorPP;
  821. int i;
  822. double s = pline->GetLength();
  823. int nsize = s/0.1;
  824. for(i=0;i<nsize;i++)
  825. {
  826. double x,y;
  827. x = pline->GetX() + i *0.1 * cos(pline->GetHdg());
  828. y = pline->GetY() + i *0.1 * sin(pline->GetHdg());
  829. PlanPoint pp;
  830. pp.x = x;
  831. pp.y = y;
  832. pp.dis = i*0.1;
  833. pp.hdg = pline->GetHdg();
  834. pp.mS = pline->GetS() + i*0.1;
  835. xvectorPP.push_back(pp);
  836. }
  837. return xvectorPP;
  838. }
  839. static std::vector<PlanPoint> getarcpoint(GeometryArc * parc)
  840. {
  841. std::vector<PlanPoint> xvectorPP;
  842. // double fRtn = 1000.0;
  843. if(parc->GetCurvature() == 0.0)return xvectorPP;
  844. double R = fabs(1.0/parc->GetCurvature());
  845. //calculate arc center
  846. double x_center = parc->GetX() + (1.0/parc->GetCurvature()) * cos(parc->GetHdg() + M_PI/2.0);
  847. double y_center = parc->GetY() + (1.0/parc->GetCurvature()) * sin(parc->GetHdg()+ M_PI/2.0);
  848. double arcdiff = 0.1/R;
  849. int nsize = parc->GetLength()/0.1;
  850. int i;
  851. for(i=0;i<nsize;i++)
  852. {
  853. double x,y;
  854. PlanPoint pp;
  855. if(parc->GetCurvature() > 0)
  856. {
  857. x = x_center + R * cos(parc->GetHdg() + i*arcdiff - M_PI/2.0);
  858. y = y_center + R * sin(parc->GetHdg() + i*arcdiff - M_PI/2.0);
  859. pp.hdg = parc->GetHdg() + i*arcdiff;
  860. }
  861. else
  862. {
  863. x = x_center + R * cos(parc->GetHdg() -i*arcdiff + M_PI/2.0);
  864. y = y_center + R * sin(parc->GetHdg() -i*arcdiff + M_PI/2.0);
  865. pp.hdg = parc->GetHdg() - i*arcdiff;
  866. }
  867. pp.x = x;
  868. pp.y = y;
  869. pp.dis = i*0.1;
  870. pp.mS = parc->GetS() + i*0.1;
  871. xvectorPP.push_back(pp);
  872. }
  873. return xvectorPP;
  874. }
  875. static std::vector<PlanPoint> getspiralpoint(GeometrySpiral * pspiral)
  876. {
  877. double x,y,hdg;
  878. double s = 0.0;
  879. double s0 = pspiral->GetS();
  880. std::vector<PlanPoint> xvectorPP;
  881. PlanPoint pp;
  882. while(s<pspiral->GetLength())
  883. {
  884. pspiral->GetCoords(s0+s,x,y,hdg);
  885. pp.x = x;
  886. pp.y = y;
  887. pp.hdg = hdg;
  888. pp.dis = s;
  889. pp.mS = pspiral->GetS() + s;
  890. xvectorPP.push_back(pp);
  891. s = s+0.1;
  892. }
  893. return xvectorPP;
  894. }
  895. static std::vector<PlanPoint> getparampoly3dpoint(GeometryParamPoly3 * parc)
  896. {
  897. double s = 0.1;
  898. std::vector<PlanPoint> xvectorPP;
  899. PlanPoint pp;
  900. double xold,yold;
  901. xold = parc->GetX();
  902. yold = parc->GetY();
  903. double hdg0 = parc->GetHdg();
  904. pp.x = xold;
  905. pp.y = yold;
  906. pp.hdg = hdg0;
  907. pp.dis = 0;
  908. xvectorPP.push_back(pp);
  909. double dt = 1.0;
  910. double tcount = parc->GetLength()/0.1;
  911. if(tcount > 0)
  912. {
  913. dt = 1.0/tcount;
  914. }
  915. double t;
  916. s = dt;
  917. s = 0.1;
  918. double ua,ub,uc,ud,va,vb,vc,vd;
  919. ua = parc->GetuA();ub= parc->GetuB();uc= parc->GetuC();ud = parc->GetuD();
  920. va = parc->GetvA();vb= parc->GetvB();vc= parc->GetvC();vd = parc->GetvD();
  921. double a = parc->GetS();
  922. while(s < parc->GetLength())
  923. // while(s<1.0)
  924. {
  925. double len = parc->GetLength();
  926. double x, y,xtem,ytem;
  927. // xtem = parc->GetuA() + parc->GetuB() * s * len + parc->GetuC() * s*s *pow(len,2) + parc->GetuD() * s*s*s *pow(len,3);
  928. // ytem = parc->GetvA() + parc->GetvB() * s* len + parc->GetvC() * s*s *pow(len,2) + parc->GetvD() * s*s*s *pow(len,3);
  929. xtem = ua + ub * s + uc * s*s + ud * s*s*s ;
  930. ytem = va + vb * s + vc * s*s + vd * s*s*s ;
  931. x = xtem*cos(hdg0) - ytem * sin(hdg0) + parc->GetX();
  932. y = xtem*sin(hdg0) + ytem * cos(hdg0) + parc->GetY();
  933. // x= xtem + parc->GetX();
  934. // y = ytem + parc->GetY();
  935. // x = xtem*cos(parc->GetHdg()) + ytem * sin(parc->GetHdg()) + parc->GetX();
  936. // y = -xtem*sin(parc->GetHdg()) + ytem * cos(parc->GetHdg()) + parc->GetY();
  937. double hdg = CalcHdg(QPointF(xold,yold),QPointF(x,y));
  938. pp.x = x;
  939. pp.y = y;
  940. pp.hdg = hdg;
  941. double disx = sqrt(pow(x-xold,2)+ pow(y-yold,2));
  942. /* if(disx > 0.1)s = s+ disx;
  943. else s = s+ 0.5*/;
  944. s = s+ 0.1;
  945. // s = s+ sqrt(pow(x-xold,2)+ pow(y-yold,2));
  946. xold = x;
  947. yold = y;
  948. // s = s+ dt;
  949. pp.dis = pp.dis + disx;;
  950. pp.mS = parc->GetS() + s;
  951. xvectorPP.push_back(pp);
  952. // std::cout<<" s is "<<s<<std::endl;
  953. }
  954. return xvectorPP;
  955. }
  956. std::vector<PlanPoint> GetPoint(Road * pRoad)
  957. {
  958. std::vector<PlanPoint> xvectorPPS;
  959. double s = 0;
  960. int i;
  961. for(i=0;i<pRoad->GetGeometryBlockCount();i++)
  962. {
  963. GeometryBlock * pgb = pRoad->GetGeometryBlock(i);
  964. RoadGeometry * prg = pgb->GetGeometryAt(0);
  965. std::vector<PlanPoint> xvectorPP;
  966. double s1 = prg->GetLength();
  967. switch (prg->GetGeomType()) {
  968. case 0:
  969. xvectorPP = getlinepoint((GeometryLine *)prg);
  970. break;
  971. case 1:
  972. xvectorPP = getspiralpoint((GeometrySpiral *)prg);
  973. break;
  974. case 2:
  975. xvectorPP = getarcpoint((GeometryArc *)prg);
  976. break;
  977. case 3:
  978. break;
  979. case 4:
  980. xvectorPP = getparampoly3dpoint((GeometryParamPoly3 *)prg);
  981. break;
  982. default:
  983. break;
  984. }
  985. int j;
  986. for(j=0;j<xvectorPP.size();j++)
  987. {
  988. PlanPoint pp = xvectorPP.at(j);
  989. pp.dis = s + pp.dis;
  990. xvectorPPS.push_back(pp);
  991. }
  992. s = s+ s1;
  993. }
  994. return xvectorPPS;
  995. }
  996. int indexinroadpoint(std::vector<PlanPoint> xvectorPP,double x,double y)
  997. {
  998. int nrtn = 0;
  999. int i;
  1000. int dismin = 1000;
  1001. for(i=0;i<xvectorPP.size();i++)
  1002. {
  1003. double dis = sqrt(pow(xvectorPP.at(i).x - x,2) + pow(xvectorPP.at(i).y -y,2));
  1004. if(dis <dismin)
  1005. {
  1006. dismin = dis;
  1007. nrtn = i;
  1008. }
  1009. }
  1010. if(dismin > 10.0)
  1011. {
  1012. std::cout<<"indexinroadpoint near point is error. dis is "<<dismin<<std::endl;
  1013. }
  1014. return nrtn;
  1015. }
  1016. double getwidth(Road * pRoad, int nlane)
  1017. {
  1018. double frtn = 0;
  1019. int i;
  1020. int nlanecount = pRoad->GetLaneSection(0)->GetLaneCount();
  1021. for(i=0;i<nlanecount;i++)
  1022. {
  1023. if(nlane == pRoad->GetLaneSection(0)->GetLane(i)->GetId())
  1024. {
  1025. LaneWidth* pLW = pRoad->GetLaneSection(0)->GetLane(i)->GetLaneWidth(0);
  1026. if(pLW != 0)
  1027. {
  1028. frtn = pRoad->GetLaneSection(0)->GetLane(i)->GetLaneWidth(0)->GetA();
  1029. break;
  1030. }
  1031. }
  1032. }
  1033. return frtn;
  1034. }
  1035. double getoff(Road * pRoad,int nlane)
  1036. {
  1037. double off = getwidth(pRoad,nlane)/2.0;
  1038. if(nlane < 0)off = off * (-1.0);
  1039. // int nlanecount = pRoad->GetLaneSection(0)->GetLaneCount();
  1040. int i;
  1041. if(nlane > 0)
  1042. off = off + getwidth(pRoad,0)/2.0;
  1043. else
  1044. off = off - getwidth(pRoad,0)/2.0;
  1045. if(nlane > 0)
  1046. {
  1047. for(i=1;i<nlane;i++)
  1048. {
  1049. off = off + getwidth(pRoad,i);
  1050. }
  1051. }
  1052. else
  1053. {
  1054. for(i=-1;i>nlane;i--)
  1055. {
  1056. off = off - getwidth(pRoad,i);
  1057. }
  1058. }
  1059. // return 0;
  1060. return off;
  1061. }
  1062. namespace iv {
  1063. struct lanewidthabcd
  1064. {
  1065. int nlane;
  1066. double A;
  1067. double B;
  1068. double C;
  1069. double D;
  1070. };
  1071. }
  1072. double getwidth(Road * pRoad, int nlane,std::vector<iv::lanewidthabcd> xvectorlwa,double s)
  1073. {
  1074. double frtn = 0;
  1075. int i;
  1076. int nlanecount = xvectorlwa.size();
  1077. for(i=0;i<nlanecount;i++)
  1078. {
  1079. if(nlane == xvectorlwa.at(i).nlane)
  1080. {
  1081. iv::lanewidthabcd * plwa = &xvectorlwa.at(i);
  1082. frtn = plwa->A + plwa->B*s + plwa->C *s*s + plwa->D *s*s*s;
  1083. break;
  1084. }
  1085. }
  1086. return frtn;
  1087. }
  1088. std::vector<iv::lanewidthabcd> GetLaneWidthABCD(Road * pRoad)
  1089. {
  1090. std::vector<iv::lanewidthabcd> xvectorlwa;
  1091. if(pRoad->GetLaneSectionCount()<1)return xvectorlwa;
  1092. int i;
  1093. LaneSection * pLS = pRoad->GetLaneSection(0);
  1094. // if(pRoad->GetLaneSectionCount() > 1)
  1095. // {
  1096. // for(i=0;i<(pRoad->GetLaneSectionCount()-1);i++)
  1097. // {
  1098. // if(s>pRoad->GetLaneSection(i+1)->GetS())
  1099. // {
  1100. // pLS = pRoad->GetLaneSection(i+1);
  1101. // }
  1102. // else
  1103. // {
  1104. // break;
  1105. // }
  1106. // }
  1107. // }
  1108. int nlanecount = pLS->GetLaneCount();
  1109. for(i=0;i<nlanecount;i++)
  1110. {
  1111. iv::lanewidthabcd xlwa;
  1112. LaneWidth* pLW = pLS->GetLane(i)->GetLaneWidth(0);
  1113. xlwa.nlane = pLS->GetLane(i)->GetId();
  1114. if(pLW != 0)
  1115. {
  1116. xlwa.A = pLW->GetA();
  1117. xlwa.B = pLW->GetB();
  1118. xlwa.C = pLW->GetC();
  1119. xlwa.D = pLW->GetD();
  1120. }
  1121. else
  1122. {
  1123. xlwa.A = 0;
  1124. xlwa.B = 0;
  1125. xlwa.C = 0;
  1126. xlwa.D = 0;
  1127. }
  1128. // if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
  1129. xvectorlwa.push_back(xlwa); //Calculate Road Width, not driving need add in.
  1130. }
  1131. return xvectorlwa;
  1132. }
  1133. inline double getoff(int nlane,double s,std::vector<iv::lanewidthabcd> xvectorLWA,std::vector<int> xvectorIndex)
  1134. {
  1135. int i;
  1136. double off = 0;
  1137. double a,b,c,d;
  1138. if(xvectorIndex.size() == 0)return off;
  1139. for(i=0;i<(xvectorIndex.size()-1);i++)
  1140. {
  1141. a = xvectorLWA[xvectorIndex[i]].A;
  1142. b = xvectorLWA[xvectorIndex[i]].B;
  1143. c = xvectorLWA[xvectorIndex[i]].C;
  1144. d = xvectorLWA[xvectorIndex[i]].D;
  1145. if(xvectorLWA[xvectorIndex[i]].nlane != 0)
  1146. {
  1147. off = off + a + b*s + c*s*s + d*s*s*s;
  1148. }
  1149. else
  1150. {
  1151. off = off + (a + b*s + c*s*s + d*s*s*s)/2.0;
  1152. }
  1153. }
  1154. i = xvectorIndex.size()-1;
  1155. a = xvectorLWA[xvectorIndex[i]].A;
  1156. b = xvectorLWA[xvectorIndex[i]].B;
  1157. c = xvectorLWA[xvectorIndex[i]].C;
  1158. d = xvectorLWA[xvectorIndex[i]].D;
  1159. off = off + (a + b*s + c*s*s + d*s*s*s)/2.0;
  1160. if(nlane < 0) off = off*(-1.0);
  1161. // std::cout<<"s is "<<s<<std::endl;
  1162. return off;
  1163. }
  1164. double GetRoadWidth(std::vector<iv::lanewidthabcd> xvectorLWA,int nlane,double s)
  1165. {
  1166. double fwidth = 0;
  1167. int i;
  1168. double a,b,c,d;
  1169. int nsize = xvectorLWA.size();
  1170. for(i=0;i<nsize;i++)
  1171. {
  1172. if(nlane*(xvectorLWA[i].nlane)>0)
  1173. {
  1174. a = xvectorLWA[i].A;
  1175. b = xvectorLWA[i].B;
  1176. c = xvectorLWA[i].C;
  1177. d = xvectorLWA[i].D;
  1178. fwidth = fwidth + a + b*s +c*s*s + d*s*s*s;
  1179. }
  1180. }
  1181. return fwidth;
  1182. }
  1183. int GetLaneOriTotal(Road * pRoad, int nlane,double s,int & nori, int & ntotal,double & fSpeed)
  1184. {
  1185. if(pRoad->GetLaneSectionCount() < 1)return -1;
  1186. LaneSection * pLS = pRoad->GetLaneSection(0);
  1187. int i;
  1188. if(pRoad->GetLaneSectionCount() > 1)
  1189. {
  1190. for(i=0;i<(pRoad->GetLaneSectionCount()-1);i++)
  1191. {
  1192. if(s>pRoad->GetLaneSection(i+1)->GetS())
  1193. {
  1194. pLS = pRoad->GetLaneSection(i+1);
  1195. }
  1196. else
  1197. {
  1198. break;
  1199. }
  1200. }
  1201. }
  1202. nori = 0;
  1203. ntotal = 0;
  1204. fSpeed = -1; //if -1 no speedlimit for map
  1205. int nlanecount = pLS->GetLaneCount();
  1206. for(i=0;i<nlanecount;i++)
  1207. {
  1208. int nlaneid = pLS->GetLane(i)->GetId();
  1209. if(nlaneid == nlane)
  1210. {
  1211. Lane * pLane = pLS->GetLane(i);
  1212. if(pLane->GetLaneSpeedCount() > 0)
  1213. {
  1214. LaneSpeed * pLSpeed = pLane->GetLaneSpeed(0);
  1215. int j;
  1216. int nspeedcount = pLane->GetLaneSpeedCount();
  1217. for(j=0;j<(nspeedcount -1);j++)
  1218. {
  1219. if((s-pLS->GetS())>=pLane->GetLaneSpeed(j+1)->GetS())
  1220. {
  1221. pLSpeed = pLane->GetLaneSpeed(j+1);
  1222. }
  1223. else
  1224. {
  1225. break;
  1226. }
  1227. }
  1228. fSpeed = pLSpeed->GetMax();
  1229. }
  1230. }
  1231. if(nlane<0)
  1232. {
  1233. if(nlaneid < 0)
  1234. {
  1235. if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
  1236. {
  1237. ntotal++;
  1238. if(nlaneid<nlane)nori++;
  1239. }
  1240. }
  1241. }
  1242. else
  1243. {
  1244. if(nlaneid > 0)
  1245. {
  1246. if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
  1247. {
  1248. ntotal++;
  1249. if(nlaneid > nlane)nori++;
  1250. }
  1251. }
  1252. }
  1253. }
  1254. return 0;
  1255. }
  1256. std::vector<int> GetLWIndex(std::vector<iv::lanewidthabcd> xvectorLWA,int nlane)
  1257. {
  1258. std::vector<int> xvectorindex;
  1259. int i;
  1260. if(nlane >= 0)
  1261. {
  1262. for(i=0;i<=nlane;i++)
  1263. {
  1264. int j;
  1265. int nsize = xvectorLWA.size();
  1266. for(j=0;j<nsize;j++)
  1267. {
  1268. if(i == xvectorLWA.at(j).nlane )
  1269. {
  1270. xvectorindex.push_back(j);
  1271. break;
  1272. }
  1273. }
  1274. }
  1275. }
  1276. else
  1277. {
  1278. for(i=0;i>=nlane;i--)
  1279. {
  1280. int j;
  1281. int nsize = xvectorLWA.size();
  1282. for(j=0;j<nsize;j++)
  1283. {
  1284. if(i == xvectorLWA.at(j).nlane )
  1285. {
  1286. xvectorindex.push_back(j);
  1287. break;
  1288. }
  1289. }
  1290. }
  1291. }
  1292. return xvectorindex;
  1293. }
  1294. //暂不考虑多个LaneSection的情况,不考虑车道宽度变化
  1295. std::vector<PlanPoint> GetLanePoint(pathsection xps,std::vector<PlanPoint> xvPP)
  1296. {
  1297. std::vector<PlanPoint> xvectorPP;
  1298. std::vector<iv::lanewidthabcd> xvectorLWA = GetLaneWidthABCD(xps.mpRoad);
  1299. std::vector<int> xvectorindex1,xvectorindex2,xvectorindex3;
  1300. int nchange1,nchange2;
  1301. int nlane1,nlane2,nlane3;
  1302. if(xps.mnStartLaneSel == xps.mnEndLaneSel)
  1303. {
  1304. xps.mainsel = xps.mnStartLaneSel;
  1305. xps.mbStartToMainChange = false;
  1306. xps.mbMainToEndChange = false;
  1307. }
  1308. else
  1309. {
  1310. if(xps.mpRoad->GetRoadLength() < 100)
  1311. {
  1312. xps.mainsel = xps.mnEndLaneSel;
  1313. xps.mbStartToMainChange = true;
  1314. xps.mbMainToEndChange = false;
  1315. }
  1316. }
  1317. double off1,off2,off3;
  1318. if(xps.mnStartLaneSel < 0)
  1319. {
  1320. off1 = getoff(xps.mpRoad,xps.mnStartLaneSel);
  1321. off2 = getoff(xps.mpRoad,xps.mainsel);
  1322. off3 = getoff(xps.mpRoad,xps.mnEndLaneSel);
  1323. xvectorindex1 = GetLWIndex(xvectorLWA,xps.mnStartLaneSel);
  1324. xvectorindex2 = GetLWIndex(xvectorLWA,xps.mainsel);
  1325. xvectorindex3 = GetLWIndex(xvectorLWA,xps.mnEndLaneSel);
  1326. nlane1 = xps.mnStartLaneSel;
  1327. nlane2 = xps.mainsel;
  1328. nlane3 = xps.mnEndLaneSel;
  1329. }
  1330. else
  1331. {
  1332. off3 = getoff(xps.mpRoad,xps.mnStartLaneSel);
  1333. off2 = getoff(xps.mpRoad,xps.mainsel);
  1334. off1 = getoff(xps.mpRoad,xps.mnEndLaneSel);
  1335. xvectorindex3 = GetLWIndex(xvectorLWA,xps.mnStartLaneSel);
  1336. xvectorindex2 = GetLWIndex(xvectorLWA,xps.mainsel);
  1337. xvectorindex1 = GetLWIndex(xvectorLWA,xps.mnEndLaneSel);
  1338. nlane3 = xps.mnStartLaneSel;
  1339. nlane2 = xps.mainsel;
  1340. nlane1 = xps.mnEndLaneSel;
  1341. }
  1342. int nchangepoint = 300;
  1343. if((nchangepoint * 3) > xvPP.size())
  1344. {
  1345. nchangepoint = xvPP.size()/3;
  1346. }
  1347. int nsize = xvPP.size();
  1348. nchange1 = nsize/3;
  1349. if(nchange1>500)nchange1 = 500;
  1350. nchange2 = nsize*2/3;
  1351. if( (nsize-nchange2)>500)nchange2 = nsize-500;
  1352. // if(nsize < 1000)
  1353. // {
  1354. // std::cout<<"GetLanePoint Error. road id is "<<xps.mpRoad->GetRoadId()<<std::endl;
  1355. // return xvectorPP;
  1356. // }
  1357. double x,y;
  1358. int i;
  1359. if(xps.mainsel < 0)
  1360. {
  1361. for(i=0;i<(nchange1- nchangepoint/2);i++)
  1362. {
  1363. PlanPoint pp = xvPP.at(i);
  1364. off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
  1365. pp.x = pp.x + off1 *cos(pp.hdg + M_PI/2.0);
  1366. pp.y = pp.y + off1 *sin(pp.hdg + M_PI/2.0);
  1367. pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  1368. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1369. pp.lanmp = 0;
  1370. pp.mfDisToRoadLeft = off1*(-1);
  1371. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
  1372. GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1373. xvectorPP.push_back(pp);
  1374. }
  1375. for(i=(nchange1 - nchangepoint/2);i<(nchange1+nchangepoint/2);i++)
  1376. {
  1377. PlanPoint pp = xvPP.at(i);
  1378. off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
  1379. off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  1380. double offx = off1 + (off2 - off1) *(i-nchange1 + nchangepoint/2)/nchangepoint;
  1381. pp.x = pp.x + offx *cos(pp.hdg + M_PI/2.0);
  1382. pp.y = pp.y + offx *sin(pp.hdg + M_PI/2.0);
  1383. double flanewidth1 = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  1384. pp.mfDisToRoadLeft = offx*(-1);
  1385. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
  1386. if(nlane1 == nlane2)
  1387. {
  1388. pp.mWidth = flanewidth1;
  1389. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1390. pp.lanmp = 0;
  1391. GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1392. }
  1393. else
  1394. {
  1395. if(nlane1 < nlane2)
  1396. {
  1397. pp.lanmp = 1;
  1398. }
  1399. else
  1400. {
  1401. pp.lanmp = -1;
  1402. }
  1403. if(i<nchange1)
  1404. {
  1405. pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  1406. double fmove = pp.mWidth * (i-(nchange1 - nchangepoint/2))/nchangepoint;
  1407. if(nlane1<nlane2)pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  1408. else pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  1409. GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1410. }
  1411. else
  1412. {
  1413. pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  1414. double fmove = pp.mWidth * (nchange1+nchangepoint/2 -i)/nchangepoint;
  1415. if(nlane1<nlane2)pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  1416. else pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  1417. GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1418. }
  1419. }
  1420. xvectorPP.push_back(pp);
  1421. }
  1422. for(i=(nchange1 + nchangepoint/2);i<(nchange2-nchangepoint/2);i++)
  1423. {
  1424. PlanPoint pp = xvPP.at(i);
  1425. off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  1426. pp.x = pp.x + off2 *cos(pp.hdg + M_PI/2.0);
  1427. pp.y = pp.y + off2 *sin(pp.hdg + M_PI/2.0);
  1428. pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  1429. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1430. pp.lanmp = 0;
  1431. pp.mfDisToRoadLeft = off2*(-1);
  1432. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane2,pp.mS);
  1433. GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1434. xvectorPP.push_back(pp);
  1435. }
  1436. for(i=(nchange2 - nchangepoint/2);i<(nchange2+nchangepoint/2);i++)
  1437. {
  1438. PlanPoint pp = xvPP.at(i);
  1439. off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  1440. off3 = getoff(nlane3,pp.mS,xvectorLWA,xvectorindex3);
  1441. double offx = off2 + (off3 - off2) *(i-nchange2 + nchangepoint/2)/nchangepoint;
  1442. pp.x = pp.x + offx *cos(pp.hdg + M_PI/2.0);
  1443. pp.y = pp.y + offx *sin(pp.hdg + M_PI/2.0);
  1444. double flanewidth1 = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  1445. pp.mfDisToRoadLeft = offx*(-1);
  1446. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane2,pp.mS);
  1447. if(nlane2 == nlane3)
  1448. {
  1449. pp.mWidth = flanewidth1;
  1450. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1451. pp.lanmp = 0;
  1452. GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1453. }
  1454. else
  1455. {
  1456. if(nlane2 < nlane3)
  1457. {
  1458. pp.lanmp = 1;
  1459. }
  1460. else
  1461. {
  1462. pp.lanmp = -1;
  1463. }
  1464. if(i<nchange2)
  1465. {
  1466. pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  1467. double fmove = pp.mWidth * (i-(nchange2 - nchangepoint/2))/nchangepoint;
  1468. if(nlane2<nlane3)pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  1469. else pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  1470. GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1471. }
  1472. else
  1473. {
  1474. pp.mWidth = getwidth(xps.mpRoad,nlane3,xvectorLWA,pp.mS);
  1475. double fmove = pp.mWidth * (nchange2+nchangepoint/2 -i)/nchangepoint;
  1476. if(nlane2<nlane3)pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  1477. else pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  1478. GetLaneOriTotal(xps.mpRoad,nlane3,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1479. }
  1480. }
  1481. xvectorPP.push_back(pp);
  1482. }
  1483. for(i=(nchange2 + nchangepoint/2);i<nsize;i++)
  1484. {
  1485. PlanPoint pp = xvPP.at(i);
  1486. off3 = getoff(nlane3,pp.mS,xvectorLWA,xvectorindex3);
  1487. pp.x = pp.x + off3 *cos(pp.hdg + M_PI/2.0);
  1488. pp.y = pp.y + off3 *sin(pp.hdg + M_PI/2.0);
  1489. pp.mWidth = getwidth(xps.mpRoad,nlane3,xvectorLWA,pp.mS);
  1490. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1491. pp.lanmp = 0;
  1492. pp.mfDisToRoadLeft = off3*(-1);
  1493. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane3,pp.mS);
  1494. GetLaneOriTotal(xps.mpRoad,nlane3,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1495. xvectorPP.push_back(pp);
  1496. }
  1497. }
  1498. else
  1499. {
  1500. for(i=0;i<(nchange1- nchangepoint/2);i++)
  1501. {
  1502. PlanPoint pp = xvPP.at(i);
  1503. off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
  1504. pp.x = pp.x + off1 *cos(pp.hdg + M_PI/2.0);
  1505. pp.y = pp.y + off1 *sin(pp.hdg + M_PI/2.0);
  1506. pp.hdg = pp.hdg + M_PI;
  1507. pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  1508. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1509. pp.lanmp = 0;
  1510. pp.mfDisToRoadLeft = off1;
  1511. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
  1512. GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1513. xvectorPP.push_back(pp);
  1514. }
  1515. for(i=(nchange1 - nchangepoint/2);i<(nchange1+nchangepoint/2);i++)
  1516. {
  1517. PlanPoint pp = xvPP.at(i);
  1518. off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
  1519. off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  1520. double offx = off1 + (off2 - off1) *(i-nchange1 + nchangepoint/2)/nchangepoint;
  1521. pp.x = pp.x + offx *cos(pp.hdg + M_PI/2.0);
  1522. pp.y = pp.y + offx *sin(pp.hdg + M_PI/2.0);
  1523. pp.hdg = pp.hdg + M_PI;
  1524. double flanewidth1 = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  1525. pp.mfDisToRoadLeft = offx;
  1526. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
  1527. if(nlane1 == nlane2)
  1528. {
  1529. pp.mWidth = flanewidth1;
  1530. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1531. pp.lanmp = 0;
  1532. GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1533. }
  1534. else
  1535. {
  1536. if(nlane1 < nlane2)
  1537. {
  1538. pp.lanmp = -1;
  1539. }
  1540. else
  1541. {
  1542. pp.lanmp = 1;
  1543. }
  1544. if(i<nchange1)
  1545. {
  1546. pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
  1547. double fmove = pp.mWidth * (i-(nchange1 - nchangepoint/2))/nchangepoint;
  1548. if(nlane1<nlane2)pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  1549. else pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  1550. GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1551. }
  1552. else
  1553. {
  1554. pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  1555. double fmove = pp.mWidth * (nchange1+nchangepoint/2 -i)/nchangepoint;
  1556. if(nlane1<nlane2)pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  1557. else pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  1558. GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1559. }
  1560. }
  1561. xvectorPP.push_back(pp);
  1562. }
  1563. for(i=(nchange1 + nchangepoint/2);i<(nchange2-nchangepoint/2);i++)
  1564. {
  1565. PlanPoint pp = xvPP.at(i);
  1566. off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  1567. pp.x = pp.x + off2 *cos(pp.hdg + M_PI/2.0);
  1568. pp.y = pp.y + off2 *sin(pp.hdg + M_PI/2.0);
  1569. pp.hdg = pp.hdg + M_PI;
  1570. pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  1571. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1572. pp.lanmp = 0;
  1573. pp.mfDisToRoadLeft = off2;
  1574. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane2,pp.mS);
  1575. GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1576. xvectorPP.push_back(pp);
  1577. }
  1578. for(i=(nchange2 - nchangepoint/2);i<(nchange2+nchangepoint/2);i++)
  1579. {
  1580. PlanPoint pp = xvPP.at(i);
  1581. off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
  1582. off3 = getoff(nlane3,pp.mS,xvectorLWA,xvectorindex3);
  1583. double offx = off2 + (off3 - off2) *(i-nchange2 + nchangepoint/2)/nchangepoint;
  1584. pp.x = pp.x + offx *cos(pp.hdg + M_PI/2.0);
  1585. pp.y = pp.y + offx *sin(pp.hdg + M_PI/2.0);
  1586. pp.hdg = pp.hdg + M_PI;
  1587. double flanewidth1 = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  1588. pp.mfDisToRoadLeft = offx;
  1589. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane2,pp.mS);
  1590. if(nlane2 == nlane3)
  1591. {
  1592. pp.mWidth = flanewidth1;
  1593. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1594. pp.lanmp = 0;
  1595. GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1596. }
  1597. else
  1598. {
  1599. if(nlane2 < nlane3)
  1600. {
  1601. pp.lanmp = -1;
  1602. }
  1603. else
  1604. {
  1605. pp.lanmp = 1;
  1606. }
  1607. if(i<nchange2)
  1608. {
  1609. pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
  1610. double fmove = pp.mWidth * (i-(nchange2 - nchangepoint/2))/nchangepoint;
  1611. if(nlane2<nlane3)pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  1612. else pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  1613. GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1614. }
  1615. else
  1616. {
  1617. pp.mWidth = getwidth(xps.mpRoad,nlane3,xvectorLWA,pp.mS);
  1618. double fmove = pp.mWidth * (nchange2+nchangepoint/2 -i)/nchangepoint;
  1619. if(nlane2<nlane3)pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
  1620. else pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
  1621. GetLaneOriTotal(xps.mpRoad,nlane3,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1622. }
  1623. }
  1624. xvectorPP.push_back(pp);
  1625. }
  1626. for(i=(nchange2+ nchangepoint/2);i<nsize;i++)
  1627. {
  1628. PlanPoint pp = xvPP.at(i);
  1629. off3 = getoff(nlane3,pp.mS,xvectorLWA,xvectorindex3);
  1630. pp.x = pp.x + off3 *cos(pp.hdg + M_PI/2.0);
  1631. pp.y = pp.y + off3 *sin(pp.hdg + M_PI/2.0);
  1632. pp.hdg = pp.hdg + M_PI;
  1633. pp.mWidth = getwidth(xps.mpRoad,nlane3,xvectorLWA,pp.mS);
  1634. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1635. pp.lanmp = 0;
  1636. pp.mfDisToRoadLeft = off3;
  1637. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane3,pp.mS);
  1638. GetLaneOriTotal(xps.mpRoad,nlane3,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1639. xvectorPP.push_back(pp);
  1640. }
  1641. }
  1642. Road * pRoad = xps.mpRoad;
  1643. if(xps.mnStartLaneSel > 0)
  1644. {
  1645. std::vector<PlanPoint> xvvPP;
  1646. int nvsize = xvectorPP.size();
  1647. for(i=0;i<nvsize;i++)
  1648. {
  1649. xvvPP.push_back(xvectorPP.at(nvsize-1-i));
  1650. }
  1651. return xvvPP;
  1652. }
  1653. // pRoad->GetLaneSection(xps.msectionid)
  1654. return xvectorPP;
  1655. }
  1656. static std::vector<PlanPoint> GetPlanPoint(std::vector<pathsection> xpathsection,Road * pRoad,GeometryBlock * pgeob,
  1657. Road * pRoad_obj,GeometryBlock * pgeob_obj,
  1658. const double x_now,const double y_now,const double head,
  1659. double nearx,double neary, double nearhead,
  1660. double nearx_obj,double neary_obj)
  1661. {
  1662. std::vector<PlanPoint> xvectorPPs;
  1663. std::vector<PlanPoint> xvectorPP = GetPoint( xpathsection[0].mpRoad);
  1664. int indexstart = indexinroadpoint(xvectorPP,nearx,neary);
  1665. int i;
  1666. std::vector<PlanPoint> xvPP = GetLanePoint(xpathsection[0],xvectorPP);
  1667. if(xpathsection[0].mainsel < 0)
  1668. {
  1669. for(i=indexstart;i<xvPP.size();i++)
  1670. {
  1671. xvectorPPs.push_back(xvPP.at(i));
  1672. }
  1673. }
  1674. else
  1675. {
  1676. for(i=(xvPP.size() -indexstart);i<xvPP.size();i++)
  1677. {
  1678. PlanPoint pp;
  1679. pp = xvPP.at(i);
  1680. // pp.hdg = pp.hdg +M_PI;
  1681. xvectorPPs.push_back(pp);
  1682. }
  1683. }
  1684. int npathlast = xpathsection.size() - 1;
  1685. // while(npathlast >= 0)
  1686. // {
  1687. // if(npathlast == 0)break;
  1688. // if(xpathsection[npathlast].mpRoad != xpathsection[npathlast - 1].mpRoad)break;
  1689. // }
  1690. for(i=1;i<(npathlast);i++)
  1691. {
  1692. if(xpathsection[i].mpRoad == xpathsection[i-1].mpRoad)
  1693. {
  1694. if(xpathsection[i].mainsel * xpathsection[i-1].mainsel >0)
  1695. {
  1696. continue;
  1697. }
  1698. }
  1699. if(xpathsection[i].mpRoad == xpathsection[npathlast].mpRoad)
  1700. {
  1701. if(xpathsection[i].mainsel * xpathsection[npathlast].mainsel > 0)
  1702. {
  1703. break;
  1704. }
  1705. }
  1706. xvectorPP = GetPoint( xpathsection[i].mpRoad);
  1707. xvPP = GetLanePoint(xpathsection[i],xvectorPP);
  1708. // std::cout<<" road id is "<<xpathsection[i].mpRoad->GetRoadId().data()<<" size is "<<xvPP.size()<<std::endl;
  1709. int j;
  1710. for(j=0;j<xvPP.size();j++)
  1711. {
  1712. xvectorPPs.push_back(xvPP.at(j));
  1713. }
  1714. }
  1715. xvectorPP = GetPoint(xpathsection[npathlast].mpRoad);
  1716. int indexend = indexinroadpoint(xvectorPP,nearx_obj,neary_obj);
  1717. xvPP = GetLanePoint(xpathsection[npathlast],xvectorPP);
  1718. int nlastsize;
  1719. if(xpathsection[npathlast].mainsel<0)
  1720. {
  1721. nlastsize = indexend;
  1722. }
  1723. else
  1724. {
  1725. if(indexend>0) nlastsize = xvPP.size() - indexend;
  1726. else nlastsize = xvPP.size();
  1727. }
  1728. for(i=0;i<nlastsize;i++)
  1729. {
  1730. xvectorPPs.push_back(xvPP.at(i));
  1731. }
  1732. //Find StartPoint
  1733. // if
  1734. // int a = 1;
  1735. return xvectorPPs;
  1736. }
  1737. std::vector<PlanPoint> gTempPP;
  1738. int getPoint(double q[3], double x, void* user_data) {
  1739. // printf("%f, %f, %f, %f\n", q[0], q[1], q[2], x);
  1740. PlanPoint pp;
  1741. pp.x = q[0];
  1742. pp.y = q[1];
  1743. pp.hdg = q[2];
  1744. pp.dis = x;
  1745. pp.speed = *((double *)user_data);
  1746. gTempPP.push_back(pp);
  1747. // std::cout<<pp.x<<" "<<" "<<pp.y<<" "<<pp.hdg<<std::endl;
  1748. return 0;
  1749. }
  1750. /**
  1751. * @brief getlanesel
  1752. * @param nSel
  1753. * @param pLaneSection
  1754. * @param nlr
  1755. * @return
  1756. */
  1757. int getlanesel(int nSel,LaneSection * pLaneSection,int nlr)
  1758. {
  1759. int nlane = nSel;
  1760. int mainselindex = 0;
  1761. if(nlr == 2)nlane = nlane*(-1);
  1762. int nlanecount = pLaneSection->GetLaneCount();
  1763. int i;
  1764. int nTrueSel = nSel;
  1765. if(nTrueSel <= 1)nTrueSel= 1;
  1766. int nCurSel = 1;
  1767. if(nlr == 2)nCurSel = nCurSel *(-1);
  1768. bool bOK = false;
  1769. int nxsel = 1;
  1770. int nlasttid = 0;
  1771. bool bfindlast = false;
  1772. while(bOK == false)
  1773. {
  1774. bool bHaveDriving = false;
  1775. int ncc = 0;
  1776. for(i=0;i<nlanecount;i++)
  1777. {
  1778. Lane * pLane = pLaneSection->GetLane(i);
  1779. if(strncmp(pLane->GetType().data(),"driving",255) == 0 )
  1780. {
  1781. if((nlr == 1)&&(pLane->GetId()>0))
  1782. {
  1783. ncc++;
  1784. }
  1785. if((nlr == 2)&&(pLane->GetId()<0))
  1786. {
  1787. ncc++;
  1788. }
  1789. if(ncc == nxsel)
  1790. {
  1791. bHaveDriving = true;
  1792. bfindlast = true;
  1793. nlasttid = pLane->GetId();
  1794. break;
  1795. }
  1796. }
  1797. }
  1798. if(bHaveDriving == true)
  1799. {
  1800. if(nxsel == nTrueSel)
  1801. {
  1802. return nlasttid;
  1803. }
  1804. else
  1805. {
  1806. nxsel++;
  1807. }
  1808. }
  1809. else
  1810. {
  1811. if(bfindlast)
  1812. {
  1813. return nlasttid;
  1814. }
  1815. else
  1816. {
  1817. std::cout<<"can't find lane."<<std::endl;
  1818. return 0;
  1819. }
  1820. //Use Last
  1821. }
  1822. }
  1823. return 0;
  1824. int k;
  1825. bool bFind = false;
  1826. while(bFind == false)
  1827. {
  1828. for(k=0;k<nlanecount;k++)
  1829. {
  1830. Lane * pLane = pLaneSection->GetLane(k);
  1831. if((nlane == pLane->GetId())&&(strncmp(pLane->GetType().data(),"driving",255) == 0))
  1832. {
  1833. bFind = true;
  1834. mainselindex = k;
  1835. break;
  1836. }
  1837. }
  1838. if(bFind)continue;
  1839. if(nlr == 1)nlane--;
  1840. else nlane++;
  1841. if(nlane == 0)
  1842. {
  1843. std::cout<<" Fail. can't find lane"<<std::endl;
  1844. break;
  1845. }
  1846. }
  1847. return nlane;
  1848. }
  1849. void checktrace(std::vector<PlanPoint> & xPlan)
  1850. {
  1851. int i;
  1852. int nsize = xPlan.size();
  1853. for(i=1;i<nsize;i++)
  1854. {
  1855. 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));
  1856. if(dis > 0.3)
  1857. {
  1858. double hdg = CalcHdg(QPointF(xPlan.at(i-1).x,xPlan.at(i-1).y),QPointF(xPlan.at(i).x,xPlan.at(i).y));
  1859. int ncount = dis/0.1;
  1860. int j;
  1861. for(j=1;j<ncount;j++)
  1862. {
  1863. double x, y;
  1864. PlanPoint pp;
  1865. pp.x = xPlan.at(i-1).x + j*0.1 *cos(hdg);
  1866. pp.y = xPlan.at(i-1).y + j*0.1 *sin(hdg);
  1867. pp.hdg = hdg;
  1868. xPlan.insert(xPlan.begin()+i+j-1,pp);
  1869. }
  1870. qDebug("dis is %f",dis);
  1871. }
  1872. }
  1873. }
  1874. #include <QFile>
  1875. /**
  1876. * @brief MakePlan 全局路径规划
  1877. * @param pxd 有向图
  1878. * @param pxodr OpenDrive地图
  1879. * @param x_now 当前x坐标
  1880. * @param y_now 当前y坐标
  1881. * @param head 当前航向
  1882. * @param x_obj 目标点x坐标
  1883. * @param y_obj 目标点y坐标
  1884. * @param obj_dis 目标点到路径的距离
  1885. * @param srcnearthresh 当前点离最近路径的阈值,如果不在这个范围,寻找失败
  1886. * @param dstnearthresh 目标点离最近路径的阈值,如果不在这个范围,寻找失败
  1887. * @param nlanesel 车道偏好,1为内车道,数值越大越偏外,如果数值不满足,会选择最靠外的。
  1888. * @param xPlan 返回的轨迹点
  1889. * @return 0 成功 <0 失败
  1890. */
  1891. int MakePlan(xodrdijkstra * pxd,OpenDrive * pxodr,const double x_now,const double y_now,const double head,
  1892. const double x_obj,const double y_obj,const double & obj_dis,
  1893. const double srcnearthresh,const double dstnearthresh,
  1894. const int nlanesel,std::vector<PlanPoint> & xPlan)
  1895. {
  1896. double s;double nearx;
  1897. double neary;double nearhead;
  1898. Road * pRoad;GeometryBlock * pgeob;
  1899. // int nfind = GetNearPoint(x_now,y_now,pxodr,&pRoad,&pgeob,s,nearx,neary,nearhead,srcnearthresh);
  1900. int nfind = GetNearPointWithHead(x_now,y_now,head,pxodr,&pRoad,&pgeob,s,nearx,neary,nearhead,srcnearthresh);
  1901. if(nfind < 0)return -1;
  1902. double s_obj;double nearx_obj;
  1903. double neary_obj;double nearhead_obj;
  1904. Road * pRoad_obj;GeometryBlock * pgeob_obj;
  1905. int nfind_obj = GetNearPoint(x_obj,y_obj,pxodr,&pRoad_obj,&pgeob_obj,s_obj,nearx_obj,neary_obj,
  1906. nearhead_obj,dstnearthresh);
  1907. if(nfind_obj < 0)return -2;
  1908. //计算终点在道路的左侧还是右侧
  1909. int lr_end = 2;
  1910. double hdg_end;
  1911. hdg_end = CalcHdg(QPointF(nearx_obj,neary_obj),QPointF(x_obj,y_obj));
  1912. double hdgdiff = nearhead_obj - hdg_end;
  1913. while(hdgdiff<0)hdgdiff= hdgdiff + 2.0*M_PI;
  1914. while(hdgdiff >= 2.0*M_PI)hdgdiff = hdgdiff- 2.0*M_PI;
  1915. if(hdgdiff<= M_PI)
  1916. {
  1917. lr_end = 2;
  1918. }
  1919. else
  1920. {
  1921. lr_end = 1;
  1922. }
  1923. if((pRoad_obj->GetLaneSection(0)->GetLeftLaneCount()<1)&&(lr_end == 1))
  1924. {
  1925. lr_end = 2;
  1926. }
  1927. if((pRoad_obj->GetLaneSection(0)->GetRightLaneCount()<1)&&(lr_end == 2))
  1928. {
  1929. lr_end = 2;
  1930. }
  1931. int lr_start = SelectRoadLeftRight(pRoad,head,nearhead);
  1932. bool bNeedDikstra = true;
  1933. if((atoi(pRoad->GetRoadId().data()) == atoi(pRoad_obj->GetRoadId().data()))&&(lr_start == lr_end))
  1934. {
  1935. std::vector<PlanPoint> xvPP = GetPoint(pRoad);
  1936. int nindexstart = indexinroadpoint(xvPP,nearx,neary);
  1937. int nindexend = indexinroadpoint(xvPP,nearx_obj,neary_obj);
  1938. int nlane = getlanesel(nlanesel,pRoad->GetLaneSection(0),lr_start);
  1939. if((nindexend >nindexstart)&&(lr_start == 2))
  1940. {
  1941. bNeedDikstra = false;
  1942. }
  1943. if((nindexend <nindexstart)&&(lr_start == 1))
  1944. {
  1945. bNeedDikstra = false;
  1946. }
  1947. if(bNeedDikstra == false)
  1948. {
  1949. std::vector<iv::lanewidthabcd> xvectorLWA = GetLaneWidthABCD(pRoad);
  1950. std::vector<int> xvectorindex1;
  1951. xvectorindex1 = GetLWIndex(xvectorLWA,nlane);
  1952. double foff = getoff(pRoad,nlane);
  1953. foff = foff + 0.0;
  1954. std::vector<PlanPoint> xvectorPP;
  1955. int i = nindexstart;
  1956. while(i!=nindexend)
  1957. {
  1958. if(lr_start == 2)
  1959. {
  1960. PlanPoint pp = xvPP.at(i);
  1961. foff = getoff(nlane,pp.mS,xvectorLWA,xvectorindex1);
  1962. pp.x = pp.x + foff *cos(pp.hdg + M_PI/2.0);
  1963. pp.y = pp.y + foff *sin(pp.hdg + M_PI/2.0);
  1964. pp.mWidth = getwidth(pRoad,nlane,xvectorLWA,pp.mS);
  1965. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1966. pp.lanmp = 0;
  1967. pp.mfDisToRoadLeft = foff *(-1.0);
  1968. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane,pp.mS);
  1969. GetLaneOriTotal(pRoad,nlane,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1970. xvectorPP.push_back(pp);
  1971. i++;
  1972. }
  1973. else
  1974. {
  1975. PlanPoint pp = xvPP.at(i);
  1976. foff = getoff(nlane,pp.mS,xvectorLWA,xvectorindex1);
  1977. pp.x = pp.x + foff *cos(pp.hdg + M_PI/2.0);
  1978. pp.y = pp.y + foff *sin(pp.hdg + M_PI/2.0);
  1979. pp.hdg = pp.hdg + M_PI;
  1980. pp.mWidth = getwidth(pRoad,nlane,xvectorLWA,pp.mS);
  1981. pp.mfDisToLaneLeft = pp.mWidth/2.0;
  1982. pp.lanmp = 0;
  1983. pp.mfDisToRoadLeft = foff;
  1984. pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane,pp.mS);
  1985. GetLaneOriTotal(pRoad,nlane,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
  1986. xvectorPP.push_back(pp);
  1987. i--;
  1988. }
  1989. }
  1990. xPlan = xvectorPP;
  1991. }
  1992. }
  1993. if(bNeedDikstra)
  1994. {
  1995. std::vector<int> xpath = pxd->getpath(atoi(pRoad->GetRoadId().data()),lr_start,atoi(pRoad_obj->GetRoadId().data()),lr_end);
  1996. std::vector<pathsection> xpathsection = pxd->getgpspoint(atoi(pRoad->GetRoadId().data()),lr_start,atoi(pRoad_obj->GetRoadId().data()),lr_end,xpath,nlanesel);
  1997. std::vector<PlanPoint> xvectorPP = GetPlanPoint(xpathsection,pRoad,pgeob,pRoad_obj,pgeob_obj,x_now,y_now,
  1998. head,nearx,neary,nearhead,nearx_obj,neary_obj);
  1999. xPlan = xvectorPP;
  2000. }
  2001. int i;
  2002. // QFile xFile;
  2003. // xFile.setFileName("/home/yuchuli/tempgps.txt");
  2004. // xFile.open(QIODevice::ReadWrite);
  2005. // for(i<0;i<xPlan.size();i++)
  2006. // {
  2007. // char strout[1000];
  2008. // snprintf(strout,1000,"%d %f %f %d %d %d %f \n",i,xPlan[i].mfDisToLaneLeft,
  2009. // xPlan[i].mfDisToRoadLeft,xPlan[i].mnLaneori,xPlan[i].mnLaneTotal,
  2010. // xPlan[i].lanmp,xPlan[i].mWidth);
  2011. // xFile.write(strout,strnlen(strout,1000));
  2012. // }
  2013. // xFile.close();
  2014. checktrace(xPlan);
  2015. // std::cout<<"pp size is "<<xvectorPP.size()<<std::endl;
  2016. return 0;
  2017. if(nfind_obj < 0)return -2;
  2018. if(pRoad != pRoad_obj)return -3; //temp,simple plan
  2019. if(pgeob != pgeob_obj)return -4; //temp,simple geo
  2020. if(!pgeob->CheckIfLine())return -5; //temp,only line plan;
  2021. int nlane = nlanesel;
  2022. if(nlane <= 0 )nlane = 1;
  2023. if(nlane >= pRoad->GetLaneSection(0)->GetLaneCount())
  2024. {
  2025. nlane = pRoad->GetLaneSection(0)->GetLaneCount()-1;
  2026. }
  2027. double bianxiandis = 0;
  2028. double bianxiandis_obj = 0;
  2029. double park_x,park_y;//Park point
  2030. bianxiandis = pRoad->GetLaneSection(0)->GetLane(1)->GetWidthValue(1)/2.0;
  2031. // int i = 1;
  2032. for(i=1;i<nlane;i++)
  2033. {
  2034. bianxiandis = bianxiandis + pRoad->GetLaneSection(0)->GetLane(i)->GetWidthValue(1)/2.0
  2035. +pRoad->GetLaneSection(0)->GetLane(i+1)->GetWidthValue(1)/2.0;
  2036. }
  2037. double bianxianx1 = bianxiandis;
  2038. bianxiandis = fabs(s - bianxiandis);
  2039. bianxiandis_obj = 0;
  2040. int ag = pRoad->GetLaneSection(0)->GetLaneCount();
  2041. for(i=(nlane +1);i<pRoad->GetLaneSection(0)->GetLaneCount();i++)
  2042. {
  2043. bianxiandis_obj = bianxiandis_obj
  2044. +pRoad->GetLaneSection(0)->GetLane(i-1)->GetWidthValue(1)/2.0
  2045. +pRoad->GetLaneSection(0)->GetLane(i)->GetWidthValue(1)/2.0;
  2046. }
  2047. // double x_objreal = nearx_obj + bianxiandis_obj * cos(nearhead_obj - M_PI/2.0);
  2048. // park_x = nearx_obj + (bianxiandis_obj +bianxianx1 + pRoad->GetLaneSection(0)->GetLane(1)->GetWidthValue(0)/2.0)*cos(nearhead_obj -M_PI/2.0);
  2049. // park_y = neary_obj + (bianxiandis_obj +bianxianx1+ pRoad->GetLaneSection(0)->GetLane(1)->GetWidthValue(0)/2.0)*sin(nearhead_obj -M_PI/2.0);
  2050. park_x = nearx_obj + (bianxiandis_obj +bianxianx1 )*cos(nearhead_obj -M_PI/2.0);
  2051. park_y = neary_obj + (bianxiandis_obj +bianxianx1 )*sin(nearhead_obj -M_PI/2.0);
  2052. const double bianxian_ang = 0.2;
  2053. double src_len,dst_len;
  2054. src_len = bianxiandis/atan(bianxian_ang);
  2055. dst_len = bianxiandis_obj/atan(bianxian_ang);
  2056. double xl1,yl1,xl2,yl2;
  2057. xl1 = nearx + src_len * cos(nearhead);
  2058. yl1 = neary + src_len * sin(nearhead);
  2059. xl2 = nearx_obj - dst_len * cos(nearhead_obj);
  2060. yl2 = neary_obj - dst_len * sin(nearhead_obj);
  2061. xl1 = xl1 + bianxianx1 * cos(nearhead - M_PI/2.0);
  2062. yl1 = yl1 + bianxianx1 * sin(nearhead - M_PI/2.0);
  2063. xl2 = xl2 + bianxianx1 * cos(nearhead_obj - M_PI/2.0);
  2064. yl2 = yl2 + bianxianx1 * sin(nearhead_obj - M_PI/2.0);
  2065. double q0[3],q1[3];
  2066. gTempPP.clear();
  2067. q0[0] = x_now;q0[1] = y_now; q0[2] = head;
  2068. q1[0] = xl1;q1[1] =yl1;q1[2] = nearhead;
  2069. int indexp = 0;
  2070. double turning_radius = 15.0;
  2071. double speedvalue = 3;
  2072. DubinsPath path;
  2073. dubins_shortest_path( &path, q0, q1, turning_radius);
  2074. dubins_path_sample_many( &path, 0.1, getPoint, &speedvalue);
  2075. for(i=indexp;i<gTempPP.size();i++)gTempPP.at(i).lanmp = 1;
  2076. indexp = gTempPP.size();
  2077. if(pRoad->GetLaneSection(0)->GetLane(nlane)->GetLaneSpeedCount()>1)
  2078. speedvalue = pRoad->GetLaneSection(0)->GetLane(nlane)->GetLaneSpeed(1)->GetMax();
  2079. else speedvalue = 10.0;
  2080. memcpy(q0,q1,3*sizeof(double));
  2081. q1[0]=xl2; q1[1]=yl2; q1[2]=nearhead;
  2082. dubins_shortest_path( &path, q0, q1, turning_radius);
  2083. dubins_path_sample_many( &path, 0.1, getPoint, &speedvalue);
  2084. for(i=indexp;i<gTempPP.size();i++)gTempPP.at(i).lanmp = 0;
  2085. indexp = gTempPP.size();
  2086. double vx = 3.0;
  2087. for(i= (gTempPP.size() -1);i>0;i--)
  2088. {
  2089. gTempPP.at(i).speed = vx;
  2090. vx = vx + 0.03;
  2091. gTempPP.at(i).lanmp = -1;
  2092. if(vx > speedvalue)break;
  2093. }
  2094. speedvalue = 3.0;
  2095. memcpy(q0,q1,3*sizeof(double));
  2096. q1[0]=park_x; q1[1]=park_y; q1[2]=nearhead_obj;
  2097. dubins_shortest_path( &path, q0, q1, turning_radius);
  2098. dubins_path_sample_many( &path, 0.1, getPoint, &speedvalue);
  2099. for(i=indexp;i<gTempPP.size();i++)gTempPP.at(i).lanmp = -1;
  2100. indexp = gTempPP.size();
  2101. double parkx_ext = park_x + 30 * cos(nearhead);
  2102. double parky_ext = park_y + 30 * sin(nearhead);
  2103. speedvalue = 0.0;
  2104. memcpy(q0,q1,3*sizeof(double));
  2105. q1[0]=parkx_ext; q1[1]=parky_ext; q1[2]=nearhead;
  2106. dubins_shortest_path( &path, q0, q1, turning_radius);
  2107. dubins_path_sample_many( &path, 0.1, getPoint, &speedvalue);
  2108. for(i=indexp;i<gTempPP.size();i++)gTempPP.at(i).lanmp = 0;
  2109. indexp = gTempPP.size();
  2110. for(i=0;i<gTempPP.size();i++)
  2111. {
  2112. xPlan.push_back(gTempPP.at(i));
  2113. }
  2114. return 0;
  2115. PlanPoint pp;
  2116. double hdgsrc,hdgdst;
  2117. double ldis1 = sqrt(pow(xl1 -x_now,2) + pow(yl1 -y_now,2) );
  2118. if(ldis1 > 0)
  2119. {
  2120. hdgsrc = asin((yl1-y_now)/ldis1);
  2121. if(xl1 < x_now)hdgsrc = M_PI - hdgsrc;
  2122. if(hdgsrc < 0)hdgsrc = hdgsrc + 2.0 * M_PI;
  2123. }
  2124. double ldis2 = sqrt(pow(park_x-xl2,2)+pow(park_y-yl2,2));
  2125. if(ldis2 > 0)
  2126. {
  2127. hdgdst = asin((park_y - yl2)/ldis2);
  2128. if(park_x < xl2)hdgdst = M_PI - hdgdst;
  2129. if(hdgdst < 0)hdgdst = hdgdst + 2.0*M_PI;
  2130. }
  2131. double xv,yv,speed;
  2132. i = 0;
  2133. double disx = 0.0;
  2134. const double step = 0.1;
  2135. xv = x_now;
  2136. yv = y_now;
  2137. pp.x = xv;pp.y = yv;pp.hdg = hdgsrc;pp.speed= 3.0;pp.lanmp = 1;xPlan.push_back(pp);
  2138. // qDebug("%d %f %f",i,xv,yv);
  2139. if(ldis1 > 0)
  2140. {
  2141. while((disx+step) < ldis1)
  2142. {
  2143. disx = disx + step;
  2144. i++;
  2145. xv = x_now + disx * cos(hdgsrc);
  2146. yv = y_now + disx * sin(hdgsrc);
  2147. pp.x = xv;pp.y = yv;pp.hdg = hdgsrc;pp.speed= 3.0;xPlan.push_back(pp);
  2148. // qDebug("%d %f %f",i,xv,yv);
  2149. }
  2150. }
  2151. i++;
  2152. xv = xl1;yv = yl1;
  2153. // qDebug("1:%d %f %f",i,xv,yv);
  2154. pp.x = xv;pp.y = yv;pp.hdg = hdgsrc;pp.speed= 3.0;pp.lanmp = 0;xPlan.push_back(pp);
  2155. double dis2p = sqrt(pow(xl2-xl1,2) + pow(yl2 -yl1,2));
  2156. disx = 0;
  2157. if(dis2p > 0)
  2158. {
  2159. while((disx+step) < dis2p)
  2160. {
  2161. disx = disx + step;
  2162. i++;
  2163. xv = xl1 + disx * cos(nearhead);
  2164. yv = yl1 + disx * sin(nearhead);
  2165. if(pRoad->GetLaneSection(0)->GetLane(nlane)->GetLaneSpeedCount()>1)
  2166. speed = pRoad->GetLaneSection(0)->GetLane(nlane)->GetLaneSpeed(1)->GetMax();
  2167. else speed = 10.0;
  2168. if((dis2p -disx)<((speed - 3.0)*5)){
  2169. speed = 3.0;
  2170. pp.lanmp = -1;
  2171. }
  2172. else
  2173. {
  2174. pp.lanmp = 0;
  2175. }
  2176. pp.x = xv;pp.y = yv;pp.hdg = nearhead;pp.speed= speed;xPlan.push_back(pp);
  2177. // qDebug("%d %f %f speed is %f",i,xv,yv,speed);
  2178. }
  2179. }
  2180. i++;
  2181. xv = xl2;yv = yl2;
  2182. pp.x = xv;pp.y = yv;pp.hdg = hdgdst;pp.speed= 3.0;pp.lanmp = -1;xPlan.push_back(pp);
  2183. // qDebug("2: %d %f %f",i,xv,yv);
  2184. disx = 0;
  2185. if(ldis2 > 0)
  2186. {
  2187. while((disx+step) < ldis2)
  2188. {
  2189. disx = disx + step;
  2190. i++;
  2191. xv = xl2 + disx * cos(hdgdst);
  2192. yv = yl2 + disx * sin(hdgdst);
  2193. speed = 3.0;
  2194. pp.x = xv;pp.y = yv;pp.hdg = hdgdst;pp.speed= 3.0;pp.lanmp = -1;xPlan.push_back(pp);
  2195. // qDebug("%d %f %f",i,xv,yv);
  2196. }
  2197. }
  2198. i++;
  2199. xv = park_x;yv = park_y;
  2200. pp.x = xv;pp.y = yv;pp.hdg = nearhead_obj;pp.speed= 0.0;pp.lanmp = 0;xPlan.push_back(pp);
  2201. // qDebug("obj: %d %f %f",i,xv,yv);
  2202. disx = 0;
  2203. while((disx+step) < 30)
  2204. {
  2205. disx = disx + step;
  2206. i++;
  2207. xv = park_x + disx * cos(nearhead);
  2208. yv = park_y + disx * sin(nearhead);
  2209. speed = 0.0;
  2210. pp.x = xv;pp.y = yv;pp.hdg = nearhead_obj;pp.speed= speed;pp.lanmp = 0;xPlan.push_back(pp);
  2211. // qDebug("%d %f %f",i,xv,yv);
  2212. }
  2213. }