123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262226322642265226622672268226922702271227222732274227522762277227822792280228122822283228422852286228722882289229022912292229322942295229622972298229923002301230223032304230523062307230823092310231123122313231423152316231723182319232023212322232323242325232623272328232923302331233223332334233523362337233823392340234123422343234423452346234723482349235023512352235323542355235623572358235923602361236223632364236523662367236823692370237123722373237423752376237723782379238023812382238323842385238623872388238923902391239223932394239523962397239823992400240124022403240424052406240724082409241024112412241324142415241624172418241924202421242224232424242524262427242824292430243124322433243424352436243724382439244024412442244324442445244624472448244924502451245224532454245524562457245824592460246124622463246424652466246724682469247024712472247324742475247624772478247924802481248224832484248524862487248824892490249124922493249424952496249724982499250025012502250325042505250625072508250925102511251225132514251525162517251825192520252125222523252425252526252725282529253025312532253325342535253625372538253925402541254225432544254525462547254825492550255125522553255425552556255725582559256025612562256325642565256625672568256925702571257225732574257525762577257825792580258125822583258425852586258725882589259025912592259325942595259625972598259926002601260226032604260526062607260826092610261126122613261426152616261726182619262026212622262326242625262626272628262926302631263226332634263526362637263826392640264126422643264426452646264726482649265026512652265326542655265626572658265926602661266226632664266526662667266826692670267126722673267426752676267726782679268026812682268326842685268626872688268926902691269226932694269526962697269826992700270127022703270427052706270727082709271027112712271327142715271627172718271927202721272227232724272527262727272827292730273127322733273427352736273727382739274027412742274327442745274627472748274927502751275227532754275527562757275827592760276127622763276427652766276727682769277027712772277327742775277627772778277927802781278227832784278527862787278827892790279127922793279427952796279727982799280028012802280328042805280628072808280928102811281228132814281528162817281828192820282128222823282428252826282728282829283028312832283328342835283628372838283928402841284228432844284528462847284828492850285128522853285428552856285728582859286028612862286328642865286628672868286928702871287228732874287528762877287828792880288128822883288428852886288728882889289028912892289328942895289628972898289929002901290229032904290529062907290829092910291129122913291429152916291729182919292029212922292329242925292629272928292929302931293229332934293529362937293829392940294129422943294429452946294729482949295029512952295329542955295629572958295929602961296229632964296529662967296829692970297129722973297429752976297729782979298029812982298329842985298629872988298929902991299229932994299529962997299829993000300130023003300430053006300730083009301030113012301330143015301630173018301930203021302230233024302530263027302830293030303130323033303430353036303730383039304030413042304330443045304630473048304930503051305230533054305530563057305830593060306130623063306430653066306730683069307030713072307330743075307630773078307930803081308230833084308530863087308830893090309130923093309430953096309730983099310031013102310331043105310631073108310931103111 |
- #include "globalplan.h"
- #include "limits"
- #include <iostream>
- #include <Eigen/Dense>
- #include <Eigen/Cholesky>
- #include <Eigen/LU>
- #include <Eigen/QR>
- #include <Eigen/SVD>
- #include <QDebug>
- #include <QPointF>
- using namespace Eigen;
- extern "C"
- {
- #include "dubins.h"
- }
- static void AddSignalMark(Road * pRoad, int nlane,std::vector<PlanPoint> & xvectorPP);
- /**
- * @brief GetLineDis 获得点到直线Geometry的距离。
- * @param pline
- * @param x
- * @param y
- * @param nearx
- * @param neary
- * @param nearhead
- * @return
- */
- static double GetLineDis(GeometryLine * pline,const double x,const double y,double & nearx,
- double & neary,double & nearhead)
- {
- double fRtn = 1000.0;
- double a1,a2,a3,a4,b1,b2;
- double ratio = pline->GetHdg();
- while(ratio >= 2.0* M_PI)ratio = ratio-2.0*M_PI;
- while(ratio<0)ratio = ratio+2.0*M_PI;
- double dis1,dis2,dis3;
- double x1,x2,x3,y1,y2,y3;
- x1 = pline->GetX();y1=pline->GetY();
- if((ratio == 0)||(ratio == M_PI))
- {
- a1 = 0;a4=0;
- a2 = 1;b1= pline->GetY();
- a3 = 1;b2= x;
- }
- else
- {
- if((ratio == 0.5*M_PI)||(ratio == 1.5*M_PI))
- {
- a2=0;a3=0;
- a1=1,b1=pline->GetX();
- a4 = 1;b2 = y;
- }
- else
- {
- a1 = tan(ratio) *(-1.0);
- a2 = 1;
- a3 = tan(ratio+M_PI/2.0)*(-1.0);
- a4 = 1;
- b1 = a1*pline->GetX() + a2 * pline->GetY();
- b2 = a3*x+a4*y;
- }
- }
- y2 = y1 + pline->GetLength() * sin(ratio);
- x2 = x1 + pline->GetLength() * cos(ratio);
- Eigen::Matrix2d A;
- A<<a1,a2,
- a3,a4;
- Eigen::Vector2d B(b1,b2);
- Eigen::Vector2d opoint = A.lu().solve(B);
- // std::cout<<opoint<<std::endl;
- x3 = opoint(0);
- y3 = opoint(1);
- dis1 = sqrt(pow(x1-x,2)+pow(y1-y,2));
- dis2 = sqrt(pow(x2-x,2)+pow(y2-y,2));
- dis3 = sqrt(pow(x3-x,2)+pow(y3-y,2));
- // std::cout<<" dis 1 is "<<dis1<<std::endl;
- // std::cout<<" dis 2 is "<<dis2<<std::endl;
- // std::cout<<" dis 3 is "<<dis3<<std::endl;
- if((dis1>pline->GetLength())||(dis2>pline->GetLength())) //Outoff line
- {
- // std::cout<<" out line"<<std::endl;
- if(dis1<dis2)
- {
- fRtn = dis1;
- nearx = x1;neary=y1;nearhead = pline->GetHdg();
- }
- else
- {
- fRtn = dis2;
- nearx = x2;neary=y2;nearhead = pline->GetHdg();
- }
- }
- else
- {
- fRtn = dis3;
- nearx = x3;neary=y3;nearhead = pline->GetHdg();
- }
- // std::cout<<"dis is "<<fRtn<<" x is "<<nearx<<" y is "<<neary<<" head is "<<nearhead<<std::endl;
- return fRtn;
- }
- static int getcirclecrosspoint(QPointF startPos, QPointF endPos, QPointF agvPos, double R,QPointF & point1,QPointF & point2 )
- {
- double m=0;
- double k;
- double b;
- //计算分子
- m=startPos.x()-endPos.x();
- //求直线的方程
- if(0==m)
- {
- k=100000;
- b=startPos.y()-k*startPos.x();
- }
- else
- {
- k=(endPos.y()-startPos.y())/(endPos.x()-startPos.x());
- b=startPos.y()-k*startPos.x();
- }
- // qDebug()<<k<<b;
- double temp = fabs(k*agvPos.x()-agvPos.y()+b)/sqrt(k*k+b*b);
- //求直线与圆的交点 前提是圆需要与直线有交点
- if(fabs(k*agvPos.x()-agvPos.y()+b)/sqrt(k*k+b*b)<R)
- {
- 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));
- 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));
- point1.setY(k*point1.x()+b);
- point2.setY(k*point2.x()+b);
- return 0;
- }
- return -1;
- }
- /**
- * @brief CalcHdg
- * 计算点0到点1的航向
- * @param p0 Point 0
- * @param p1 Point 1
- **/
- static double CalcHdg(QPointF p0, QPointF p1)
- {
- double x0,y0,x1,y1;
- x0 = p0.x();
- y0 = p0.y();
- x1 = p1.x();
- y1 = p1.y();
- if(x0 == x1)
- {
- if(y0 < y1)
- {
- return M_PI/2.0;
- }
- else
- return M_PI*3.0/2.0;
- }
- double ratio = (y1-y0)/(x1-x0);
- double hdg = atan(ratio);
- if(ratio > 0)
- {
- if(y1 > y0)
- {
- }
- else
- {
- hdg = hdg + M_PI;
- }
- }
- else
- {
- if(y1 > y0)
- {
- hdg = hdg + M_PI;
- }
- else
- {
- hdg = hdg + 2.0*M_PI;
- }
- }
- return hdg;
- }
- static bool pointinarc(GeometryArc * parc,QPointF poingarc,QPointF point1)
- {
- double hdg = CalcHdg(poingarc,point1);
- if(parc->GetCurvature() >0)hdg = hdg + M_PI/2.0;
- else hdg = hdg - M_PI/2.0;
- if(hdg >= 2.0*M_PI)hdg = hdg - 2.0*M_PI;
- if(hdg < 0)hdg = hdg + 2.0*M_PI;
- double hdgrange = parc->GetLength()/(1.0/parc->GetCurvature());
- double hdgdiff = hdg - parc->GetHdg();
- if(hdgrange >= 0 )
- {
- if(hdgdiff < 0)hdgdiff = hdgdiff + M_PI*2.0;
- }
- else
- {
- if(hdgdiff > 0)hdgdiff = hdgdiff - M_PI*2.0;
- }
- if(fabs(hdgdiff ) < fabs(hdgrange))return true;
- return false;
- }
- static inline double calcpointdis(QPointF p1,QPointF p2)
- {
- return sqrt(pow(p1.x()-p2.x(),2)+pow(p1.y()-p2.y(),2));
- }
- /**
- * @brief GetArcDis
- * 计算点到圆弧的最短距离,首先用点和圆弧中心点的直线与圆的交点,计算点到交点的距离,如果交点在圆弧上,则最短距离是交点之一,否则计算点到圆弧两个端点的距离。
- * @param parc pointer to a arc geomery
- * @param x current x
- * @param y current y
- * @param nearx near x
- * @param neary near y
- * @param nearhead nearhead
- **/
- static double GetArcDis(GeometryArc * parc,double x,double y,double & nearx,
- double & neary,double & nearhead)
- {
- // double fRtn = 1000.0;
- if(parc->GetCurvature() == 0.0)return 1000.0;
- double R = fabs(1.0/parc->GetCurvature());
- // if(parc->GetX() == 4.8213842690322309e+01)
- // {
- // int a = 1;
- // a = 3;
- // }
- // if(parc->GetCurvature() == -0.0000110203)
- // {
- // int a = 1;
- // a = 3;
- // }
- //calculate arc center
- double x_center,y_center;
- if(parc->GetCurvature() > 0)
- {
- x_center = parc->GetX() + R * cos(parc->GetHdg() + M_PI/2.0);
- y_center = parc->GetY() + R * sin(parc->GetHdg()+ M_PI/2.0);
- }
- else
- {
- x_center = parc->GetX() + R * cos(parc->GetHdg() - M_PI/2.0);
- y_center = parc->GetY() + R * sin(parc->GetHdg() - M_PI/2.0);
- }
- double hdgltoa = CalcHdg(QPointF(x,y),QPointF(x_center,y_center));
- QPointF arcpoint;
- arcpoint.setX(x_center);arcpoint.setY(y_center);
- QPointF pointnow;
- pointnow.setX(x);pointnow.setY(y);
- QPointF point1,point2;
- point1.setX(x_center + (R * cos(hdgltoa)));
- point1.setY(y_center + (R * sin(hdgltoa)));
- point2.setX(x_center + (R * cos(hdgltoa + M_PI)));
- point2.setY(y_center + (R * sin(hdgltoa + M_PI)));
- //calculat dis
- bool bp1inarc,bp2inarc;
- bp1inarc =pointinarc(parc,arcpoint,point1);
- bp2inarc =pointinarc(parc,arcpoint,point2);
- double fdis[4];
- fdis[0] = calcpointdis(pointnow,point1);
- fdis[1] = calcpointdis(pointnow,point2);
- fdis[2] = calcpointdis(pointnow,QPointF(parc->GetX(),parc->GetY()));
- QPointF pointend;
- double hdgrange = parc->GetLength()*parc->GetCurvature();
- double hdgend = parc->GetHdg() + hdgrange;
- while(hdgend <0.0)hdgend = hdgend + 2.0 *M_PI;
- while(hdgend >= 2.0*M_PI) hdgend = hdgend -2.0*M_PI;
- if(parc->GetCurvature() >0)
- {
- pointend.setX(arcpoint.x() + R*cos(hdgend -M_PI/2.0 ));
- pointend.setY(arcpoint.y() + R*sin(hdgend -M_PI/2.0) );
- }
- else
- {
- pointend.setX(arcpoint.x() + R*cos(hdgend +M_PI/2.0 ));
- pointend.setY(arcpoint.y() + R*sin(hdgend +M_PI/2.0) );
- }
- fdis[3] = calcpointdis(pointnow,pointend);
- int indexmin = -1;
- double fdismin = 1000000.0;
- if(bp1inarc)
- {
- indexmin = 0;fdismin = fdis[0];
- }
- if(bp2inarc)
- {
- if(indexmin == -1)
- {
- indexmin = 1;fdismin = fdis[1];
- }
- else
- {
- if(fdis[1]<fdismin)
- {
- indexmin = 1;fdismin = fdis[1];
- }
- }
- }
- if(indexmin == -1)
- {
- indexmin = 2;fdismin = fdis[2];
- }
- else
- {
- if(fdis[2]<fdismin)
- {
- indexmin = 2;fdismin = fdis[2];
- }
- }
- if(fdis[3]<fdismin)
- {
- indexmin = 3;fdismin = fdis[3];
- }
- switch (indexmin) {
- case 0:
- nearx = point1.x();
- neary = point1.y();
- if(parc->GetCurvature()<0)
- {
- nearhead = CalcHdg(arcpoint,point1) - M_PI/2.0;
- }
- else
- {
- nearhead = CalcHdg(arcpoint,point1) + M_PI/2.0;
- }
- break;
- case 1:
- nearx = point2.x();
- neary = point2.y();
- if(parc->GetCurvature()<0)
- {
- nearhead = CalcHdg(arcpoint,point2) - M_PI/2.0;
- }
- else
- {
- nearhead = CalcHdg(arcpoint,point2) + M_PI/2.0;
- }
- break;
- case 2:
- nearx = parc->GetX();
- neary = parc->GetY();
- nearhead = parc->GetHdg();
- break;
- case 3:
- nearx = pointend.x();
- neary = pointend.y();
- nearhead = hdgend;
- break;
- default:
- std::cout<<"error in arcdis "<<std::endl;
- break;
- }
- while(nearhead>2.0*M_PI)nearhead = nearhead -2.0*M_PI;
- while(nearhead<0)nearhead = nearhead + 2.0*M_PI;
- return fdismin;
- }
- static double GetSpiralDis(GeometrySpiral * pspiral,double xnow,double ynow,double & nearx,
- double & neary,double & nearhead)
- {
- double x,y,hdg;
- double s = 0.0;
- double fdismin = 100000.0;
- double s0 = pspiral->GetS();
- while(s<pspiral->GetLength())
- {
- pspiral->GetCoords(s0+s,x,y,hdg);
- s = s+0.1;
- double fdis = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
- if(fdis<fdismin)
- {
- fdismin = fdis;
- nearhead = hdg;
- nearx = x;
- neary = y;
- }
- }
- return fdismin;
- }
- /**
- * @brief GetParamPoly3Dis 获得点到贝塞尔曲线的距离。
- * @param parc
- * @param xnow
- * @param ynow
- * @param nearx
- * @param neary
- * @param nearhead
- * @return
- */
- static double GetParamPoly3Dis(GeometryParamPoly3 * parc,double xnow,double ynow,double & nearx,
- double & neary,double & nearhead)
- {
- double s = 0.1;
- double fdismin = 100000.0;
- double xold,yold;
- xold = parc->GetX();
- yold = parc->GetY();
- double fdis = calcpointdis(QPointF(parc->GetX(),parc->GetY()),QPointF(xnow,ynow));
- if(fdis<fdismin)
- {
- fdismin = fdis;
- nearhead = parc->GetHdg();
- nearx = parc->GetX();
- neary = parc->GetY();
- }
- while(s < parc->GetLength())
- {
- double x, y,xtem,ytem;
- xtem = parc->GetuA() + parc->GetuB() * s + parc->GetuC() * s*s + parc->GetuD() * s*s*s;
- ytem = parc->GetvA() + parc->GetvB() * s + parc->GetvC() * s*s + parc->GetvD() * s*s*s;
- x = xtem*cos(parc->GetHdg()) - ytem * sin(parc->GetHdg()) + parc->GetX();
- y = xtem*sin(parc->GetHdg()) + ytem * cos(parc->GetHdg()) + parc->GetY();
- double hdg = CalcHdg(QPointF(xold,yold),QPointF(x,y));
- double fdis = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
- if(fdis<fdismin)
- {
- fdismin = fdis;
- nearhead = hdg;
- nearx = x;
- neary = y;
- }
- xold = x;
- yold = y;
- s = s+ 0.1;
- }
- return fdismin;
- }
- static double GetPoly3Dis(GeometryPoly3 * ppoly,double xnow,double ynow,double & nearx,
- double & neary,double & nearhead)
- {
- double x,y,hdg;
- // double s = 0.0;
- double fdismin = 100000.0;
- // double s0 = ppoly->GetS();
- x = ppoly->GetX();
- y = ppoly->GetY();
- double A,B,C,D;
- A = ppoly->GetA();
- B = ppoly->GetB();
- C = ppoly->GetC();
- D = ppoly->GetD();
- const double steplim = 0.3;
- double du = steplim;
- double u = 0;
- double v = 0;
- double oldx,oldy;
- oldx = x;
- oldy = y;
- double xstart,ystart;
- xstart = x;
- ystart = y;
- double hdgstart = ppoly->GetHdg();
- double flen = 0;
- u = u+du;
- while(flen < ppoly->GetLength())
- {
- double fdis = 0;
- v = A + B*u + C*u*u + D*u*u*u;
- x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
- y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
- fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
- if(fdis>(steplim*2.0))du = du/2.0;
- flen = flen + fdis;
- u = u + du;
- hdg = CalcHdg(QPointF(oldx,oldy),QPointF(x,y));
- double fdisnow = calcpointdis(QPointF(x,y),QPointF(xnow,ynow));
- if(fdisnow<fdismin)
- {
- fdismin = fdisnow;
- nearhead = hdg;
- nearx = x;
- neary = y;
- }
- oldx = x;
- oldy = y;
- }
- return fdismin;
- }
- /**
- * @brief GetNearPoint
- * 计算点到圆弧的最短距离,首先用点和圆弧中心点的直线与圆的交点,计算点到交点的距离,如果交点在圆弧上,则最短距离是交点之一,否则计算点到圆弧两个端点的距离。
- * @param x current x
- * @param y current y
- * @param pxodr OpenDrive
- * @param pObjRoad Road
- * @param pgeo Geometry of road
- * @param nearx near x
- * @param neary near y
- * @param nearhead nearhead
- * @param nearthresh near threshhold
- * @retval if == 0 successfull <0 fail.
- **/
- int GetNearPoint(const double x,const double y,OpenDrive * pxodr,Road ** pObjRoad,GeometryBlock ** pgeo, double & s,double & nearx,
- double & neary,double & nearhead,const double nearthresh,double &froads)
- {
- double dismin = std::numeric_limits<double>::infinity();
- s = dismin;
- int i;
- double frels;
- for(i=0;i<pxodr->GetRoadCount();i++)
- {
- int j;
- Road * proad = pxodr->GetRoad(i);
- double nx,ny,nh;
- for(j=0;j<proad->GetGeometryBlockCount();j++)
- {
- GeometryBlock * pgb = proad->GetGeometryBlock(j);
- double dis;
- RoadGeometry * pg;
- pg = pgb->GetGeometryAt(0);
- switch (pg->GetGeomType()) {
- case 0: //line
- dis = xodrfunc::GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh,frels);
- // dis = GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh);
- break;
- case 1:
- dis = xodrfunc::GetSpiralDis((GeometrySpiral *)pg,x,y,nx,ny,nh,frels);
- break;
- case 2: //arc
- dis = xodrfunc::GetArcDis((GeometryArc *)pg,x,y,nx,ny,nh,frels);
- break;
- case 3:
- dis = xodrfunc::GetPoly3Dis((GeometryPoly3 *)pg,x,y,nx,ny,nh,frels);
- break;
- case 4:
- dis = xodrfunc::GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh,frels);
- break;
- default:
- dis = 100000.0;
- break;
- }
- if(dis < dismin)
- {
- dismin = dis;
- nearx = nx;
- neary = ny;
- nearhead = nh;
- s = dis;
- froads = frels;
- *pObjRoad = proad;
- *pgeo = pgb;
- }
- // if(pgb->CheckIfLine())
- // {
- // GeometryLine * pline = (GeometryLine *)pgb->GetGeometryAt(0);
- // double dis = GetLineDis(pline,x,y,nx,ny,nh);
- // if(dis < dismin)
- // {
- // dismin = dis;
- // nearx = nx;
- // neary = ny;
- // nearhead = nh;
- // s = dis;
- // *pObjRoad = proad;
- // *pgeo = pgb;
- // }
- // }
- // else
- // {
- // GeometryLine * pline1 = (GeometryLine *)pgb->GetGeometryAt(0);
- // double dis = GetLineDis(pline1,x,y,nx,ny,nh);
- // if(dis < dismin)
- // {
- // dismin = dis;
- // nearx = nx;
- // neary = ny;
- // nearhead = nh;
- // s = dis;
- // *pObjRoad = proad;
- // *pgeo = pgb;
- // }
- // GeometryArc * parc = (GeometryArc *)pgb->GetGeometryAt(1);
- // dis = GetArcDis(parc,x,y,nx,ny,nh);
- // if(dis < dismin)
- // {
- // dismin = dis;
- // nearx = nx;
- // neary = ny;
- // nearhead = nh;
- // s = dis;
- // *pObjRoad = proad;
- // *pgeo = pgb;
- // }
- // pline1 = (GeometryLine *)pgb->GetGeometryAt(2);
- // dis = GetLineDis(pline1,x,y,nx,ny,nh);
- // if(dis < dismin)
- // {
- // dismin = dis;
- // nearx = nx;
- // neary = ny;
- // nearhead = nh;
- // s = dis;
- // *pObjRoad = proad;
- // *pgeo = pgb;
- // }
- // }
- }
- }
- if(s > nearthresh)return -1;
- return 0;
- }
- int GetNearPointWithHead(const double x,const double y,const double hdg,OpenDrive * pxodr,Road ** pObjRoad,GeometryBlock ** pgeo, double & s,double & nearx,
- double & neary,double & nearhead,const double nearthresh,double &froads)
- {
- double dismin = std::numeric_limits<double>::infinity();
- s = dismin;
- int i;
- double frels;
- std::vector<Road * > xvectorroad;
- std::vector<double > xvectordismin;
- std::vector<double > xvecotrnearx;
- std::vector<double > xvectorneary;
- std::vector<double > xvectornearhead;
- std::vector<double > xvectors;
- std::vector<GeometryBlock *> xvectorgeob;
- std::vector<double > xvectorfrels;
- double VECTORTHRESH = 5;
- for(i=0;i<pxodr->GetRoadCount();i++)
- {
- int j;
- Road * proad = pxodr->GetRoad(i);
- double nx,ny,nh;
- bool bchange = false;
- double localdismin = std::numeric_limits<double>::infinity();
- double localnearx = 0;
- double localneary = 0;
- double localnearhead = 0;
- double locals = 0;
- double localfrels = 0;
- GeometryBlock * pgeolocal;
- for(j=0;j<proad->GetGeometryBlockCount();j++)
- {
- GeometryBlock * pgb = proad->GetGeometryBlock(j);
- double dis;
- RoadGeometry * pg;
- pg = pgb->GetGeometryAt(0);
- switch (pg->GetGeomType()) {
- case 0: //line
- dis = xodrfunc::GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh,frels);
- break;
- case 1:
- dis = xodrfunc::GetSpiralDis((GeometrySpiral *)pg,x,y,nx,ny,nh,frels);
- break;
- case 2: //arc
- dis = xodrfunc::GetArcDis((GeometryArc *)pg,x,y,nx,ny,nh,frels);
- break;
- case 3:
- dis = xodrfunc::GetPoly3Dis((GeometryPoly3 *)pg,x,y,nx,ny,nh,frels);
- break;
- case 4:
- dis = xodrfunc::GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh,frels);
- break;
- default:
- dis = 100000.0;
- break;
- }
- if(dis < dismin)
- {
- dismin = dis;
- nearx = nx;
- neary = ny;
- nearhead = nh;
- s = dis;
- froads = frels;
- *pObjRoad = proad;
- *pgeo = pgb;
- }
- if((dis<VECTORTHRESH) &&(dis<localdismin))
- {
- localdismin = dis;
- localnearx = nx;
- localneary = ny;
- localnearhead = nh;
- locals = dis;
- localfrels = frels;
- pgeolocal = pgb;
- bchange = true;
- }
- }
- if(bchange)
- {
- xvectorroad.push_back(proad);
- xvecotrnearx.push_back(localnearx);
- xvectorneary.push_back(localneary);
- xvectordismin.push_back(localdismin);
- xvectors.push_back(locals);
- xvectorgeob.push_back(pgeolocal);
- xvectornearhead.push_back(localnearhead);
- xvectorfrels.push_back(localfrels);
- }
- }
- if(s > nearthresh)return -1;
- if((*pObjRoad)->GetLaneSectionCount()>0)
- {
- LaneSection * pLS = (*pObjRoad)->GetLaneSection(0);
- if((*pObjRoad)->GetLaneSection(0)->GetLeftLaneCount()&&(*pObjRoad)->GetLaneSection(0)->GetRightLaneCount()>0)
- {
- return 0;
- }
- else
- {
- double headdiff = hdg - nearhead;
- while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
- while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
- if(((headdiff <M_PI/2.0)||(headdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
- {
- return 0;
- }
- else
- {
- if((headdiff >=M_PI/2.0)&&(headdiff <= M_PI*3.0/2.0)&&(pLS->GetLeftLaneCount()>0))
- {
- return 0;
- }
- else
- {
- bool bHaveSame = false;
- for(i=0;i<xvectorroad.size();i++)
- {
- if(xvectorroad[i]->GetLaneSectionCount()<1)continue;
- bool bNeedFind = false;
- if(bHaveSame == false)bNeedFind = true;
- else
- {
- if(xvectordismin[i]<dismin)bNeedFind = true;
- }
- if(bNeedFind)
- {
- double fdiff = hdg - xvectornearhead[i];
- while(fdiff < 2.0*M_PI) fdiff = fdiff + 2.0*M_PI;
- while(fdiff >= 2.0*M_PI)fdiff = fdiff - 2.0*M_PI;
- bool bUse = false;
- LaneSection * pLS = xvectorroad[i]->GetLaneSection(0);
- if(((fdiff <M_PI/2.0)||(fdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
- {
- bUse = true;
- }
- if(((fdiff >=M_PI/2.0)&&(fdiff <= M_PI*3.0/2.0))&&(pLS->GetLeftLaneCount()>0))
- {
- bUse = true;
- }
- if(bUse)
- {
- dismin = xvectordismin[i];
- nearx = xvecotrnearx[i];
- neary = xvectorneary[i];
- nearhead = xvectornearhead[i];
- s = xvectors[i];
- froads = xvectorfrels[i];
- *pObjRoad = xvectorroad[i];
- *pgeo = xvectorgeob[i];
- bHaveSame = true;
- std::cout<<"change road. "<<std::endl;
- }
- }
- }
- }
- }
- }
- }
- return 0;
- }
- /**
- * @brief SelectRoadLeftRight
- * 选择左侧道路或右侧道路
- * 1.选择角度差小于90度的道路一侧,即同侧道路
- * 2.单行路,选择存在的那一侧道路。
- * @param pRoad 道路
- * @param head1 车的航向或目标点的航向
- * @param head_road 目标点的航向
- * @retval 1 left 2 right
- **/
- static int SelectRoadLeftRight(Road * pRoad,const double head1,const double head_road)
- {
- int nrtn = 2;
- double headdiff = head1 - head_road;
- while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
- while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
- bool bSel = false;
- if((headdiff >=M_PI/2.0)&&(headdiff <= M_PI*3.0/2.0)) //if diff is
- {
- if(pRoad->GetLaneSection(0)->GetLeftLaneCount()>0)
- {
- nrtn = 1;
- bSel = true;
- }
- }
- else
- {
- if(pRoad->GetLaneSection(0)->GetRightLaneCount()>0)
- {
- nrtn = 2;
- bSel = true;
- }
- }
- if(bSel == false)
- {
- if(pRoad->GetLaneSection(0)->GetLeftLaneCount() >0)
- {
- nrtn = 1;
- }
- else
- {
- nrtn = 2;
- }
- }
- return nrtn;
- }
- //static double getlinereldis(GeometryLine * pline,double x,double y)
- //{
- // double x0,y0;
- // x0 = pline->GetX();
- // y0 = pline->GetY();
- // double dis = sqrt(pow(x-x0,2) + pow(y-y0,2));
- // if(dis > pline->GetS())
- // {
- // std::cout<<"getlinereldis exceed s S is "<<pline->GetS()<<" dis is "<<dis<<std::endl;
- // return dis;
- // }
- // return dis;
- //}
- //static double getarcreldis(GeometryArc * parc,double x,double y)
- //{
- // double x0,y0;
- // x0 = parc->GetX();
- // y0 = parc->GetY();
- // double dis = sqrt(pow(x-x0,2) + pow(y-y0,2));
- // double R = fabs(1.0/parc->GetCurvature());
- // double ang = 2.0* asin(dis/(2.0*R));
- // double frtn = ang * R;
- // return frtn;
- //}
- //static double getparampoly3reldis(GeometryParamPoly3 *parc, double xnow, double ynow)
- //{
- // double s = 0.1;
- // double xold,yold;
- // xold = parc->GetX();
- // yold = parc->GetY();
- // while(s < parc->GetLength())
- // {
- // double x, y,xtem,ytem;
- // xtem = parc->GetuA() + parc->GetuB() * s + parc->GetuC() * s*s + parc->GetuD() * s*s*s;
- // ytem = parc->GetvA() + parc->GetvB() * s + parc->GetvC() * s*s + parc->GetvD() * s*s*s;
- // x = xtem*cos(parc->GetHdg()) - ytem * sin(parc->GetHdg()) + parc->GetX();
- // y = xtem*sin(parc->GetHdg()) + ytem * cos(parc->GetHdg()) + parc->GetY();
- // if(sqrt(pow(xnow - x,2) + pow(ynow -y,2))<0.3)
- // {
- // break;
- // }
- // xold = x;
- // yold = y;
- // s = s+ 0.1;
- // }
- // return s;
- //}
- //static double getreldis(RoadGeometry * prg,double x,double y)
- //{
- // int ngeotype = prg->GetGeomType();
- // double frtn = 0;
- // switch (ngeotype) {
- // case 0:
- // frtn = getlinereldis((GeometryLine *)prg,x,y);
- // break;
- // case 1:
- // break;
- // case 2:
- // frtn = getarcreldis((GeometryArc *)prg,x,y);
- // break;
- // case 3:
- // break;
- // case 4:
- // frtn = getparampoly3reldis((GeometryParamPoly3 *)prg,x,y);
- // break;
- // default:
- // break;
- // }
- // return frtn;
- //}
- //static double getposinroad(Road * pRoad,GeometryBlock * pgeob,double x,double y)
- //{
- // RoadGeometry* prg = pgeob->GetGeometryAt(0);
- // double s1 = prg->GetS();
- // double srtn = s1;
- // return s1 + getreldis(prg,x,y);
- //}
- static std::vector<PlanPoint> getlinepoint(GeometryLine * pline,const double fspace = 0.1)
- {
- std::vector<PlanPoint> xvectorPP;
- int i;
- double s = pline->GetLength();
- int nsize = s/fspace;
- if(nsize ==0)nsize = 1;
- for(i=0;i<nsize;i++)
- {
- double x,y;
- x = pline->GetX() + i *fspace * cos(pline->GetHdg());
- y = pline->GetY() + i *fspace * sin(pline->GetHdg());
- PlanPoint pp;
- pp.x = x;
- pp.y = y;
- pp.dis = i*0.1;
- pp.hdg = pline->GetHdg();
- pp.mS = pline->GetS() + i*fspace;
- xvectorPP.push_back(pp);
- }
- return xvectorPP;
- }
- static std::vector<PlanPoint> getarcpoint(GeometryArc * parc,const double fspace = 0.1)
- {
- std::vector<PlanPoint> xvectorPP;
- // double fRtn = 1000.0;
- if(parc->GetCurvature() == 0.0)return xvectorPP;
- double R = fabs(1.0/parc->GetCurvature());
- //calculate arc center
- double x_center = parc->GetX() + (1.0/parc->GetCurvature()) * cos(parc->GetHdg() + M_PI/2.0);
- double y_center = parc->GetY() + (1.0/parc->GetCurvature()) * sin(parc->GetHdg()+ M_PI/2.0);
- double arcdiff = fspace/R;
- int nsize = parc->GetLength()/fspace;
- if(nsize == 0)nsize = 1;
- int i;
- for(i=0;i<nsize;i++)
- {
- double x,y;
- PlanPoint pp;
- if(parc->GetCurvature() > 0)
- {
- x = x_center + R * cos(parc->GetHdg() + i*arcdiff - M_PI/2.0);
- y = y_center + R * sin(parc->GetHdg() + i*arcdiff - M_PI/2.0);
- pp.hdg = parc->GetHdg() + i*arcdiff;
- }
- else
- {
- x = x_center + R * cos(parc->GetHdg() -i*arcdiff + M_PI/2.0);
- y = y_center + R * sin(parc->GetHdg() -i*arcdiff + M_PI/2.0);
- pp.hdg = parc->GetHdg() - i*arcdiff;
- }
- pp.x = x;
- pp.y = y;
- pp.dis = i*0.1;
- pp.mS = parc->GetS() + i*0.1;
- xvectorPP.push_back(pp);
- }
- return xvectorPP;
- }
- static std::vector<PlanPoint> getspiralpoint(GeometrySpiral * pspiral,const double fspace = 0.1)
- {
- double x,y,hdg;
- double s = 0.0;
- double s0 = pspiral->GetS();
- std::vector<PlanPoint> xvectorPP;
- PlanPoint pp;
- while(s<pspiral->GetLength())
- {
- pspiral->GetCoords(s0+s,x,y,hdg);
- pp.x = x;
- pp.y = y;
- pp.hdg = hdg;
- pp.dis = s;
- pp.mS = pspiral->GetS() + s;
- xvectorPP.push_back(pp);
- s = s+fspace;
- }
- return xvectorPP;
- }
- static std::vector<PlanPoint> getpoly3dpoint(GeometryPoly3 * ppoly,const double fspace = 0.1)
- {
- double x,y;
- x = ppoly->GetX();
- y = ppoly->GetY();
- double A,B,C,D;
- A = ppoly->GetA();
- B = ppoly->GetB();
- C = ppoly->GetC();
- D = ppoly->GetD();
- const double steplim = fspace;
- double du = steplim;
- double u = 0;
- double v = 0;
- double oldx,oldy;
- oldx = x;
- oldy = y;
- double xstart,ystart;
- xstart = x;
- ystart = y;
- double hdgstart = ppoly->GetHdg();
- double flen = 0;
- std::vector<PlanPoint> xvectorPP;
- PlanPoint pp;
- pp.x = xstart;
- pp.y = ystart;
- pp.hdg = hdgstart;
- pp.dis = 0;
- pp.mS = ppoly->GetS();
- xvectorPP.push_back(pp);
- u = du;
- while(flen < ppoly->GetLength())
- {
- double fdis = 0;
- v = A + B*u + C*u*u + D*u*u*u;
- x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
- y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
- fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
- double hdg = CalcHdg(QPointF(oldx,oldy),QPointF(x,y));
- oldx = x;
- oldy = y;
- if(fdis>(steplim*2.0))du = du/2.0;
- flen = flen + fdis;
- u = u + du;
- pp.x = x;
- pp.y = y;
- pp.hdg = hdg;
- // s = s+ dt;
- pp.dis = flen;;
- pp.mS = ppoly->GetS() + flen;
- xvectorPP.push_back(pp);
- }
- return xvectorPP;
- }
- static std::vector<PlanPoint> getparampoly3dpoint(GeometryParamPoly3 * parc,const double fspace = 0.1)
- {
- double s = 0.1;
- std::vector<PlanPoint> xvectorPP;
- PlanPoint pp;
- double xold,yold;
- xold = parc->GetX();
- yold = parc->GetY();
- double hdg0 = parc->GetHdg();
- pp.x = xold;
- pp.y = yold;
- pp.hdg = hdg0;
- pp.dis = 0;
- xvectorPP.push_back(pp);
- double dt = 1.0;
- double tcount = parc->GetLength()/0.1;
- if(tcount > 0)
- {
- dt = 1.0/tcount;
- }
- double t;
- s = dt;
- s = 0.1;
- double ua,ub,uc,ud,va,vb,vc,vd;
- ua = parc->GetuA();ub= parc->GetuB();uc= parc->GetuC();ud = parc->GetuD();
- va = parc->GetvA();vb= parc->GetvB();vc= parc->GetvC();vd = parc->GetvD();
- double a = parc->GetS();
- while(s < parc->GetLength())
- // while(s<1.0)
- {
- double len = parc->GetLength();
- double x, y,xtem,ytem;
- // xtem = parc->GetuA() + parc->GetuB() * s * len + parc->GetuC() * s*s *pow(len,2) + parc->GetuD() * s*s*s *pow(len,3);
- // ytem = parc->GetvA() + parc->GetvB() * s* len + parc->GetvC() * s*s *pow(len,2) + parc->GetvD() * s*s*s *pow(len,3);
- xtem = ua + ub * s + uc * s*s + ud * s*s*s ;
- ytem = va + vb * s + vc * s*s + vd * s*s*s ;
- x = xtem*cos(hdg0) - ytem * sin(hdg0) + parc->GetX();
- y = xtem*sin(hdg0) + ytem * cos(hdg0) + parc->GetY();
- // x= xtem + parc->GetX();
- // y = ytem + parc->GetY();
- // x = xtem*cos(parc->GetHdg()) + ytem * sin(parc->GetHdg()) + parc->GetX();
- // y = -xtem*sin(parc->GetHdg()) + ytem * cos(parc->GetHdg()) + parc->GetY();
- double hdg = CalcHdg(QPointF(xold,yold),QPointF(x,y));
- pp.x = x;
- pp.y = y;
- pp.hdg = hdg;
- double disx = sqrt(pow(x-xold,2)+ pow(y-yold,2));
- /* if(disx > 0.1)s = s+ disx;
- else s = s+ 0.5*/;
- s = s+ fspace;
- // s = s+ sqrt(pow(x-xold,2)+ pow(y-yold,2));
- xold = x;
- yold = y;
- // s = s+ dt;
- pp.dis = pp.dis + disx;;
- pp.mS = parc->GetS() + s;
- xvectorPP.push_back(pp);
- // std::cout<<" s is "<<s<<std::endl;
- }
- return xvectorPP;
- }
- std::vector<PlanPoint> GetPoint(pathsection xpath,const double fspace = 0.1)
- {
- Road * pRoad = xpath.mpRoad;
- double s_start,s_end;
- LaneSection * pLS = pRoad->GetLaneSection(xpath.msectionid);
- s_start = pLS->GetS();
- if(xpath.msectionid == (pRoad->GetLaneSectionCount()-1))s_end = pRoad->GetRoadLength();
- else
- {
- s_end = pRoad->GetLaneSection(xpath.msectionid+1)->GetS();
- }
- std::vector<PlanPoint> xvectorPPS;
- double s = 0;
- int i;
- for(i=0;i<pRoad->GetGeometryBlockCount();i++)
- {
- GeometryBlock * pgb = pRoad->GetGeometryBlock(i);
- RoadGeometry * prg = pgb->GetGeometryAt(0);
- std::vector<PlanPoint> xvectorPP;
- if(i<(pRoad->GetGeometryBlockCount() -0))
- {
- if(prg->GetS()>s_end)
- {
- continue;
- }
- if((prg->GetS() + prg->GetLength())<s_start)
- {
- continue;
- }
- }
- double s1 = prg->GetLength();
- switch (prg->GetGeomType()) {
- case 0:
- xvectorPP = getlinepoint((GeometryLine *)prg,fspace);
- break;
- case 1:
- xvectorPP = getspiralpoint((GeometrySpiral *)prg,fspace);
- break;
- case 2:
- xvectorPP = getarcpoint((GeometryArc *)prg,fspace);
- break;
- case 3:
- xvectorPP = getpoly3dpoint((GeometryPoly3 *)prg,fspace);
- break;
- case 4:
- xvectorPP = getparampoly3dpoint((GeometryParamPoly3 *)prg,fspace);
- break;
- default:
- break;
- }
- int j;
- if(prg->GetS()<s_start)
- {
- s1 = prg->GetLength() -(s_start - prg->GetS());
- }
- if((prg->GetS() + prg->GetLength())>s_end)
- {
- s1 = s_end - prg->GetS();
- }
- for(j=0;j<xvectorPP.size();j++)
- {
- PlanPoint pp = xvectorPP.at(j);
- if(((pp.dis+prg->GetS()) >= s_start) &&((pp.dis+prg->GetS()) <= s_end))
- {
- if(s_start > prg->GetS())
- {
- pp.dis = s + pp.dis -(s_start - prg->GetS());
- }
- else
- {
- pp.dis = s+ pp.dis;
- }
- pp.nRoadID = atoi(pRoad->GetRoadId().data());
- xvectorPPS.push_back(pp);
- }
- // if((prg->GetS()>s_start)&&((prg->GetS() + prg->GetLength())<s_end))
- // {
- // pp.dis = s + pp.dis;
- // pp.nRoadID = atoi(pRoad->GetRoadId().data());
- // xvectorPPS.push_back(pp);
- // }
- // else
- // {
- // if(prg->GetS()<s_start)
- // {
- // }
- // else
- // {
- // if(pp.dis<(s_end -prg->GetS()))
- // {
- // pp.dis = s + pp.dis;
- // pp.nRoadID = atoi(pRoad->GetRoadId().data());
- // xvectorPPS.push_back(pp);
- // }
- // }
- // }
- }
- s = s+ s1;
- }
- return xvectorPPS;
- }
- std::vector<PlanPoint> GetPoint(Road * pRoad)
- {
- std::vector<PlanPoint> xvectorPPS;
- double s = 0;
- int i;
- for(i=0;i<pRoad->GetGeometryBlockCount();i++)
- {
- GeometryBlock * pgb = pRoad->GetGeometryBlock(i);
- RoadGeometry * prg = pgb->GetGeometryAt(0);
- std::vector<PlanPoint> xvectorPP;
- double s1 = prg->GetLength();
- switch (prg->GetGeomType()) {
- case 0:
- xvectorPP = getlinepoint((GeometryLine *)prg);
- break;
- case 1:
- xvectorPP = getspiralpoint((GeometrySpiral *)prg);
- break;
- case 2:
- xvectorPP = getarcpoint((GeometryArc *)prg);
- break;
- case 3:
- xvectorPP = getpoly3dpoint((GeometryPoly3 *)prg);
- break;
- case 4:
- xvectorPP = getparampoly3dpoint((GeometryParamPoly3 *)prg);
- break;
- default:
- break;
- }
- int j;
- for(j=0;j<xvectorPP.size();j++)
- {
- PlanPoint pp = xvectorPP.at(j);
- pp.dis = s + pp.dis;
- pp.nRoadID = atoi(pRoad->GetRoadId().data());
- xvectorPPS.push_back(pp);
- }
- s = s+ s1;
- }
- return xvectorPPS;
- }
- int indexinroadpoint(std::vector<PlanPoint> xvectorPP,double x,double y)
- {
- int nrtn = 0;
- int i;
- int dismin = 1000;
- for(i=0;i<xvectorPP.size();i++)
- {
- double dis = sqrt(pow(xvectorPP.at(i).x - x,2) + pow(xvectorPP.at(i).y -y,2));
- if(dis <dismin)
- {
- dismin = dis;
- nrtn = i;
- }
- }
- if(dismin > 10.0)
- {
- std::cout<<"indexinroadpoint near point is error. dis is "<<dismin<<std::endl;
- }
- return nrtn;
- }
- double getwidth(Road * pRoad, int nlane)
- {
- double frtn = 0;
- int i;
- int nlanecount = pRoad->GetLaneSection(0)->GetLaneCount();
- for(i=0;i<nlanecount;i++)
- {
- if(nlane == pRoad->GetLaneSection(0)->GetLane(i)->GetId())
- {
- LaneWidth* pLW = pRoad->GetLaneSection(0)->GetLane(i)->GetLaneWidth(0);
- if(pLW != 0)
- {
- frtn = pRoad->GetLaneSection(0)->GetLane(i)->GetLaneWidth(0)->GetA();
- break;
- }
- }
- }
- return frtn;
- }
- double getoff(Road * pRoad,int nlane)
- {
- double off = getwidth(pRoad,nlane)/2.0;
- if(nlane < 0)off = off * (-1.0);
- // int nlanecount = pRoad->GetLaneSection(0)->GetLaneCount();
- int i;
- if(nlane > 0)
- off = off + getwidth(pRoad,0)/2.0;
- else
- off = off - getwidth(pRoad,0)/2.0;
- if(nlane > 0)
- {
- for(i=1;i<nlane;i++)
- {
- off = off + getwidth(pRoad,i);
- }
- }
- else
- {
- for(i=-1;i>nlane;i--)
- {
- off = off - getwidth(pRoad,i);
- }
- }
- // return 0;
- return off;
- }
- namespace iv {
- struct lanewidthabcd
- {
- int nlane;
- double A;
- double B;
- double C;
- double D;
- };
- }
- double getwidth(Road * pRoad, int nlane,std::vector<iv::lanewidthabcd> xvectorlwa,double s)
- {
- double frtn = 0;
- int i;
- int nlanecount = xvectorlwa.size();
- for(i=0;i<nlanecount;i++)
- {
- if(nlane == xvectorlwa.at(i).nlane)
- {
- iv::lanewidthabcd * plwa = &xvectorlwa.at(i);
- frtn = plwa->A + plwa->B*s + plwa->C *s*s + plwa->D *s*s*s;
- break;
- }
- }
- return frtn;
- }
- std::vector<iv::lanewidthabcd> GetLaneWidthABCD(Road * pRoad)
- {
- std::vector<iv::lanewidthabcd> xvectorlwa;
- if(pRoad->GetLaneSectionCount()<1)return xvectorlwa;
- int i;
- LaneSection * pLS = pRoad->GetLaneSection(0);
- // if(pRoad->GetLaneSectionCount() > 1)
- // {
- // for(i=0;i<(pRoad->GetLaneSectionCount()-1);i++)
- // {
- // if(s>pRoad->GetLaneSection(i+1)->GetS())
- // {
- // pLS = pRoad->GetLaneSection(i+1);
- // }
- // else
- // {
- // break;
- // }
- // }
- // }
- int nlanecount = pLS->GetLaneCount();
- for(i=0;i<nlanecount;i++)
- {
- iv::lanewidthabcd xlwa;
- LaneWidth* pLW = pLS->GetLane(i)->GetLaneWidth(0);
- xlwa.nlane = pLS->GetLane(i)->GetId();
- if(pLW != 0)
- {
- xlwa.A = pLW->GetA();
- xlwa.B = pLW->GetB();
- xlwa.C = pLW->GetC();
- xlwa.D = pLW->GetD();
- }
- else
- {
- xlwa.A = 0;
- xlwa.B = 0;
- xlwa.C = 0;
- xlwa.D = 0;
- }
- // if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
- xvectorlwa.push_back(xlwa); //Calculate Road Width, not driving need add in.
- }
- return xvectorlwa;
- }
- inline double getoff(int nlane,double s,std::vector<iv::lanewidthabcd> xvectorLWA,std::vector<int> xvectorIndex)
- {
- int i;
- double off = 0;
- double a,b,c,d;
- if(xvectorIndex.size() == 0)return off;
- for(i=0;i<(xvectorIndex.size()-1);i++)
- {
- a = xvectorLWA[xvectorIndex[i]].A;
- b = xvectorLWA[xvectorIndex[i]].B;
- c = xvectorLWA[xvectorIndex[i]].C;
- d = xvectorLWA[xvectorIndex[i]].D;
- if(xvectorLWA[xvectorIndex[i]].nlane != 0)
- {
- off = off + a + b*s + c*s*s + d*s*s*s;
- }
- else
- {
- off = off + (a + b*s + c*s*s + d*s*s*s)/2.0;
- }
- }
- i = xvectorIndex.size()-1;
- a = xvectorLWA[xvectorIndex[i]].A;
- b = xvectorLWA[xvectorIndex[i]].B;
- c = xvectorLWA[xvectorIndex[i]].C;
- d = xvectorLWA[xvectorIndex[i]].D;
- off = off + (a + b*s + c*s*s + d*s*s*s)/2.0;
- if(nlane < 0) off = off*(-1.0);
- // std::cout<<"s is "<<s<<std::endl;
- // std::cout<<" off is "<<off<<std::endl;
- return off;
- }
- double GetRoadWidth(std::vector<iv::lanewidthabcd> xvectorLWA,int nlane,double s)
- {
- double fwidth = 0;
- int i;
- double a,b,c,d;
- int nsize = xvectorLWA.size();
- for(i=0;i<nsize;i++)
- {
- if(nlane*(xvectorLWA[i].nlane)>0)
- {
- a = xvectorLWA[i].A;
- b = xvectorLWA[i].B;
- c = xvectorLWA[i].C;
- d = xvectorLWA[i].D;
- fwidth = fwidth + a + b*s +c*s*s + d*s*s*s;
- }
- }
- return fwidth;
- }
- int GetLaneOriTotal(Road * pRoad, int nlane,double s,int & nori, int & ntotal,double & fSpeed)
- {
- if(pRoad->GetLaneSectionCount() < 1)return -1;
- LaneSection * pLS = pRoad->GetLaneSection(0);
- int i;
- if(pRoad->GetLaneSectionCount() > 1)
- {
- for(i=0;i<(pRoad->GetLaneSectionCount()-1);i++)
- {
- if(s>pRoad->GetLaneSection(i+1)->GetS())
- {
- pLS = pRoad->GetLaneSection(i+1);
- }
- else
- {
- break;
- }
- }
- }
- nori = 0;
- ntotal = 0;
- fSpeed = -1; //if -1 no speedlimit for map
- int nlanecount = pLS->GetLaneCount();
- for(i=0;i<nlanecount;i++)
- {
- int nlaneid = pLS->GetLane(i)->GetId();
- if(nlaneid == nlane)
- {
- Lane * pLane = pLS->GetLane(i);
- if(pLane->GetLaneSpeedCount() > 0)
- {
- LaneSpeed * pLSpeed = pLane->GetLaneSpeed(0);
- int j;
- int nspeedcount = pLane->GetLaneSpeedCount();
- for(j=0;j<(nspeedcount -1);j++)
- {
- if((s-pLS->GetS())>=pLane->GetLaneSpeed(j+1)->GetS())
- {
- pLSpeed = pLane->GetLaneSpeed(j+1);
- }
- else
- {
- break;
- }
- }
- if(pLSpeed->GetS()<=(s-pLS->GetS()))fSpeed = pLSpeed->GetMax();
- }
- }
- if(nlane<0)
- {
- if(nlaneid < 0)
- {
- if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
- {
- ntotal++;
- if(nlaneid<nlane)nori++;
- }
- }
- }
- else
- {
- if(nlaneid > 0)
- {
- if(strncmp(pLS->GetLane(i)->GetType().data(),"driving",256) == 0)
- {
- ntotal++;
- if(nlaneid > nlane)nori++;
- }
- }
- }
- }
- return 0;
- }
- std::vector<int> GetLWIndex(std::vector<iv::lanewidthabcd> xvectorLWA,int nlane)
- {
- std::vector<int> xvectorindex;
- int i;
- if(nlane >= 0)
- {
- for(i=0;i<=nlane;i++)
- {
- int j;
- int nsize = xvectorLWA.size();
- for(j=0;j<nsize;j++)
- {
- if(i == xvectorLWA.at(j).nlane )
- {
- xvectorindex.push_back(j);
- break;
- }
- }
- }
- }
- else
- {
- for(i=0;i>=nlane;i--)
- {
- int j;
- int nsize = xvectorLWA.size();
- for(j=0;j<nsize;j++)
- {
- if(i == xvectorLWA.at(j).nlane )
- {
- xvectorindex.push_back(j);
- break;
- }
- }
- }
- }
- return xvectorindex;
- }
- void CalcInLaneAvoid(pathsection xps,std::vector<PlanPoint> & xvectorPP,const double fvehiclewidth,
- const int nchang1,const int nchang2,const int nchangpoint)
- {
- if(xvectorPP.size()<2)return;
- bool bInlaneavoid = false;
- int i;
- if((xps.mbStartToMainChange == false) && (xps.mbMainToEndChange == false))
- {
- if(xps.mpRoad->GetRoadLength()<30)
- {
- double hdgdiff = xvectorPP.at(xvectorPP.size()-1).hdg - xvectorPP.at(0).hdg;
- if(hdgdiff<0)hdgdiff = hdgdiff + 2.0*M_PI;
- if(hdgdiff>(M_PI/3.0)&&(hdgdiff<(5.0*M_PI/3.0)))
- bInlaneavoid = false;
- else
- bInlaneavoid = true;
- }
- else
- {
- bInlaneavoid = true;
- }
- }
- else
- {
- if(xps.mpRoad->GetRoadLength()>100)bInlaneavoid = true;
- }
- if(bInlaneavoid == false)
- {
- int nvpsize = xvectorPP.size();
- for(i=0;i<nvpsize;i++)
- {
- xvectorPP.at(i).bInlaneAvoid = false;
- xvectorPP.at(i).mx_left = xvectorPP.at(i).x;
- xvectorPP.at(i).my_left = xvectorPP.at(i).y;
- xvectorPP.at(i).mx_right = xvectorPP.at(i).x;
- xvectorPP.at(i).my_right = xvectorPP.at(i).y;
- }
- }
- else
- {
- int nvpsize = xvectorPP.size();
- for(i=0;i<nvpsize;i++)xvectorPP.at(i).bInlaneAvoid = true;
- if((xps.mbStartToMainChange == true)||(xps.mbMainToEndChange == true))
- {
- if(xps.mbStartToMainChange == true)
- {
- for(i=(nchang1 - nchangpoint/2);i<(nchang1 + nchangpoint/2);i++)
- {
- if((i>=0)&&(i<nvpsize))
- xvectorPP.at(i).bInlaneAvoid = false;
- }
- }
- if(xps.mbMainToEndChange)
- {
- for(i=(nchang2 - nchangpoint/2);i<(nchang2 + nchangpoint/2);i++)
- {
- if((i>=0)&&(i<nvpsize))
- xvectorPP.at(i).bInlaneAvoid = false;
- }
- }
- }
- for(i=0;i<nvpsize;i++)
- {
- if(xvectorPP.at(i).bInlaneAvoid)
- {
- double foff = xvectorPP.at(i).mfDisToLaneLeft -0.3-fvehiclewidth*0.5; //30cm + 0.5vehcilewidth
- if(foff < 0.3)
- {
- xvectorPP.at(i).bInlaneAvoid = false;
- xvectorPP.at(i).mx_left = xvectorPP.at(i).x;
- xvectorPP.at(i).my_left = xvectorPP.at(i).y;
- xvectorPP.at(i).mx_right = xvectorPP.at(i).x;
- xvectorPP.at(i).my_right = xvectorPP.at(i).y;
- }
- else
- {
- xvectorPP.at(i).mx_left = xvectorPP.at(i).x + foff * cos(xvectorPP.at(i).hdg + M_PI/2.0);
- xvectorPP.at(i).my_left = xvectorPP.at(i).y + foff * sin(xvectorPP.at(i).hdg + M_PI/2.0);
- xvectorPP.at(i).mx_right = xvectorPP.at(i).x + foff * cos(xvectorPP.at(i).hdg - M_PI/2.0);
- xvectorPP.at(i).my_right = xvectorPP.at(i).y + foff * sin(xvectorPP.at(i).hdg - M_PI/2.0);
- }
- }
- }
- }
- }
- double getoff(Road * pRoad,int nlane,const double s)
- {
- int i;
- int nLSCount = pRoad->GetLaneSectionCount();
- double s_section = 0;
- double foff = 0;
- for(i=0;i<nLSCount;i++)
- {
- LaneSection * pLS = pRoad->GetLaneSection(i);
- if(i<(nLSCount -1))
- {
- if(pRoad->GetLaneSection(i+1)->GetS()<s)
- {
- continue;
- }
- }
- s_section = pLS->GetS();
- int nlanecount = pLS->GetLaneCount();
- int j;
- for(j=0;j<nlanecount;j++)
- {
- Lane * pLane = pLS->GetLane(j);
- int k;
- double s_lane = s-s_section;
- if(pLane->GetId() != 0)
- {
- for(k=0;k<pLane->GetLaneWidthCount();k++)
- {
- if(k<(pLane->GetLaneWidthCount()-1))
- {
- if((pLane->GetLaneWidth(k+1)->GetS()+s_section)<s)
- {
- continue;
- }
- }
- s_lane = pLane->GetLaneWidth(k)->GetS();
- break;
- }
- LaneWidth * pLW = pLane->GetLaneWidth(k);
- if(pLW == 0)
- {
- std::cout<<"not find LaneWidth"<<std::endl;
- break;
- }
- double fds = s - s_lane - s_section;
- double fwidth= pLW->GetA() + pLW->GetB() * fds
- +pLW->GetC() * pow(fds,2) + pLW->GetD() * pow(fds,3);
- if(nlane == pLane->GetId())
- {
- foff = foff + fwidth/2.0;
- }
- if((nlane*(pLane->GetId())>0)&&(abs(nlane)>abs(pLane->GetId())))
- {
- foff = foff + fwidth;
- }
- }
- }
- break;
- }
- if(nlane<0)foff = foff*(-1);
- return foff;
- }
- std::vector<PlanPoint> GetLanePoint(pathsection xps,std::vector<PlanPoint> xvPP,const double fvehiclewidth)
- {
- std::vector<PlanPoint> xvectorPP;
- std::vector<iv::lanewidthabcd> xvectorLWA = GetLaneWidthABCD(xps.mpRoad);
- std::vector<int> xvectorindex1,xvectorindex2,xvectorindex3;
- int nchange1,nchange2;
- int nlane1,nlane2,nlane3;
- if(xps.mnStartLaneSel == xps.mnEndLaneSel)
- {
- xps.mainsel = xps.mnStartLaneSel;
- xps.mbStartToMainChange = false;
- xps.mbMainToEndChange = false;
- }
- else
- {
- if(xps.mpRoad->GetRoadLength() < 100)
- {
- xps.mainsel = xps.mnEndLaneSel;
- xps.mbStartToMainChange = true;
- xps.mbMainToEndChange = false;
- }
- }
- double off1,off2,off3;
- if(xps.mnStartLaneSel < 0)
- {
- off1 = getoff(xps.mpRoad,xps.mnStartLaneSel);
- off2 = getoff(xps.mpRoad,xps.mainsel);
- off3 = getoff(xps.mpRoad,xps.mnEndLaneSel);
- xvectorindex1 = GetLWIndex(xvectorLWA,xps.mnStartLaneSel);
- xvectorindex2 = GetLWIndex(xvectorLWA,xps.mainsel);
- xvectorindex3 = GetLWIndex(xvectorLWA,xps.mnEndLaneSel);
- nlane1 = xps.mnStartLaneSel;
- nlane2 = xps.mainsel;
- nlane3 = xps.mnEndLaneSel;
- }
- else
- {
- off3 = getoff(xps.mpRoad,xps.mnStartLaneSel);
- off2 = getoff(xps.mpRoad,xps.mainsel);
- off1 = getoff(xps.mpRoad,xps.mnEndLaneSel);
- xvectorindex3 = GetLWIndex(xvectorLWA,xps.mnStartLaneSel);
- xvectorindex2 = GetLWIndex(xvectorLWA,xps.mainsel);
- xvectorindex1 = GetLWIndex(xvectorLWA,xps.mnEndLaneSel);
- nlane3 = xps.mnStartLaneSel;
- nlane2 = xps.mainsel;
- nlane1 = xps.mnEndLaneSel;
- }
- int nchangepoint = 300;
- if((nchangepoint * 3) > xvPP.size())
- {
- nchangepoint = xvPP.size()/3;
- }
- int nsize = xvPP.size();
- nchange1 = nsize/3;
- if(nchange1>500)nchange1 = 500;
- nchange2 = nsize*2/3;
- if( (nsize-nchange2)>500)nchange2 = nsize-500;
- // if(nsize < 1000)
- // {
- // std::cout<<"GetLanePoint Error. road id is "<<xps.mpRoad->GetRoadId()<<std::endl;
- // return xvectorPP;
- // }
- double x,y;
- int i;
- if(xps.mainsel < 0)
- {
- for(i=0;i<nsize;i++)
- {
- PlanPoint pp = xvPP.at(i);
- // off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
- off1 = getoff(xps.mpRoad,nlane2,pp.mS);
- pp.x = pp.x + off1 *cos(pp.hdg + M_PI/2.0);
- pp.y = pp.y + off1 *sin(pp.hdg + M_PI/2.0);
- pp.nlrchange = 1;
- if(xps.mainsel != xps.secondsel)
- {
- off1 = getoff(xps.mpRoad,xps.secondsel,pp.mS);
- pp.mfSecx = xvPP.at(i).x + off1 *cos(pp.hdg + M_PI/2.0);
- pp.mfSecy = xvPP.at(i).y + off1 *sin(pp.hdg + M_PI/2.0);
- if(xps.mainsel >xps.secondsel)
- {
- pp.nlrchange = 1;
- }
- else
- {
- pp.nlrchange = 2;
- }
- }
- else
- {
- pp.mfSecx = pp.x ;
- pp.mfSecy = pp.y ;
- }
- pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
- pp.mfDisToLaneLeft = pp.mWidth/2.0;
- pp.lanmp = 0;
- pp.mfDisToRoadLeft = off1*(-1);
- pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
- GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- xvectorPP.push_back(pp);
- }
- }
- else
- {
- for(i=0;i<nsize;i++)
- {
- PlanPoint pp = xvPP.at(i);
- // off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
- off1 = getoff(xps.mpRoad,nlane2,pp.mS);
- pp.x = pp.x + off1 *cos(pp.hdg + M_PI/2.0);
- pp.y = pp.y + off1 *sin(pp.hdg + M_PI/2.0);
- pp.nlrchange = 1;
- if(xps.mainsel != xps.secondsel)
- {
- off1 = getoff(xps.mpRoad,xps.secondsel,pp.mS);
- pp.mfSecx = xvPP.at(i).x + off1 *cos(pp.hdg + M_PI/2.0);
- pp.mfSecy = xvPP.at(i).y + off1 *sin(pp.hdg + M_PI/2.0);
- if(xps.mainsel >xps.secondsel)
- {
- pp.nlrchange = 2;
- }
- else
- {
- pp.nlrchange = 1;
- }
- }
- else
- {
- pp.mfSecx = pp.x ;
- pp.mfSecy = pp.y ;
- }
- pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
- pp.mfDisToLaneLeft = pp.mWidth/2.0;
- pp.lanmp = 0;
- pp.mfDisToRoadLeft = off1;
- pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
- GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- xvectorPP.push_back(pp);
- }
- // for(i=0;i<(nchange1- nchangepoint/2);i++)
- // {
- // PlanPoint pp = xvPP.at(i);
- // off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
- // pp.x = pp.x + off1 *cos(pp.hdg + M_PI/2.0);
- // pp.y = pp.y + off1 *sin(pp.hdg + M_PI/2.0);
- // pp.hdg = pp.hdg + M_PI;
- // pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
- // pp.mfDisToLaneLeft = pp.mWidth/2.0;
- // pp.lanmp = 0;
- // pp.mfDisToRoadLeft = off1;
- // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
- // GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // xvectorPP.push_back(pp);
- // }
- // for(i=(nchange1 - nchangepoint/2);i<(nchange1+nchangepoint/2);i++)
- // {
- // PlanPoint pp = xvPP.at(i);
- // off1 = getoff(nlane1,pp.mS,xvectorLWA,xvectorindex1);
- // off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
- // double offx = off1 + (off2 - off1) *(i-nchange1 + nchangepoint/2)/nchangepoint;
- // pp.x = pp.x + offx *cos(pp.hdg + M_PI/2.0);
- // pp.y = pp.y + offx *sin(pp.hdg + M_PI/2.0);
- // pp.hdg = pp.hdg + M_PI;
- // double flanewidth1 = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
- // pp.mfDisToRoadLeft = offx;
- // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane1,pp.mS);
- // if(nlane1 == nlane2)
- // {
- // pp.mWidth = flanewidth1;
- // pp.mfDisToLaneLeft = pp.mWidth/2.0;
- // pp.lanmp = 0;
- // GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // }
- // else
- // {
- // if(nlane1 < nlane2)
- // {
- // pp.lanmp = -1;
- // }
- // else
- // {
- // pp.lanmp = 1;
- // }
- // if(i<nchange1)
- // {
- // pp.mWidth = getwidth(xps.mpRoad,nlane1,xvectorLWA,pp.mS);
- // double fmove = pp.mWidth * (i-(nchange1 - nchangepoint/2))/nchangepoint;
- // if(nlane1<nlane2)pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
- // else pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
- // GetLaneOriTotal(xps.mpRoad,nlane1,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // }
- // else
- // {
- // pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
- // double fmove = pp.mWidth * (nchange1+nchangepoint/2 -i)/nchangepoint;
- // if(nlane1<nlane2)pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
- // else pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
- // GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // }
- // }
- // xvectorPP.push_back(pp);
- // }
- // for(i=(nchange1 + nchangepoint/2);i<(nchange2-nchangepoint/2);i++)
- // {
- // PlanPoint pp = xvPP.at(i);
- // off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
- // pp.x = pp.x + off2 *cos(pp.hdg + M_PI/2.0);
- // pp.y = pp.y + off2 *sin(pp.hdg + M_PI/2.0);
- // pp.hdg = pp.hdg + M_PI;
- // pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
- // pp.mfDisToLaneLeft = pp.mWidth/2.0;
- // pp.lanmp = 0;
- // pp.mfDisToRoadLeft = off2;
- // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane2,pp.mS);
- // GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // xvectorPP.push_back(pp);
- // }
- // for(i=(nchange2 - nchangepoint/2);i<(nchange2+nchangepoint/2);i++)
- // {
- // PlanPoint pp = xvPP.at(i);
- // off2 = getoff(nlane2,pp.mS,xvectorLWA,xvectorindex2);
- // off3 = getoff(nlane3,pp.mS,xvectorLWA,xvectorindex3);
- // double offx = off2 + (off3 - off2) *(i-nchange2 + nchangepoint/2)/nchangepoint;
- // pp.x = pp.x + offx *cos(pp.hdg + M_PI/2.0);
- // pp.y = pp.y + offx *sin(pp.hdg + M_PI/2.0);
- // pp.hdg = pp.hdg + M_PI;
- // double flanewidth1 = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
- // pp.mfDisToRoadLeft = offx;
- // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane2,pp.mS);
- // if(nlane2 == nlane3)
- // {
- // pp.mWidth = flanewidth1;
- // pp.mfDisToLaneLeft = pp.mWidth/2.0;
- // pp.lanmp = 0;
- // GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // }
- // else
- // {
- // if(nlane2 < nlane3)
- // {
- // pp.lanmp = -1;
- // }
- // else
- // {
- // pp.lanmp = 1;
- // }
- // if(i<nchange2)
- // {
- // pp.mWidth = getwidth(xps.mpRoad,nlane2,xvectorLWA,pp.mS);
- // double fmove = pp.mWidth * (i-(nchange2 - nchangepoint/2))/nchangepoint;
- // if(nlane2<nlane3)pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
- // else pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
- // GetLaneOriTotal(xps.mpRoad,nlane2,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // }
- // else
- // {
- // pp.mWidth = getwidth(xps.mpRoad,nlane3,xvectorLWA,pp.mS);
- // double fmove = pp.mWidth * (nchange2+nchangepoint/2 -i)/nchangepoint;
- // if(nlane2<nlane3)pp.mfDisToLaneLeft = pp.mWidth/2.0 + fmove;
- // else pp.mfDisToLaneLeft = pp.mWidth/2.0 - fmove;
- // GetLaneOriTotal(xps.mpRoad,nlane3,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // }
- // }
- // xvectorPP.push_back(pp);
- // }
- // for(i=(nchange2+ nchangepoint/2);i<nsize;i++)
- // {
- // PlanPoint pp = xvPP.at(i);
- // off3 = getoff(nlane3,pp.mS,xvectorLWA,xvectorindex3);
- // pp.x = pp.x + off3 *cos(pp.hdg + M_PI/2.0);
- // pp.y = pp.y + off3 *sin(pp.hdg + M_PI/2.0);
- // pp.hdg = pp.hdg + M_PI;
- // pp.mWidth = getwidth(xps.mpRoad,nlane3,xvectorLWA,pp.mS);
- // pp.mfDisToLaneLeft = pp.mWidth/2.0;
- // pp.lanmp = 0;
- // pp.mfDisToRoadLeft = off3;
- // pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane3,pp.mS);
- // GetLaneOriTotal(xps.mpRoad,nlane3,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- // xvectorPP.push_back(pp);
- // }
- }
- CalcInLaneAvoid(xps,xvectorPP,fvehiclewidth,nchange1,nchange2,nchangepoint);
- if(xps.mnStartLaneSel > 0)
- {
- std::vector<PlanPoint> xvvPP;
- int nvsize = xvectorPP.size();
- for(i=0;i<nvsize;i++)
- {
- xvvPP.push_back(xvectorPP.at(nvsize-1-i));
- }
- AddSignalMark(xps.mpRoad,xps.mainsel,xvvPP);
- return xvvPP;
- }
- // pRoad->GetLaneSection(xps.msectionid)
- AddSignalMark(xps.mpRoad,xps.mainsel,xvectorPP);
- return xvectorPP;
- }
- static void AddSignalMark(Road * pRoad, int nlane,std::vector<PlanPoint> & xvectorPP)
- {
- if(pRoad->GetSignalCount() == 0)return;
- int nsigcount = pRoad->GetSignalCount();
- int i;
- for(i=0;i<nsigcount;i++)
- {
- Signal * pSig = pRoad->GetSignal(i);
- int nfromlane = -100;
- int ntolane = 100;
- signal_laneValidity * pSig_laneValidity = pSig->GetlaneValidity();
- if(pSig_laneValidity != 0)
- {
- nfromlane = pSig_laneValidity->GetfromLane();
- ntolane = pSig_laneValidity->GettoLane();
- }
- if((nlane < 0)&&(nfromlane >= 0))
- {
- continue;
- }
- if((nlane > 0)&&(ntolane<=0))
- {
- continue;
- }
- double s = pSig->Gets();
- double fpos = s/pRoad->GetRoadLength();
- if(nlane > 0)fpos = 1.0 -fpos;
- int npos = fpos *xvectorPP.size();
- if(npos <0)npos = 0;
- if(npos>=xvectorPP.size())npos = xvectorPP.size()-1;
- while(xvectorPP.at(npos).nSignal != -1)
- {
- if(npos > 0)npos--;
- else break;
- }
- while(xvectorPP.at(npos).nSignal != -1)
- {
- if(npos < (xvectorPP.size()-1))npos++;
- else break;
- }
- xvectorPP.at(npos).nSignal = atoi(pSig->Gettype().data());
- }
- }
- static std::vector<PlanPoint> GetPlanPoint(std::vector<pathsection> xpathsection,Road * pRoad,GeometryBlock * pgeob,
- Road * pRoad_obj,GeometryBlock * pgeob_obj,
- const double x_now,const double y_now,const double head,
- double nearx,double neary, double nearhead,
- double nearx_obj,double neary_obj,const double fvehiclewidth,const double flen = 1000)
- {
- std::vector<PlanPoint> xvectorPPs;
- double fspace = 0.1;
- if(flen<2000)fspace = 0.1;
- else
- {
- if(flen<5000)fspace = 0.3;
- else
- {
- if(flen<10000)fspace = 0.5;
- else
- fspace = 1.0;
- }
- }
- int i;
- // std::vector<PlanPoint> xvectorPP = GetPoint( xpathsection[0].mpRoad);
- std::vector<PlanPoint> xvectorPP = GetPoint( xpathsection[0],fspace);
- int indexstart = indexinroadpoint(xvectorPP,nearx,neary);
- std::vector<PlanPoint> xvPP = GetLanePoint(xpathsection[0],xvectorPP,fvehiclewidth);
- if(xpathsection[0].mainsel < 0)
- {
- for(i=indexstart;i<xvPP.size();i++)
- {
- xvectorPPs.push_back(xvPP.at(i));
- }
- }
- else
- {
- for(i=(xvPP.size() -indexstart);i<xvPP.size();i++)
- {
- PlanPoint pp;
- pp = xvPP.at(i);
- // pp.hdg = pp.hdg +M_PI;
- xvectorPPs.push_back(pp);
- }
- }
- int npathlast = xpathsection.size() - 1;
- // while(npathlast >= 0)
- // {
- // if(npathlast == 0)break;
- // if(xpathsection[npathlast].mpRoad != xpathsection[npathlast - 1].mpRoad)break;
- // }
- for(i=1;i<(npathlast);i++)
- {
- // if(xpathsection[i].mpRoad == xpathsection[i-1].mpRoad)
- // {
- // if(xpathsection[i].mainsel * xpathsection[i-1].mainsel >0)
- // {
- // continue;
- // }
- // }
- // if(xpathsection[i].mpRoad == xpathsection[npathlast].mpRoad)
- // {
- // if(xpathsection[i].mainsel * xpathsection[npathlast].mainsel > 0)
- // {
- // break;
- // }
- // }
- // xvectorPP = GetPoint( xpathsection[i].mpRoad);
- xvectorPP = GetPoint( xpathsection[i],fspace);
- xvPP = GetLanePoint(xpathsection[i],xvectorPP,fvehiclewidth);
- // std::cout<<" road id: "<<xpathsection[i].mroadid<<" section: "
- // <<xpathsection[i].msectionid<<" size is "<<xvectorPP.size()<<std::endl;
- // std::cout<<" road id is "<<xpathsection[i].mpRoad->GetRoadId().data()<<" size is "<<xvPP.size()<<std::endl;
- int j;
- for(j=0;j<xvPP.size();j++)
- {
- xvectorPPs.push_back(xvPP.at(j));
- }
- }
- xvectorPP = GetPoint(xpathsection[npathlast],fspace);
- // xvectorPP = GetPoint(xpathsection[npathlast].mpRoad);
- int indexend = indexinroadpoint(xvectorPP,nearx_obj,neary_obj);
- xvPP = GetLanePoint(xpathsection[npathlast],xvectorPP,fvehiclewidth);
- int nlastsize;
- if(xpathsection[npathlast].mainsel<0)
- {
- nlastsize = indexend;
- }
- else
- {
- if(indexend>0) nlastsize = xvPP.size() - indexend;
- else nlastsize = xvPP.size();
- }
- for(i=0;i<nlastsize;i++)
- {
- xvectorPPs.push_back(xvPP.at(i));
- }
- //Find StartPoint
- // if
- // int a = 1;
- return xvectorPPs;
- }
- std::vector<PlanPoint> gTempPP;
- int getPoint(double q[3], double x, void* user_data) {
- // printf("%f, %f, %f, %f\n", q[0], q[1], q[2], x);
- PlanPoint pp;
- pp.x = q[0];
- pp.y = q[1];
- pp.hdg = q[2];
- pp.dis = x;
- pp.speed = *((double *)user_data);
- gTempPP.push_back(pp);
- // std::cout<<pp.x<<" "<<" "<<pp.y<<" "<<pp.hdg<<std::endl;
- return 0;
- }
- /**
- * @brief getlanesel
- * @param nSel
- * @param pLaneSection
- * @param nlr
- * @return
- */
- int getlanesel(int nSel,LaneSection * pLaneSection,int nlr)
- {
- int nlane = nSel;
- int mainselindex = 0;
- if(nlr == 2)nlane = nlane*(-1);
- int nlanecount = pLaneSection->GetLaneCount();
- int i;
- int nTrueSel = nSel;
- if(nTrueSel <= 1)nTrueSel= 1;
- int nCurSel = 1;
- if(nlr == 2)nCurSel = nCurSel *(-1);
- bool bOK = false;
- int nxsel = 1;
- int nlasttid = 0;
- bool bfindlast = false;
- while(bOK == false)
- {
- bool bHaveDriving = false;
- int ncc = 0;
- for(i=0;i<nlanecount;i++)
- {
- Lane * pLane = pLaneSection->GetLane(i);
- if(strncmp(pLane->GetType().data(),"driving",255) == 0 )
- {
- if((nlr == 1)&&(pLane->GetId()>0))
- {
- ncc++;
- }
- if((nlr == 2)&&(pLane->GetId()<0))
- {
- ncc++;
- }
- if(ncc == nxsel)
- {
- bHaveDriving = true;
- bfindlast = true;
- nlasttid = pLane->GetId();
- break;
- }
- }
- }
- if(bHaveDriving == true)
- {
- if(nxsel == nTrueSel)
- {
- return nlasttid;
- }
- else
- {
- nxsel++;
- }
- }
- else
- {
- if(bfindlast)
- {
- return nlasttid;
- }
- else
- {
- std::cout<<"can't find lane."<<std::endl;
- return 0;
- }
- //Use Last
- }
- }
- return 0;
- int k;
- bool bFind = false;
- while(bFind == false)
- {
- for(k=0;k<nlanecount;k++)
- {
- Lane * pLane = pLaneSection->GetLane(k);
- if((nlane == pLane->GetId())&&(strncmp(pLane->GetType().data(),"driving",255) == 0))
- {
- bFind = true;
- mainselindex = k;
- break;
- }
- }
- if(bFind)continue;
- if(nlr == 1)nlane--;
- else nlane++;
- if(nlane == 0)
- {
- std::cout<<" Fail. can't find lane"<<std::endl;
- break;
- }
- }
- return nlane;
- }
- void checktrace(std::vector<PlanPoint> & xPlan)
- {
- int i;
- int nsize = xPlan.size();
- for(i=1;i<nsize;i++)
- {
- 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));
- if(dis > 0.3)
- {
- double hdg = CalcHdg(QPointF(xPlan.at(i-1).x,xPlan.at(i-1).y),QPointF(xPlan.at(i).x,xPlan.at(i).y));
- int ncount = dis/0.1;
- int j;
- for(j=1;j<ncount;j++)
- {
- double x, y;
- PlanPoint pp;
- pp.x = xPlan.at(i-1).x + j*0.1 *cos(hdg);
- pp.y = xPlan.at(i-1).y + j*0.1 *sin(hdg);
- pp.hdg = hdg;
- xPlan.insert(xPlan.begin()+i+j-1,pp);
- }
- qDebug("dis is %f",dis);
- }
- }
- }
- void ChangeLane(std::vector<PlanPoint> & xvectorPP)
- {
- int i = 0;
- int nsize = xvectorPP.size();
- for(i=0;i<nsize;i++)
- {
- if((xvectorPP[i].mfSecx == xvectorPP[i].x)&&(xvectorPP[i].mfSecy == xvectorPP[i].y))
- {
- }
- else
- {
- int k;
- for(k=i;k<(nsize-1);k++)
- {
- if((xvectorPP[k].mfSecx == xvectorPP[k].x)&&(xvectorPP[k].mfSecy == xvectorPP[k].y))
- {
- break;
- }
- }
- int nnum = k-i;
- int nchangepoint = 300;
- double froadlen = sqrt(pow(xvectorPP[k].x - xvectorPP[i].x,2)
- +pow(xvectorPP[k].y - xvectorPP[i].y,2));
- const double fMAXCHANGE = 100;
- if(froadlen<fMAXCHANGE)
- {
- nchangepoint = nnum;
- }
- else
- {
- nchangepoint = (fMAXCHANGE/froadlen) * nnum;
- }
- qDebug(" road %d len is %f changepoint is %d nnum is %d",
- xvectorPP[k-1].nRoadID,froadlen,nchangepoint,nnum);
- int nstart = i + nnum/2 -nchangepoint/2;
- int nend = i+nnum/2 + nchangepoint/2;
- if(nnum<300)
- {
- nstart = i;
- nend = k;
- }
- int j;
- for(j=i;j<nstart;j++)
- {
- xvectorPP[j].x = xvectorPP[j].mfSecx;
- xvectorPP[j].y = xvectorPP[j].mfSecy;
- }
- nnum = nend - nstart;
- for(j=nstart;j<nend;j++)
- {
- double fdis = sqrt(pow(xvectorPP[j].x - xvectorPP[j].mfSecx,2)
- +pow(xvectorPP[j].y - xvectorPP[j].mfSecy,2));
- double foff = fdis *(j-nstart)/nnum;
- if(xvectorPP[j].nlrchange == 1)
- {
- // std::cout<<"foff is "<<foff<<std::endl;
- xvectorPP[j].x = xvectorPP[j].mfSecx + foff *cos(xvectorPP[j].hdg + M_PI/2.0);
- xvectorPP[j].y = xvectorPP[j].mfSecy + foff *sin(xvectorPP[j].hdg + M_PI/2.0);
- xvectorPP[j].mfDisToRoadLeft = xvectorPP[j].mfDisToRoadLeft + fdis - foff;
- }
- else
- {
- xvectorPP[j].x = xvectorPP[j].mfSecx + foff *cos(xvectorPP[j].hdg - M_PI/2.0);
- xvectorPP[j].y = xvectorPP[j].mfSecy + foff *sin(xvectorPP[j].hdg - M_PI/2.0);
- xvectorPP[j].mfDisToRoadLeft = xvectorPP[j].mfDisToRoadLeft - fdis +foff;
- }
- }
- i =k;
- }
- }
- }
- #include <QFile>
- /**
- * @brief MakePlan 全局路径规划
- * @param pxd 有向图
- * @param pxodr OpenDrive地图
- * @param x_now 当前x坐标
- * @param y_now 当前y坐标
- * @param head 当前航向
- * @param x_obj 目标点x坐标
- * @param y_obj 目标点y坐标
- * @param obj_dis 目标点到路径的距离
- * @param srcnearthresh 当前点离最近路径的阈值,如果不在这个范围,寻找失败
- * @param dstnearthresh 目标点离最近路径的阈值,如果不在这个范围,寻找失败
- * @param nlanesel 车道偏好,1为内车道,数值越大越偏外,如果数值不满足,会选择最靠外的。
- * @param xPlan 返回的轨迹点
- * @return 0 成功 <0 失败
- */
- int MakePlan(xodrdijkstra * pxd,OpenDrive * pxodr,const double x_now,const double y_now,const double head,
- const double x_obj,const double y_obj,const double & obj_dis,
- const double srcnearthresh,const double dstnearthresh,
- const int nlanesel,std::vector<PlanPoint> & xPlan,const double fvehiclewidth )
- {
- double s;double nearx;
- double neary;double nearhead;
- Road * pRoad;GeometryBlock * pgeob;
- double fs1,fs2;
- // int nfind = GetNearPoint(x_now,y_now,pxodr,&pRoad,&pgeob,s,nearx,neary,nearhead,srcnearthresh);
- int nfind = GetNearPointWithHead(x_now,y_now,head,pxodr,&pRoad,&pgeob,s,nearx,neary,nearhead,srcnearthresh,fs1);
- if(nfind < 0)return -1;
- fs1 =fs1 + pgeob->GetGeometryAt(0)->GetS();
- double s_obj;double nearx_obj;
- double neary_obj;double nearhead_obj;
- Road * pRoad_obj;GeometryBlock * pgeob_obj;
- int nfind_obj = GetNearPoint(x_obj,y_obj,pxodr,&pRoad_obj,&pgeob_obj,s_obj,nearx_obj,neary_obj,
- nearhead_obj,dstnearthresh,fs2);
- if(nfind_obj < 0)return -2;
- fs2 = fs2 + pgeob_obj->GetGeometryAt(0)->GetS();
- //计算终点在道路的左侧还是右侧
- int lr_end = 2;
- double hdg_end;
- hdg_end = CalcHdg(QPointF(nearx_obj,neary_obj),QPointF(x_obj,y_obj));
- double hdgdiff = nearhead_obj - hdg_end;
- while(hdgdiff<0)hdgdiff= hdgdiff + 2.0*M_PI;
- while(hdgdiff >= 2.0*M_PI)hdgdiff = hdgdiff- 2.0*M_PI;
- if(hdgdiff<= M_PI)
- {
- lr_end = 2;
- }
- else
- {
- lr_end = 1;
- }
- if((pRoad_obj->GetLaneSection(0)->GetLeftLaneCount()<1)&&(lr_end == 1))
- {
- lr_end = 2;
- }
- if((pRoad_obj->GetLaneSection(0)->GetRightLaneCount()<1)&&(lr_end == 2))
- {
- lr_end = 2;
- }
- int lr_start = SelectRoadLeftRight(pRoad,head,nearhead);
- bool bNeedDikstra = true;
- if((atoi(pRoad->GetRoadId().data()) == atoi(pRoad_obj->GetRoadId().data()))&&(lr_start == lr_end) &&(pRoad->GetLaneSectionCount() == 1))
- {
- std::vector<PlanPoint> xvPP = GetPoint(pRoad);
- int nindexstart = indexinroadpoint(xvPP,nearx,neary);
- int nindexend = indexinroadpoint(xvPP,nearx_obj,neary_obj);
- int nlane = getlanesel(nlanesel,pRoad->GetLaneSection(0),lr_start);
- AddSignalMark(pRoad,nlane,xvPP);
- if((nindexend >nindexstart)&&(lr_start == 2))
- {
- bNeedDikstra = false;
- }
- if((nindexend <nindexstart)&&(lr_start == 1))
- {
- bNeedDikstra = false;
- }
- if(bNeedDikstra == false)
- {
- std::vector<iv::lanewidthabcd> xvectorLWA = GetLaneWidthABCD(pRoad);
- std::vector<int> xvectorindex1;
- xvectorindex1 = GetLWIndex(xvectorLWA,nlane);
- double foff = getoff(pRoad,nlane);
- foff = foff + 0.0;
- std::vector<PlanPoint> xvectorPP;
- int i = nindexstart;
- while(i!=nindexend)
- {
- if(lr_start == 2)
- {
- PlanPoint pp = xvPP.at(i);
- foff = getoff(nlane,pp.mS,xvectorLWA,xvectorindex1);
- pp.x = pp.x + foff *cos(pp.hdg + M_PI/2.0);
- pp.y = pp.y + foff *sin(pp.hdg + M_PI/2.0);
- pp.mWidth = getwidth(pRoad,nlane,xvectorLWA,pp.mS);
- pp.mfDisToLaneLeft = pp.mWidth/2.0;
- pp.lanmp = 0;
- pp.mfDisToRoadLeft = foff *(-1.0);
- pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane,pp.mS);
- GetLaneOriTotal(pRoad,nlane,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- xvectorPP.push_back(pp);
- i++;
- }
- else
- {
- PlanPoint pp = xvPP.at(i);
- foff = getoff(nlane,pp.mS,xvectorLWA,xvectorindex1);
- pp.x = pp.x + foff *cos(pp.hdg + M_PI/2.0);
- pp.y = pp.y + foff *sin(pp.hdg + M_PI/2.0);
- pp.hdg = pp.hdg + M_PI;
- pp.mWidth = getwidth(pRoad,nlane,xvectorLWA,pp.mS);
- pp.mfDisToLaneLeft = pp.mWidth/2.0;
- pp.lanmp = 0;
- pp.mfDisToRoadLeft = foff;
- pp.mfRoadWidth = GetRoadWidth(xvectorLWA,nlane,pp.mS);
- GetLaneOriTotal(pRoad,nlane,pp.mS,pp.mnLaneori,pp.mnLaneTotal,pp.speed);
- xvectorPP.push_back(pp);
- i--;
- }
- }
- pathsection xps;
- xps.mbStartToMainChange = false;
- xps.mbMainToEndChange = false;
- // CalcInLaneAvoid(xps,xvectorPP,fvehiclewidth,0,0,0);
- xPlan = xvectorPP;
- }
- }
- if(bNeedDikstra)
- {
- std::vector<int> xpath = pxd->getpath(atoi(pRoad->GetRoadId().data()),lr_start,atoi(pRoad_obj->GetRoadId().data()),lr_end,fs1,fs2);
- double flen = pxd->getpathlength(xpath);
- std::vector<pathsection> xpathsection = pxd->getgpspoint(atoi(pRoad->GetRoadId().data()),lr_start,atoi(pRoad_obj->GetRoadId().data()),lr_end,xpath,nlanesel);
- std::vector<PlanPoint> xvectorPP = GetPlanPoint(xpathsection,pRoad,pgeob,pRoad_obj,pgeob_obj,x_now,y_now,
- head,nearx,neary,nearhead,nearx_obj,neary_obj,fvehiclewidth,flen);
- ChangeLane(xvectorPP);
- xPlan = xvectorPP;
- }
- int i;
- // QFile xFile;
- // xFile.setFileName("/home/yuchuli/tempgps.txt");
- // xFile.open(QIODevice::ReadWrite);
- // for(i<0;i<xPlan.size();i++)
- // {
- // char strout[1000];
- // snprintf(strout,1000,"%d %f %f %d %d %d %f \n",i,xPlan[i].mfDisToLaneLeft,
- // xPlan[i].mfDisToRoadLeft,xPlan[i].mnLaneori,xPlan[i].mnLaneTotal,
- // xPlan[i].lanmp,xPlan[i].mWidth);
- // xFile.write(strout,strnlen(strout,1000));
- // }
- // xFile.close();
- // checktrace(xPlan);
- // std::cout<<"pp size is "<<xvectorPP.size()<<std::endl;
- return 0;
- if(nfind_obj < 0)return -2;
- if(pRoad != pRoad_obj)return -3; //temp,simple plan
- if(pgeob != pgeob_obj)return -4; //temp,simple geo
- if(!pgeob->CheckIfLine())return -5; //temp,only line plan;
- int nlane = nlanesel;
- if(nlane <= 0 )nlane = 1;
- if(nlane >= pRoad->GetLaneSection(0)->GetLaneCount())
- {
- nlane = pRoad->GetLaneSection(0)->GetLaneCount()-1;
- }
- double bianxiandis = 0;
- double bianxiandis_obj = 0;
- double park_x,park_y;//Park point
- bianxiandis = pRoad->GetLaneSection(0)->GetLane(1)->GetWidthValue(1)/2.0;
- // int i = 1;
- for(i=1;i<nlane;i++)
- {
- bianxiandis = bianxiandis + pRoad->GetLaneSection(0)->GetLane(i)->GetWidthValue(1)/2.0
- +pRoad->GetLaneSection(0)->GetLane(i+1)->GetWidthValue(1)/2.0;
- }
- double bianxianx1 = bianxiandis;
- bianxiandis = fabs(s - bianxiandis);
- bianxiandis_obj = 0;
- int ag = pRoad->GetLaneSection(0)->GetLaneCount();
- for(i=(nlane +1);i<pRoad->GetLaneSection(0)->GetLaneCount();i++)
- {
- bianxiandis_obj = bianxiandis_obj
- +pRoad->GetLaneSection(0)->GetLane(i-1)->GetWidthValue(1)/2.0
- +pRoad->GetLaneSection(0)->GetLane(i)->GetWidthValue(1)/2.0;
- }
- // double x_objreal = nearx_obj + bianxiandis_obj * cos(nearhead_obj - M_PI/2.0);
- // park_x = nearx_obj + (bianxiandis_obj +bianxianx1 + pRoad->GetLaneSection(0)->GetLane(1)->GetWidthValue(0)/2.0)*cos(nearhead_obj -M_PI/2.0);
- // park_y = neary_obj + (bianxiandis_obj +bianxianx1+ pRoad->GetLaneSection(0)->GetLane(1)->GetWidthValue(0)/2.0)*sin(nearhead_obj -M_PI/2.0);
- park_x = nearx_obj + (bianxiandis_obj +bianxianx1 )*cos(nearhead_obj -M_PI/2.0);
- park_y = neary_obj + (bianxiandis_obj +bianxianx1 )*sin(nearhead_obj -M_PI/2.0);
- const double bianxian_ang = 0.2;
- double src_len,dst_len;
- src_len = bianxiandis/atan(bianxian_ang);
- dst_len = bianxiandis_obj/atan(bianxian_ang);
- double xl1,yl1,xl2,yl2;
- xl1 = nearx + src_len * cos(nearhead);
- yl1 = neary + src_len * sin(nearhead);
- xl2 = nearx_obj - dst_len * cos(nearhead_obj);
- yl2 = neary_obj - dst_len * sin(nearhead_obj);
- xl1 = xl1 + bianxianx1 * cos(nearhead - M_PI/2.0);
- yl1 = yl1 + bianxianx1 * sin(nearhead - M_PI/2.0);
- xl2 = xl2 + bianxianx1 * cos(nearhead_obj - M_PI/2.0);
- yl2 = yl2 + bianxianx1 * sin(nearhead_obj - M_PI/2.0);
- double q0[3],q1[3];
- gTempPP.clear();
- q0[0] = x_now;q0[1] = y_now; q0[2] = head;
- q1[0] = xl1;q1[1] =yl1;q1[2] = nearhead;
- int indexp = 0;
- double turning_radius = 15.0;
- double speedvalue = 3;
- DubinsPath path;
- dubins_shortest_path( &path, q0, q1, turning_radius);
- dubins_path_sample_many( &path, 0.1, getPoint, &speedvalue);
- for(i=indexp;i<gTempPP.size();i++)gTempPP.at(i).lanmp = 1;
- indexp = gTempPP.size();
- if(pRoad->GetLaneSection(0)->GetLane(nlane)->GetLaneSpeedCount()>1)
- speedvalue = pRoad->GetLaneSection(0)->GetLane(nlane)->GetLaneSpeed(1)->GetMax();
- else speedvalue = 10.0;
- memcpy(q0,q1,3*sizeof(double));
- q1[0]=xl2; q1[1]=yl2; q1[2]=nearhead;
- dubins_shortest_path( &path, q0, q1, turning_radius);
- dubins_path_sample_many( &path, 0.1, getPoint, &speedvalue);
- for(i=indexp;i<gTempPP.size();i++)gTempPP.at(i).lanmp = 0;
- indexp = gTempPP.size();
- double vx = 3.0;
- for(i= (gTempPP.size() -1);i>0;i--)
- {
- gTempPP.at(i).speed = vx;
- vx = vx + 0.03;
- gTempPP.at(i).lanmp = -1;
- if(vx > speedvalue)break;
- }
- speedvalue = 3.0;
- memcpy(q0,q1,3*sizeof(double));
- q1[0]=park_x; q1[1]=park_y; q1[2]=nearhead_obj;
- dubins_shortest_path( &path, q0, q1, turning_radius);
- dubins_path_sample_many( &path, 0.1, getPoint, &speedvalue);
- for(i=indexp;i<gTempPP.size();i++)gTempPP.at(i).lanmp = -1;
- indexp = gTempPP.size();
- double parkx_ext = park_x + 30 * cos(nearhead);
- double parky_ext = park_y + 30 * sin(nearhead);
- speedvalue = 0.0;
- memcpy(q0,q1,3*sizeof(double));
- q1[0]=parkx_ext; q1[1]=parky_ext; q1[2]=nearhead;
- dubins_shortest_path( &path, q0, q1, turning_radius);
- dubins_path_sample_many( &path, 0.1, getPoint, &speedvalue);
- for(i=indexp;i<gTempPP.size();i++)gTempPP.at(i).lanmp = 0;
- indexp = gTempPP.size();
- for(i=0;i<gTempPP.size();i++)
- {
- xPlan.push_back(gTempPP.at(i));
- }
- return 0;
- PlanPoint pp;
- double hdgsrc,hdgdst;
- double ldis1 = sqrt(pow(xl1 -x_now,2) + pow(yl1 -y_now,2) );
- if(ldis1 > 0)
- {
- hdgsrc = asin((yl1-y_now)/ldis1);
- if(xl1 < x_now)hdgsrc = M_PI - hdgsrc;
- if(hdgsrc < 0)hdgsrc = hdgsrc + 2.0 * M_PI;
- }
- double ldis2 = sqrt(pow(park_x-xl2,2)+pow(park_y-yl2,2));
- if(ldis2 > 0)
- {
- hdgdst = asin((park_y - yl2)/ldis2);
- if(park_x < xl2)hdgdst = M_PI - hdgdst;
- if(hdgdst < 0)hdgdst = hdgdst + 2.0*M_PI;
- }
- double xv,yv,speed;
- i = 0;
- double disx = 0.0;
- const double step = 0.1;
- xv = x_now;
- yv = y_now;
- pp.x = xv;pp.y = yv;pp.hdg = hdgsrc;pp.speed= 3.0;pp.lanmp = 1;xPlan.push_back(pp);
- // qDebug("%d %f %f",i,xv,yv);
- if(ldis1 > 0)
- {
- while((disx+step) < ldis1)
- {
- disx = disx + step;
- i++;
- xv = x_now + disx * cos(hdgsrc);
- yv = y_now + disx * sin(hdgsrc);
- pp.x = xv;pp.y = yv;pp.hdg = hdgsrc;pp.speed= 3.0;xPlan.push_back(pp);
- // qDebug("%d %f %f",i,xv,yv);
- }
- }
- i++;
- xv = xl1;yv = yl1;
- // qDebug("1:%d %f %f",i,xv,yv);
- pp.x = xv;pp.y = yv;pp.hdg = hdgsrc;pp.speed= 3.0;pp.lanmp = 0;xPlan.push_back(pp);
- double dis2p = sqrt(pow(xl2-xl1,2) + pow(yl2 -yl1,2));
- disx = 0;
- if(dis2p > 0)
- {
- while((disx+step) < dis2p)
- {
- disx = disx + step;
- i++;
- xv = xl1 + disx * cos(nearhead);
- yv = yl1 + disx * sin(nearhead);
- if(pRoad->GetLaneSection(0)->GetLane(nlane)->GetLaneSpeedCount()>1)
- speed = pRoad->GetLaneSection(0)->GetLane(nlane)->GetLaneSpeed(1)->GetMax();
- else speed = 10.0;
- if((dis2p -disx)<((speed - 3.0)*5)){
- speed = 3.0;
- pp.lanmp = -1;
- }
- else
- {
- pp.lanmp = 0;
- }
- pp.x = xv;pp.y = yv;pp.hdg = nearhead;pp.speed= speed;xPlan.push_back(pp);
- // qDebug("%d %f %f speed is %f",i,xv,yv,speed);
- }
- }
- i++;
- xv = xl2;yv = yl2;
- pp.x = xv;pp.y = yv;pp.hdg = hdgdst;pp.speed= 3.0;pp.lanmp = -1;xPlan.push_back(pp);
- // qDebug("2: %d %f %f",i,xv,yv);
- disx = 0;
- if(ldis2 > 0)
- {
- while((disx+step) < ldis2)
- {
- disx = disx + step;
- i++;
- xv = xl2 + disx * cos(hdgdst);
- yv = yl2 + disx * sin(hdgdst);
- speed = 3.0;
- pp.x = xv;pp.y = yv;pp.hdg = hdgdst;pp.speed= 3.0;pp.lanmp = -1;xPlan.push_back(pp);
- // qDebug("%d %f %f",i,xv,yv);
- }
- }
- i++;
- xv = park_x;yv = park_y;
- pp.x = xv;pp.y = yv;pp.hdg = nearhead_obj;pp.speed= 0.0;pp.lanmp = 0;xPlan.push_back(pp);
- // qDebug("obj: %d %f %f",i,xv,yv);
- disx = 0;
- while((disx+step) < 30)
- {
- disx = disx + step;
- i++;
- xv = park_x + disx * cos(nearhead);
- yv = park_y + disx * sin(nearhead);
- speed = 0.0;
- pp.x = xv;pp.y = yv;pp.hdg = nearhead_obj;pp.speed= speed;pp.lanmp = 0;xPlan.push_back(pp);
- // qDebug("%d %f %f",i,xv,yv);
- }
- }
|