12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547 |
- #include <QCoreApplication>
- #include <math.h>
- #include <string>
- #include <thread>
- #include <QFile>
- #include "OpenDrive/OpenDrive.h"
- #include "OpenDrive/OpenDriveXmlParser.h"
- #include "globalplan.h"
- #include "gpsimu.pb.h"
- #include "mapdata.pb.h"
- #include "mapglobal.pb.h"
- #include "v2x.pb.h"
- #include "modulecomm.h"
- #include "xmlparam.h"
- #include "gps_type.h"
- #include "xodrdijkstra.h"
- #include "gnss_coordinate_convert.h"
- #include "ivexit.h"
- #include "ivversion.h"
- #include "ivbacktrace.h"
- #include <signal.h>
- #include "service_roi_xodr.h"
- #include "ivservice.h"
- #ifdef USE_TMERS
- #include "proj.h"
- //#include "projects.h"
- PJ_CONTEXT *C;//用于处理多线程程序
- PJ *P;//初始化投影目标
- PJ *norm;//初始化投影目标
- #endif
- OpenDrive mxodr;
- xodrdijkstra * gpxd;
- bool gmapload = false;
- double glat0,glon0,ghead0;
- double gvehiclewidth = 2.0;
- bool gbExtendMap = true;
- static bool gbSideEnable = false;
- static bool gbSideLaneEnable = false;
- static std::string gstrcdata;
- static void * gpa;
- static void * gpasrc;
- static void * gpmap;
- static void * gpagps;
- static void * gpasimple;
- static void * gpav2x;
- static void * gpanewtrace;
- static void * gpamapglobal;
- iv::Ivfault *gfault = nullptr;
- iv::Ivlog *givlog = nullptr;
- static QCoreApplication * gApp;
- service_roi_xodr gsrx;
- namespace iv {
- struct simpletrace
- {
- double gps_lat = 0;//纬度
- double gps_lng = 0;//经度
- double gps_x = 0;
- double gps_y = 0;
- double gps_z = 0;
- double ins_heading_angle = 0; //航向角
- };
- }
- /**
- *
- *
- *
- *
- * */
- bool LoadXODR(std::string strpath)
- {
- OpenDriveXmlParser xp(&mxodr);
- xp.ReadFile(strpath);
- std::cout<<"road cout is "<<mxodr.GetRoadCount()<<std::endl;
- if(mxodr.GetRoadCount() < 1)
- {
- gmapload = true;
- return false;
- }
- xodrdijkstra * pxd = new xodrdijkstra(&mxodr);
- gpxd = pxd;
- // std::vector<int> xpath = pxd->getpath(10001,2,30012,2);
- // pxd->getgpspoint(10001,2,30012,2,xpath);
- int i;
- double nlenth = 0;
- int nroadsize = mxodr.GetRoadCount();
- for(i=0;i<nroadsize;i++)
- {
- Road * px = mxodr.GetRoad(i);
- nlenth = nlenth + px->GetRoadLength();
- int bloksize = px->GetGeometryBlockCount();
- if(px->GetGeometryBlock(0)->GetGeometryAt(0)->GetGeomType() == 4)
- {
- GeometryParamPoly3 * p = (GeometryParamPoly3 *) px->GetGeometryBlock(0)->GetGeometryAt(0);
- double a = p->GetuA();
- a = p->GetuB();
- a = p->GetuC();
- a = p->GetuD();
- a = p->GetvA();
- }
- }
- // void Header::GetAllParams(unsigned short int &revMajor, unsigned short int &revMinor, string &name, float &version, string &date,
- // double &north, double &south, double &east,double &west,double &lat0,double &lon0, double & hdg0)
- unsigned short int revMajor,revMinor;
- std::string name,date;
- float version;
- double north,south,east,west,lat0,lon0,hdg0;
- if(mxodr.GetHeader() != 0)
- {
- mxodr.GetHeader()->GetAllParams(revMajor,revMinor,name,version,date,north,south,east,west,lat0,lon0,hdg0);
- glat0 = lat0;
- glon0 = lon0;
- }
- Road * proad1 = mxodr.GetRoad(0);
- givlog->info("road name is %s",proad1->GetRoadName().data());
- std::cout<<" road name is "<<proad1->GetRoadName()<<std::endl;
- gsrx.SetXODR(&mxodr);
- }
- class roadx
- {
- public:
- roadx * para;
- std::vector<roadx> child;
- int nlen;
- };
- #define EARTH_RADIUS 6370856.0
- //从1到2的距离和方向
- int CalcDisAngle(double lat1,double lon1,double lat2,double lon2,double * pLatDis,double * pLonDis,double * pDis,double * pangle)
- {
- double a,b;
- double LonDis,LatDis;
- double LonRadius;
- double Dis;
- double angle;
- if((lat1 == lat2)&&(lon1 == lon2))return -1;
- LonRadius = EARTH_RADIUS * cos(lat2/(180.0/M_PI));
- a = (EARTH_RADIUS * M_PI*2.0/360.0)/(100000.0);
- b = lat2 - lat1; b = b*100000.0;
- LatDis = a*b;
- a = (LonRadius * M_PI*2.0/360.0)/100000.0;
- b = lon2 - lon1; b = b*100000.0;
- LonDis = a*b;
- Dis = sqrt(LatDis*LatDis + LonDis *LonDis);
- angle = acos(fabs(LonDis)/Dis);
- angle = angle * 180.0/M_PI;
- if(LonDis > 0)
- {
- if(LatDis > 0)angle = 90.0 - angle;
- else angle= 90.0+angle;
- }
- else
- {
- if(LatDis > 0)angle = 270.0+angle;
- else angle = 270.0-angle;
- }
- if(pLatDis != 0)*pLatDis = LatDis;
- if(pLonDis != 0)*pLonDis = LonDis;
- if(pDis != 0)*pDis = Dis;
- if(pangle != 0)*pangle = angle;
- }
- //==========================================================
- //高斯投影由经纬度(Unit:DD)反算大地坐标(含带号,Unit:Metres)
- //void GaussProjCal(double longitude, double latitude, double *X, double *Y)
- //{
- // int ProjNo = 0; int ZoneWide; ////带宽
- // double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
- // double a, f, e2, ee, NN, T, C, A, M, iPI;
- // iPI = 0.0174532925199433; ////3.1415926535898/180.0;
- // ZoneWide = 6; ////6度带宽
- // a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
- // ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
- // ProjNo = (int)(longitude / ZoneWide);
- // longitude0 = ProjNo * ZoneWide + ZoneWide / 2;
- // longitude0 = longitude0 * iPI;
- // latitude0 = 0;
- // longitude1 = longitude * iPI; //经度转换为弧度
- // latitude1 = latitude * iPI; //纬度转换为弧度
- // e2 = 2 * f - f * f;
- // ee = e2 * (1.0 - e2);
- // NN = a / sqrt(1.0 - e2 * sin(latitude1)*sin(latitude1));
- // T = tan(latitude1)*tan(latitude1);
- // C = ee * cos(latitude1)*cos(latitude1);
- // A = (longitude1 - longitude0)*cos(latitude1);
- // M = a * ((1 - e2 / 4 - 3 * e2*e2 / 64 - 5 * e2*e2*e2 / 256)*latitude1 - (3 * e2 / 8 + 3 * e2*e2 / 32 + 45 * e2*e2
- // *e2 / 1024)*sin(2 * latitude1)
- // + (15 * e2*e2 / 256 + 45 * e2*e2*e2 / 1024)*sin(4 * latitude1) - (35 * e2*e2*e2 / 3072)*sin(6 * latitude1));
- // xval = NN * (A + (1 - T + C)*A*A*A / 6 + (5 - 18 * T + T * T + 72 * C - 58 * ee)*A*A*A*A*A / 120);
- // yval = M + NN * tan(latitude1)*(A*A / 2 + (5 - T + 9 * C + 4 * C*C)*A*A*A*A / 24
- // + (61 - 58 * T + T * T + 600 * C - 330 * ee)*A*A*A*A*A*A / 720);
- // X0 = 1000000L * (ProjNo + 1) + 500000L;
- // Y0 = 0;
- // xval = xval + X0; yval = yval + Y0;
- // *X = xval;
- // *Y = yval;
- //}
- #include <math.h>
- static void OffLngLat(double fLat0,double fLng0,double & fLat,double & fLng,double fHeading,double x,double y)
- {
- double fxdiff,fydiff;
- double xoff = y*(-1);
- double yoff = x;
- fxdiff = 0+xoff * cos(fHeading*M_PI/180.0)+ yoff*sin(fHeading*M_PI/180.0); //East
- fydiff = 0-xoff * sin(fHeading*M_PI/180.0)+ yoff*cos(fHeading*M_PI/180.0); //South
- double fEarthRadius = 6378245.0;
- double ns1d = fEarthRadius*2*M_PI/360.0;
- double fewRadius = fEarthRadius * cos(fLat0*M_PI/180.0);
- double ew1d = fewRadius * 2*M_PI/360.0;
- fLat = fLat0 + fydiff/ns1d;
- fLng = fLng0 + fxdiff/ew1d;
- }
- void CalcXY(const double lat0,const double lon0,const double hdg0,
- const double lat,const double lon,
- double & x,double & y)
- {
- double x0,y0;
- GaussProjCal(lon0,lat0,&x0,&y0);
- GaussProjCal(lon,lat,&x,&y);
- x = x - x0;
- y = y- y0;
- // double ang,dis;
- // CalcDisAngle(lat0,lon0,lat,lon,0,0,&dis,&ang);
- // double xang = hdg0 - ang;
- // while(xang<0)xang = xang + 360.0;
- // x = dis * cos(xang * M_PI/180.0);
- // y = dis * sin(xang * M_PI/180.0);
- }
- //void CalcLatLon(const double lat0,const double lon0,const double hdg0,
- // const double x,const double y,const double xyhdg,
- // double &lat,double & lon, double & hdg)
- //{
- // OffLngLat(lat0,lon0,lat,lon,hdg0,x,y);
- // hdg = hdg0 - xyhdg * 180.0/M_PI;
- // while(hdg < 0)hdg = hdg + 360;
- // while(hdg >= 360)hdg = hdg - 360;
- //}
- void CalcLatLon(const double lat0,const double lon0,
- const double x,const double y,
- double &lat,double & lon)
- {
- double x0,y0;
- GaussProjCal(lon0,lat0,&x0,&y0);
- double x_gps,y_gps;
- x_gps = x0+x;
- y_gps = y0+y;
- GaussProjInvCal(x_gps,y_gps,&lon,&lat);
- }
- void CalcLatLon(const double lat0,const double lon0,const double hdg0,
- const double x,const double y,const double xyhdg,
- double &lat,double & lon, double & hdg)
- {
- double x0,y0;
- GaussProjCal(lon0,lat0,&x0,&y0);
- double x_gps,y_gps;
- x_gps = x0+x;
- y_gps = y0+y;
- GaussProjInvCal(x_gps,y_gps,&lon,&lat);
- // hdg = hdg0 -xyhdg * 270/M_PI;
- hdg = 90 - xyhdg* 180.0/M_PI;
- // OffLngLat(lat0,lon0,lat,lon,hdg0,x,y);
- // hdg = hdg0 - xyhdg * 180.0/M_PI;
- while(hdg < 0)hdg = hdg + 360;
- while(hdg >= 360)hdg = hdg - 360;
- #ifdef USE_TMERS
- if(gstrcdata.length()>3)
- {
- PJ_COORD cp;//初始化投影坐标
- cp.enu.e = x;
- cp.enu.n = y;
- cp = proj_trans(P, PJ_INV, cp);//xy坐标转化为经纬度坐标
- lon = cp.lp.lam;
- lat = cp.lp.phi;
- }
- #endif
- }
- class xodrobj
- {
- public:
- double flatsrc;
- double flonsrc;
- double fhgdsrc;
- double flat;
- double flon;
- int lane;
- };
- static xodrobj gsrc;
- void ShareMapGlobal(std::vector<PlanPoint> & xvectorPlan)
- {
- iv::map::mapglobal xglobal;
- unsigned int i;
- unsigned int nsize = static_cast<unsigned int >(xvectorPlan.size());
- for(i=0;i<nsize;i++)
- {
- iv::map::pointglobal * ppoint = xglobal.add_point();
- double gps_lon,gps_lat,gps_heading;
- CalcLatLon(glat0,glon0,ghead0,xvectorPlan[i].x,xvectorPlan[i].y,xvectorPlan[i].hdg,gps_lat,
- gps_lon,gps_heading);
- ppoint->set_gps_lat(gps_lat);
- ppoint->set_gps_lng(gps_lon);
- ppoint->set_ins_heading_angle(gps_heading);
- double gps_x,gps_y;
- GaussProjCal(gps_lon,gps_lat,&gps_x,&gps_y);
- ppoint->set_gps_x(gps_x);
- ppoint->set_gps_y(gps_y);
- ppoint->set_gps_z(0);
- ppoint->set_mfcurvature(xvectorPlan[i].mfCurvature);
- ppoint->set_mfdistolaneleft(xvectorPlan[i].mfDisToLaneLeft);
- ppoint->set_mfdistoroadleft(xvectorPlan[i].mfDisToRoadLeft);
- ppoint->set_mflanewidth(xvectorPlan[i].mWidth);
- ppoint->set_mfroadwidth(xvectorPlan[i].mfRoadWidth);
- ppoint->set_speed(xvectorPlan[i].speed);
- unsigned int nlanecount = static_cast<unsigned int>(xvectorPlan[i].mVectorLaneWidth.size());
- unsigned int j;
- for(j=0;j<nlanecount;j++)
- {
- ppoint->add_mfvectorlanewidth(xvectorPlan[i].mVectorLaneWidth[j]);
- }
- ppoint->set_mlanecount(xvectorPlan[i].mLaneCount);
- ppoint->set_mlanecur(xvectorPlan[i].mLaneCur);
- }
- int bytesize = static_cast<int>(xglobal.ByteSize()) ;
- std::shared_ptr<char> pstr_ptr = std::shared_ptr<char>(new char[bytesize]);
- if(xglobal.SerializePartialToArray(pstr_ptr.get(),bytesize))
- {
- iv::modulecomm::ModuleSendMsg(gpamapglobal,pstr_ptr.get(),static_cast<unsigned int>(bytesize) );
- }
- else
- {
- std::cout<<" ShareMapGlobal Serialzie Fail."<<std::endl;
- }
- }
- void ShareMap(std::vector<iv::GPSData> navigation_data)
- {
- if(navigation_data.size()<1)return;
- iv::GPS_INS x;
- x = *(navigation_data.at(0));
- char * data = new char[sizeof(iv::GPS_INS)*navigation_data.size()];
- int gpssize = sizeof(iv::GPS_INS);
- int i;
- for(i=0;i<navigation_data.size();i++)
- {
- x = *(navigation_data.at(i));
- memcpy(data+i*gpssize,&x,gpssize);
- }
- iv::modulecomm::ModuleSendMsg(gpmap,data,navigation_data.size()*gpssize);
- int nsize = 100;
- int nstep = 1;
- if(navigation_data.size() < 100)
- {
- nsize = navigation_data.size();
- }
- else
- {
- nstep = navigation_data.size()/100;
- }
- iv::simpletrace psim[100];
- for(i=0;i<nsize;i++)
- {
- x = *(navigation_data.at(i*nstep));
- psim[i].gps_lat = x.gps_lat;
- psim[i].gps_lng = x.gps_lng;
- psim[i].gps_z = x.gps_z;
- psim[i].gps_x = x.gps_x;
- psim[i].gps_y = x.gps_y;
- psim[i].ins_heading_angle = x.ins_heading_angle;
- }
- if(navigation_data.size()>100)
- {
- int nlast = 99;
- x = *(navigation_data.at(navigation_data.size()-1));
- psim[nlast].gps_lat = x.gps_lat;
- psim[nlast].gps_lng = x.gps_lng;
- psim[nlast].gps_z = x.gps_z;
- psim[nlast].gps_x = x.gps_x;
- psim[nlast].gps_y = x.gps_y;
- psim[nlast].ins_heading_angle = x.ins_heading_angle;
- }
- iv::modulecomm::ModuleSendMsg(gpasimple,(char *)psim,nsize * sizeof(iv::simpletrace));
- delete data;
- }
- static void ToGPSTrace(std::vector<PlanPoint> xPlan)
- {
- // double x_src,y_src,x_dst,y_dst;
- // x_src = -26;y_src = 10;
- // x_dst = -50;y_dst = -220;
- int i;
- int nSize = xPlan.size();
- std::vector<iv::GPSData> mapdata;
- QFile xfile;
- QString strpath;
- strpath = getenv("HOME");
- strpath = strpath + "/map/maptrace.txt";
- xfile.setFileName(strpath);
- bool bFileOpen = xfile.open(QIODevice::ReadWrite);
- for(i=0;i<nSize;i++)
- {
- iv::GPSData data(new iv::GPS_INS);
- CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
- data->gps_lng,data->ins_heading_angle);
- data->index = i;
- data->speed = xPlan[i].speed;
- GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
- givlog->debug(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
- data->gps_lng,data->ins_heading_angle);
- data->roadSum = xPlan[i].mnLaneTotal;
- data->roadMode = 0;
- data->roadOri = xPlan[i].mnLaneori;
- data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
- data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
- data->mfLaneWidth = xPlan[i].mWidth;
- data->mfRoadWidth = xPlan[i].mfRoadWidth;
- data->mnLaneChangeMark = xPlan[i].lanmp;
- if(xPlan[i].lanmp == -1)data->roadMode = 15;
- if(xPlan[i].lanmp == 1)data->roadMode = 14;
- mapdata.push_back(data);
- char strline[255];
- snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\n",
- i,data->gps_lng,data->gps_lat,0,0,data->ins_heading_angle,0,0,0,0);
- if(bFileOpen) xfile.write(strline);
- // fout << gps_index << "\t" << data->gps_lng << "\t" << data->gps_lat << "\t" << ServiceCarStatus.location->speed_mode << "\t" << ServiceCarStatus.location->mode2 << "\t" << data->ins_heading_angle << "\t" << obs_modes << "\t" << speed_modes << "\t" << lane_num << "\t" << lane_status <<"\t" <<road_width <<std::endl;
- }
- if(bFileOpen)xfile.close();
- ShareMap(mapdata);
- }
- int avoidroadid[] = {10002,10019,10003,10098,10099,10063,10099,10100,10104,10110,10111};
- inline bool isboringroad(int nroadid)
- {
- int i;
- bool brtn = false;
- for(i=0;i<11;i++)
- {
- if(avoidroadid[i] == nroadid)
- {
- brtn = true;
- break;
- }
- }
- return brtn;
- }
- void CalcLaneSide(std::vector<PlanPoint> & xPlan)
- {
- const double fsidedis = 0.3;
- const int nChangePoint = 150;
- const int nStopPoint = 50;
- if(xPlan.size()<nChangePoint)return;
- int i;
- int nsize = xPlan.size();
- for(i=(nsize-1);i>=(nsize - nStopPoint);i--)
- {
- double fMove = xPlan[i].mfRoadWidth - xPlan[i].mfDisToRoadLeft - (gvehiclewidth/2.0 + fsidedis);
- // double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
- double xold = xPlan[i].x;
- double yold = xPlan[i].y;
- xPlan[i].x = xold + fMove*cos(xPlan[i].hdg - M_PI/2.0);
- xPlan[i].y = yold + fMove*sin(xPlan[i].hdg - M_PI/2.0);
- xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fMove;
- }
- for(i=(nsize-nStopPoint-1);i>=(nsize - nChangePoint);i--)
- {
- double fMove = xPlan[i].mfRoadWidth - xPlan[i].mfDisToRoadLeft - (gvehiclewidth/2.0 + fsidedis);
- // double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
- double xold = xPlan[i].x;
- double yold = xPlan[i].y;
- double fRatio = 1.0 - ((nsize-nStopPoint) -i )*1.0/(nChangePoint-nStopPoint);
- xPlan[i].x = xold + fRatio*fMove*cos(xPlan[i].hdg - M_PI/2.0);
- xPlan[i].y = yold + fRatio*fMove*sin(xPlan[i].hdg - M_PI/2.0);
- xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fRatio*fMove;
- }
- return;
- }
- void CalcSide(std::vector<PlanPoint> & xPlan)
- {
- const double fsidedis = 0.3;
- const int nChangePoint = 150;
- const int nStopPoint = 50;
- if(xPlan.size()<nChangePoint)return;
- bool bChange = true;
- int i;
- int nsize = xPlan.size();
- for(i=(nsize-1);i>=(nsize - nChangePoint);i--)
- {
- if(xPlan[i].mWidth<(2.0*(gvehiclewidth/2.0+fsidedis)))
- {
- std::cout<<" Because Lane is narrow, not change."<<std::endl;
- bChange = false;
- break;
- }
- }
- if(bChange == false)return;
- for(i=(nsize-1);i>=(nsize - nStopPoint);i--)
- {
- double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
- double xold = xPlan[i].x;
- double yold = xPlan[i].y;
- xPlan[i].x = xold + fMove*cos(xPlan[i].hdg - M_PI/2.0);
- xPlan[i].y = yold + fMove*sin(xPlan[i].hdg - M_PI/2.0);
- xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fMove;
- }
- for(i=(nsize-nStopPoint-1);i>=(nsize - nChangePoint);i--)
- {
- double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
- double xold = xPlan[i].x;
- double yold = xPlan[i].y;
- double fRatio = 1.0 - ((nsize-nStopPoint) -i )*1.0/(nChangePoint-nStopPoint);
- xPlan[i].x = xold + fRatio*fMove*cos(xPlan[i].hdg - M_PI/2.0);
- xPlan[i].y = yold + fRatio*fMove*sin(xPlan[i].hdg - M_PI/2.0);
- xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fRatio*fMove;
- }
- return;
- }
- #ifdef TESTSPEEDPLAN
- #include <math.h>
- #include <limits>
- double valuemin(double a,double b)
- {
- if(a<b)return a;
- return b;
- }
- int getPlanSpeed(std::vector<iv::GPSData> MapTrace)
- {
- int mode0to5count=0,mode0to18count=0,mode0to5countSum=0,mode0to18countSum=0,mode18count=0,mode18countSum=0,mode0to5flash=0,mode18flash=0;
- double straightSpeed=40;
- double straightCurveSpeed=30;
- double Curve_SmallSpeed=15;
- double Curve_LargeSpeed=8;
- std::vector<std::vector<double>> doubledata;
- doubledata.clear();
- for (int i = 0; i < MapTrace.size(); i++) { // 1225/14:25
- std::vector<double> temp;
- temp.clear();
- temp.push_back(0);temp.push_back(0);temp.push_back(0);temp.push_back(0);temp.push_back(0);//先push四个空量,然后就可以给量赋值了
- doubledata.push_back(temp);
- doubledata[i][0] = MapTrace.at(i)->gps_x;
- doubledata[i][1] = MapTrace.at(i)->gps_y;
- doubledata[i][2] = (MapTrace.at(i)->ins_heading_angle) / 180 * M_PI;
- doubledata[i][3]=0;
- doubledata[i][4]=0;
- }
- for(int i=0;i<doubledata.size();i++)
- {
- if((MapTrace[i]->mfCurvature>-0.02)&&(MapTrace[i]->mfCurvature<0.02)){
- MapTrace[i]->roadMode=5;
- }else if(((MapTrace[i]->mfCurvature>=0.02)&&(MapTrace[i]->mfCurvature<=0.16))||((MapTrace[i]->mfCurvature>=-0.16)&&(MapTrace[i]->mfCurvature<=-0.02))){
- MapTrace[i]->roadMode=18;
- }else if(((MapTrace[i]->mfCurvature>0.16))||((MapTrace[i]->mfCurvature<-0.16))){
- MapTrace[i]->roadMode=14;
- }
- }
- for(int i=0;i<MapTrace.size();i++)
- {
- if(MapTrace[i]->roadMode==0){
- doubledata[i][4]=straightSpeed;
- mode0to5count++;
- //mode0to18count++;
- mode18count=0;
- mode0to5flash=mode0to5count;
- }else if(MapTrace[i]->roadMode==5){
- doubledata[i][4]=straightCurveSpeed;
- mode0to5count++;
- //mode0to18count++;
- mode18count=0;
- mode0to5flash=mode0to5count;
- }else if(MapTrace[i]->roadMode==18){
- mode0to5countSum=mode0to5count;
- doubledata[i][4]=Curve_SmallSpeed;
- double brake_distance_double=(pow((straightCurveSpeed/3.6),2)-pow((Curve_SmallSpeed/3.6),2))*10/0.6;
- int brake_distance=(int)brake_distance_double;
- int step_count=0;
- if((i>brake_distance)&&(mode0to5countSum>brake_distance))
- {
- double step_speed=(straightCurveSpeed-Curve_SmallSpeed)/brake_distance;
- for(int j=i;j>i-brake_distance;j--){
- doubledata[j][4]=valuemin((Curve_SmallSpeed+step_count*step_speed),straightCurveSpeed);
- step_count++;
- }
- }else if(mode0to5countSum>0){
- for(int j=i;j>=i-mode0to5countSum;j--){
- doubledata[j][4]=Curve_SmallSpeed;
- step_count++;
- }
- }else{
- doubledata[i][4]=Curve_SmallSpeed;
- }
- mode0to5count=0;
- //mode0to18count++;
- mode18count++;
- mode18flash=mode18count;
- }else if(MapTrace[i]->roadMode==14){
- mode0to18countSum=mode0to5flash+mode18flash;
- mode18countSum=mode18count;
- double brake_distanceLarge_double=(pow((Curve_SmallSpeed/3.6),2)-pow((Curve_LargeSpeed/3.6),2))*10/0.6;
- double brake_distance0to18_double=(pow((straightCurveSpeed/3.6),2)-pow((Curve_LargeSpeed/3.6),2))*10/0.6;
- int brake_distanceLarge=(int)brake_distanceLarge_double;
- int brake_distance0to18=(int)brake_distance0to18_double;
- int step_count=0;
- doubledata[i][4]=Curve_LargeSpeed;
- if(mode18countSum>brake_distanceLarge)
- {
- double step_speed=(Curve_SmallSpeed-Curve_LargeSpeed)/brake_distanceLarge;
- for(int j=i;j>i-brake_distanceLarge;j--){
- doubledata[j][4]=valuemin((Curve_LargeSpeed+step_count*step_speed),Curve_SmallSpeed);
- step_count++;
- }
- }else if(mode0to18countSum>brake_distance0to18){
- double step_speed=(straightCurveSpeed-Curve_LargeSpeed)/brake_distance0to18;
- for(int j=i;j>i-brake_distance0to18;j--){
- doubledata[j][4]=valuemin((Curve_LargeSpeed+step_count*step_speed),straightCurveSpeed);
- step_count++;
- }
- }else{
- doubledata[i][4]=Curve_LargeSpeed;
- }
- mode0to5count=0;
- mode18count=0;
- mode0to5flash=0;
- mode18flash=0;
- }
- }
- return 0;
- }
- #endif
- void SetPlan(xodrobj xo)
- {
- double x_src,y_src,x_dst,y_dst;
- CalcXY(glat0,glon0,ghead0,xo.flatsrc,xo.flonsrc,x_src,y_src);
- CalcXY(glat0,glon0,ghead0,xo.flat,xo.flon,x_dst,y_dst);
- std::vector<PlanPoint> xPlan;
- double s;
- // x_src = -5;y_src = 6;
- // x_dst = -60;y_src = -150;
- int nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,(90 - xo.fhgdsrc)*M_PI/180.0,x_dst,y_dst,s,30.0,100.0,xo.lane,xPlan);
- if(nRtn < 0)
- {
- qDebug("plan fail.");
- return;
- }
- int i;
- int nSize = xPlan.size();
- if(gbSideLaneEnable)
- {
- CalcLaneSide(xPlan);
- }
- else
- {
- if(gbSideEnable)
- {
- CalcSide(xPlan);
- }
- }
- if(nSize<1)
- {
- qDebug("plan fail.");
- return;
- }
- PlanPoint xLastPoint = xPlan[nSize -1];
- for(i=0;i<600;i++)
- {
- PlanPoint pp = xLastPoint;
- double fdis = 0.1*(i+1);
- pp.mS = pp.mS + i*0.1;
- pp.x = pp.x + fdis * cos(pp.hdg);
- pp.y = pp.y + fdis * sin(pp.hdg);
- pp.nSignal = 23;
- if(gbExtendMap)
- {
- xPlan.push_back(pp);
- }
- }
-
- iv::map::tracemap xtrace;
- nSize = xPlan.size();
- std::vector<iv::GPSData> mapdata;
- //maptrace
- QFile xfile;
- QString strpath;
- strpath = getenv("HOME");
- strpath = strpath + "/map/maptrace.txt";
- xfile.setFileName(strpath);
- xfile.open(QIODevice::ReadWrite);
- //maptrace_add
- QFile xfile_1;
- QString strpath_1;
- strpath_1 = getenv("HOME");
- strpath_1 = strpath_1 + "/map/mapadd.txt";
- xfile_1.setFileName(strpath_1);
- xfile_1.open(QIODevice::ReadWrite);
- for(i=0;i<nSize;i++)
- {
- iv::map::mappoint * pmappoint = xtrace.add_point();
- double gps_lon,gps_lat,gps_lon_avoidleft,gps_lat_avoidleft,gps_lat_avoidright,gps_lon_avoidright,gps_heading;
- CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,gps_lat,
- gps_lon,gps_heading);
- CalcLatLon(glat0,glon0,xPlan[i].mx_left,xPlan[i].my_left,
- gps_lat_avoidleft,gps_lon_avoidleft);
- CalcLatLon(glat0,glon0,xPlan[i].mx_right,xPlan[i].my_right,
- gps_lat_avoidright,gps_lon_avoidright);
- pmappoint->set_gps_lat(gps_lat);
- pmappoint->set_gps_lat_avoidleft(gps_lat_avoidleft);
- pmappoint->set_gps_lat_avoidright(gps_lat_avoidright);
- pmappoint->set_gps_lng(gps_lon);
- pmappoint->set_gps_lat_avoidleft(gps_lat_avoidleft);
- pmappoint->set_gps_lng_avoidright(gps_lon_avoidright);
- pmappoint->set_ins_heading_angle(gps_heading);
- double gps_x,gps_y,gps_x_avoidleft,gps_y_avoidleft,gps_x_avoidright,gps_y_avoidright;
- GaussProjCal(gps_lon,gps_lat,&gps_x,&gps_y);
- GaussProjCal(gps_lon_avoidleft,gps_lat_avoidleft,&gps_x_avoidleft,&gps_y_avoidleft);
- GaussProjCal(gps_lon_avoidright,gps_lat_avoidright,&gps_x_avoidright,&gps_y_avoidright);
- pmappoint->set_gps_x(gps_x);
- pmappoint->set_gps_x_avoidleft(gps_x_avoidleft);
- pmappoint->set_gps_x_avoidright(gps_x_avoidright);
- pmappoint->set_gps_y(gps_y);
- pmappoint->set_gps_y_avoidleft(gps_y_avoidleft);
- pmappoint->set_gps_y_avoidright(gps_y_avoidright);
- pmappoint->set_speed(xPlan[i].speed);
- pmappoint->set_index(i);
- pmappoint->set_roadori(xPlan[i].mnLaneori);
- pmappoint->set_roadsum(xPlan[i].mnLaneTotal);
- pmappoint->set_mfdistolaneleft(xPlan[i].mfDisToLaneLeft);
- pmappoint->set_mfdistoroadleft(xPlan[i].mfDisToRoadLeft);
- pmappoint->set_mflanewidth(xPlan[i].mWidth);
- pmappoint->set_mfroadwidth(xPlan[i].mfRoadWidth);
- pmappoint->set_mbinlaneavoid(xPlan[i].bInlaneAvoid);
- iv::GPSData data(new iv::GPS_INS);
- data->roadMode = 0;
- // std::cout<<"i:"<<i<<" lr:"<<xPlan[i].nlrchange<<std::endl;
- if(xPlan[i].nlrchange == 1)
- {
- data->roadMode = 14;
- }
- if(xPlan[i].nlrchange == 2)
- {
- data->roadMode = 15;
- }
- if(i>50)
- {
- if((xPlan[i-1].nlrchange == 0)&&(xPlan[i].nlrchange != 0))
- {
- int j;
- for(j=(i-1);j>=(i-50);j--)
- {
- if(xPlan[i].nlrchange == 1)
- {
- mapdata[j]->roadMode = 14;
- }
- if(xPlan[i].nlrchange == 2)
- {
- mapdata[j]->roadMode = 15;
- }
- if(j <=0)break;
- }
- }
- }
- data->gps_lat = gps_lat;
- data->gps_lat_avoidleft = gps_lat_avoidleft;
- data->gps_lat_avoidright = gps_lat_avoidright;
- data->gps_lng = gps_lon;
- data->gps_lng_avoidleft = gps_lon_avoidleft;
- data->gps_lng_avoidright = gps_lon_avoidright;
- data->ins_heading_angle = gps_heading;
- data->gps_x = gps_x;
- data->gps_x_avoidleft = gps_x_avoidleft;
- data->gps_x_avoidright = gps_x_avoidright;
- data->gps_y = gps_y;
- data->gps_y_avoidleft = gps_y_avoidleft;
- data->gps_y_avoidright = gps_y_avoidright;
- pmappoint->set_mbnoavoid(xPlan[i].mbNoavoid);
- pmappoint->set_mfcurvature(xPlan[i].mfCurvature);
- // CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
- // data->gps_lng,data->ins_heading_angle);
- // CalcLatLon(glat0,glon0,xPlan[i].mx_left,xPlan[i].my_left,
- // data->gps_lat_avoidleft,data->gps_lng_avoidleft);
- // CalcLatLon(glat0,glon0,xPlan[i].mx_right,xPlan[i].my_right,
- // data->gps_lat_avoidright,data->gps_lng_avoidright);
- data->index = i;
- data->speed = xPlan[i].speed;
- // ZBGaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
- // GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
- // GaussProjCal(data->gps_lng_avoidleft,data->gps_lat_avoidleft,&data->gps_x_avoidleft,&data->gps_y_avoidleft);
- // GaussProjCal(data->gps_lng_avoidright,data->gps_lat_avoidright,&data->gps_x_avoidright,&data->gps_y_avoidright);
- givlog->verbose(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
- data->gps_lng,data->ins_heading_angle);
- data->roadOri = xPlan[i].mnLaneori;
- data->roadSum = xPlan[i].mnLaneTotal;
- data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
- data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
- data->mfLaneWidth = xPlan[i].mWidth;
- data->mfRoadWidth = xPlan[i].mfRoadWidth;
- data->mbInLaneAvoid = xPlan[i].bInlaneAvoid;
- if(xPlan[i].mbBoringRoad)
- {
- data->roadOri = 0;
- data->roadSum = 2;
- pmappoint->set_roadori(0);
- pmappoint->set_roadsum(2);
- }
- data->mbnoavoid = xPlan[i].mbNoavoid;
- if(data->mbnoavoid)
- {
- qDebug("no avoid i = %d",i);
- }
- data->mfCurvature = xPlan[i].mfCurvature;
- data->mode2 = xPlan[i].nSignal;
- if(data->mode2 == 3000)
- {
- int k;
- for(k=(mapdata.size()-1);k>(mapdata.size()-150);k--)
- {
- if(k<0)break;
- if((mapdata.at(k)->mode2 != -1)&&(mapdata.at(k)->mode2 !=3000))
- {
- continue;
- }
- mapdata.at(k)->mode2 = 3000;
- }
- }
- if(data->mode2 == 1000001)
- {
- int k;
- for(k=(mapdata.size()-1);k>(mapdata.size()-10);k--)
- {
- if(k<0)break;
- if((mapdata.at(k)->mode2 != -1)&&(mapdata.at(k)->mode2 !=1000001))
- {
- continue;
- }
- mapdata.at(k)->mode2 = 1000001;
- }
- }
- pmappoint->set_mode2(data->mode2);
- pmappoint->set_rel_x(xPlan[i].x);
- pmappoint->set_rel_y(xPlan[i].y);
- pmappoint->set_rel_z(0);
- pmappoint->set_rel_yaw(xPlan[i].hdg);
- pmappoint->set_laneid(-1);
- pmappoint->set_roadid(xPlan[i].nRoadID);
- #ifdef BOAVOID
- if(isboringroad(xPlan[i].nRoadID))
- {
- const int nrangeavoid = 300;
- if((i+(nrangeavoid + 10))<nSize)
- {
- double fhdg1 = xPlan[i].hdg;
- bool bavoid = true;
- // int k;
- // for(k=0;k<=10;k++)
- // {
- // double fhdg5 = xPlan[i+nrangeavoid*k/10].hdg;
- // double fhdgdiff1 = fhdg5 - fhdg1;
- // while(fhdgdiff1<0)fhdgdiff1 = fhdgdiff1 + 2.0*M_PI;
- // if((fhdgdiff1>(M_PI/3.0))&&(fhdgdiff1<(5.0*M_PI/3.0)))
- // {
- // bavoid = false;
- // break;
- // }
- // }
- if(bavoid)
- {
- data->roadSum = 2;
- data->roadOri = 0;
- }
- }
- else
- {
- int a = 1;
- a++;
- }
- }
- #endif
- mapdata.push_back(data);
- // char strline[255];
- // // snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%11.3f\t%d\t%d\t%d\t%d\t%d\t%d\t%11.7f\n",
- // // i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,data->roadOri,data->roadSum,data->mode2,data->mfCurvature);
- // snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\t%d\n",
- // i,data->gps_lng,data->gps_lat,0,0,data->ins_heading_angle,0,0,data->roadSum,data->roadOri,data->mode2);
- // xfile.write(strline);
- }
- for(int j=0;j<nSize;j++)
- {
- char strline[255];
- snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\n",
- j,mapdata.at(j)->gps_lng,mapdata.at(j)->gps_lat,0,0,mapdata.at(j)->ins_heading_angle,0,0,mapdata.at(j)->roadSum,mapdata.at(j)->roadOri);
- xfile.write(strline);
- //mapttrace1
- char strline_1[255];
- snprintf(strline_1,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\t%d\n",
- j,mapdata.at(j)->gps_lng,mapdata.at(j)->gps_lat,0,0,mapdata.at(j)->ins_heading_angle,0,0,mapdata.at(j)->roadSum,mapdata.at(j)->roadOri,mapdata.at(j)->mode2);
- xfile_1.write(strline_1);
- }
- xfile.close();
- xfile_1.close();
- ShareMap(mapdata);
- #ifdef TESTSPEEDPLAN
- getPlanSpeed(mapdata);
- #endif
- ShareMapGlobal(xPlan);
- int nnewmapsize = xtrace.ByteSize();
- std::shared_ptr<char> str_ptr = std::shared_ptr<char>(new char[nnewmapsize]);
- if(xtrace.SerializeToArray(str_ptr.get(),nnewmapsize))
- {
- iv::modulecomm::ModuleSendMsg(gpanewtrace ,str_ptr.get(),nnewmapsize);
- }
- else
- {
- std::cout<<" new trace map serialize fail."<<std::endl;
- }
- s = 1;
- }
- void MultiStationPlan(iv::v2x::v2x * pxv2x,double fsrclat,double fsrclon,double fsrcheading,int nlane)
- {
- std::vector<PlanPoint> xPlan;
- int i;
- double fLastHdg = 0;
- int ndeflane =nlane;
- for(i=0;i<pxv2x->stgps_size();i++)
- {
- double x_src,y_src,x_dst,y_dst;
- if(i==0)
- {
- CalcXY(glat0,glon0,ghead0,fsrclat,fsrclon,x_src,y_src);
- }
- else
- {
- CalcXY(glat0,glon0,ghead0,pxv2x->stgps(i-1).lat(),pxv2x->stgps(i-1).lon(),x_src,y_src);
- }
- CalcXY(glat0,glon0,ghead0,pxv2x->stgps(i).lat(),pxv2x->stgps(i).lon(),x_dst,y_dst);
- std::vector<PlanPoint> xPlanPart;
- double s;
- // x_src = -5;y_src = 6;
- // x_dst = -60;y_src = -150;
- int nRtn = -1;
- if(i==0)
- {
- nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,(90 - fsrcheading)*M_PI/180.0,x_dst,y_dst,s,30.0,100.0,ndeflane,xPlanPart);
- }
- else
- {
- nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,fLastHdg,x_dst,y_dst,s,30.0,100.0,ndeflane,xPlanPart);
- }
- if(nRtn < 0)
- {
- qDebug("plan fail.");
- return;
- }
- int j;
- for(j=0;j<xPlanPart.size();j++)xPlan.push_back(xPlanPart.at(j));
- fLastHdg = xPlanPart.at(xPlanPart.size()-1).hdg;
- }
- int nSize = xPlan.size();
- std::vector<iv::GPSData> mapdata;
- QFile xfile;
- QString strpath;
- strpath = getenv("HOME");
- strpath = strpath + "/map/maptrace.txt";
- xfile.setFileName(strpath);
- xfile.open(QIODevice::ReadWrite);
- for(i=0;i<nSize;i++)
- {
- iv::GPSData data(new iv::GPS_INS);
- CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
- data->gps_lng,data->ins_heading_angle);
- data->index = i;
- data->speed = xPlan[i].speed;
- // ZBGaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
- GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
- givlog->verbose(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
- data->gps_lng,data->ins_heading_angle);
- // data->roadSum = 1;
- // data->roadMode = 0;
- // data->roadOri = 0;
- // if(xPlan[i].lanmp == -1)data->roadMode = 15;
- // if(xPlan[i].lanmp == 1)data->roadMode = 14;
- data->roadOri = xPlan[i].mnLaneori;
- data->roadSum = xPlan[i].mnLaneTotal;
- data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
- data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
- data->mfLaneWidth = xPlan[i].mWidth;
- data->mfRoadWidth = xPlan[i].mfRoadWidth;
- data->mode2 = xPlan[i].nSignal;
- if(data->mode2 == 3000)
- {
- int k;
- for(k=(mapdata.size()-1);k>(mapdata.size()-150);k--)
- {
- if(k<0)break;
- mapdata.at(k)->mode2 = 3000;
- }
- }
- mapdata.push_back(data);
- char strline[255];
- snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\n",
- i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,0,0);
- xfile.write(strline);
- }
- xfile.close();
- ShareMap(mapdata);
- }
- void ListenCmd(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
- {
- if(nSize<sizeof(xodrobj))
- {
- std::cout<<"ListenCmd small."<<std::endl;
- return;
- }
- xodrobj xo;
- memcpy(&xo,strdata,sizeof(xodrobj));
- givlog->debug("lat is %f", xo.flat);
- xo.fhgdsrc = gsrc.fhgdsrc;
- xo.flatsrc = gsrc.flatsrc;
- xo.flonsrc = gsrc.flonsrc;
- SetPlan(xo);
- }
- void ListenV2X(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
- {
- iv::v2x::v2x xv2x;
- if(!xv2x.ParseFromArray(strdata,nSize))
- {
- givlog->warn("ListernV2X Parse Error.");
- std::cout<<"ListenV2X Parse Error."<<std::endl;
- return;
- }
- if(xv2x.stgps_size()<1)
- {
- givlog->debug("ListenV2X no gps station.");
- std::cout<<"ListenV2X no gps station."<<std::endl;
- return;
- }
- MultiStationPlan(&xv2x,gsrc.flatsrc,gsrc.flonsrc,gsrc.fhgdsrc,1);
- }
- void ListenSrc(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
- {
- if(nSize<sizeof(xodrobj))
- {
- givlog->warn("ListenSrc small");
- std::cout<<"ListenSrc small."<<std::endl;
- return;
- }
- memcpy(&gsrc,strdata,sizeof(xodrobj));
- givlog->debug("src hdg is %f", gsrc.fhgdsrc);
- std::cout<<"src hdg is "<<gsrc.fhgdsrc<<std::endl;
- }
- void UpdateGPSIMU(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
- {
- iv::gps::gpsimu xgpsimu;
- if(!xgpsimu.ParseFromArray(strdata,nSize))
- {
- givlog->warn("ADCIntelligentVehicle::UpdateGPSIMU parse error. nSize is %d",nSize);
- return;
- }
- xodrobj xo;
- xo.fhgdsrc = xgpsimu.heading();
- xo.flatsrc = xgpsimu.lat();
- xo.flonsrc = xgpsimu.lon();
- gsrc = xo;
- givlog->debug("src hdg is %f", gsrc.fhgdsrc);
- std::cout<<"src hdg is "<<gsrc.fhgdsrc<<std::endl;
- }
- void ExitFunc()
- {
- // gApp->quit();
- iv::modulecomm::Unregister(gpasimple);
- iv::modulecomm::Unregister(gpav2x);
- iv::modulecomm::Unregister(gpagps);
- iv::modulecomm::Unregister(gpasrc);
- iv::modulecomm::Unregister(gpmap);
- iv::modulecomm::Unregister(gpa);
- std::cout<<"driver_map_xodrload exit."<<std::endl;
- gApp->quit();
- std::this_thread::sleep_for(std::chrono::milliseconds(100));
- // std::this_thread::sleep_for(std::chrono::milliseconds(900));
- }
- void signal_handler(int sig)
- {
- if(sig == SIGINT)
- {
- ExitFunc();
- }
- }
- void ProcROIReq(std::shared_ptr<char> pstr_req,const int nreqsize,std::shared_ptr<char> & pstr_res,int & nressize)
- {
- (void)pstr_req;
- (void)nreqsize;
- std::shared_ptr<iv::roi::request> pstr_roireq = std::shared_ptr<iv::roi::request>(new iv::roi::request);
- if(pstr_roireq->ParseFromArray(pstr_req.get(),nreqsize))
- {
- std::shared_ptr<iv::roi::resultarray> pstr_roires;
- gsrx.GetROI(pstr_roireq,pstr_roires);
- int nbytesize = pstr_roires->ByteSize();
- pstr_res = std::shared_ptr<char>(new char[nbytesize]);
- if(pstr_roires->SerializeToArray(pstr_res.get(),nbytesize))
- {
- nressize = nbytesize;
- std::cout<<"return res."<<std::endl;
- return;
- }
- else
- {
- std::cout<<" ProcROIReq fail serizlizetoarray"<<std::endl;
- }
- }
- else
- {
- std::cout<<" ProcROIReq parse pstr_req fail."<<std::endl;
- return;
- }
- }
- int main(int argc, char *argv[])
- {
- showversion("driver_map_xodrload");
- QCoreApplication a(argc, argv);
- gApp = &a;
- RegisterIVBackTrace();
- gfault = new iv::Ivfault("driver_map_xodrload");
- givlog = new iv::Ivlog("driver_map_xodrload");
- std::string strmapth,strparapath;
- if(argc<3)
- {
- // strmapth = "./map.xodr";
- strmapth = getenv("HOME");
- strmapth = strmapth + "/map/map.xodr";
- // strmapth = "/home/yuchuli/1226.xodr";
- strparapath = "./driver_map_xodrload.xml";
- }
- else
- {
- strmapth = argv[1];
- strparapath = argv[2];
- }
- iv::xmlparam::Xmlparam xp(strparapath);
- xp.GetParam(std::string("he"),std::string("1"));
- std::string strlat0 = xp.GetParam("lat0","39");
- std::string strlon0 = xp.GetParam("lon0","117.0");
- std::string strhdg0 = xp.GetParam("hdg0","360.0");
- std::string strgpsmsg = xp.GetParam("gpsmsg","hcp2_gpsimu");
- std::string strv2xmsg = xp.GetParam("v2xmsg","v2x");
- std::string strvehiclewidth = xp.GetParam("vehiclewidth","2.0");
- std::string strextendmap = xp.GetParam("extendmap","false");
- std::string strsideenable = xp.GetParam("sideenable","false");
- std::string strsidelaneenable = xp.GetParam("sidelaneenable","false");
- gstrcdata = xp.GetParam("cdata","");
- std::cout<<" cdata: "<<gstrcdata.data()<<std::endl;
- #ifdef USE_TMERS
- if(gstrcdata.length()>3)
- {
- C = proj_context_create();//创建多线程,由于本示例为单线程,此处为展示作用
- P = proj_create_crs_to_crs (C,
- "WGS84",
- "+proj=tmerc +ellps=WGS84 +datum=WGS84 +units=m +lat_0=28.3252659663377 +lon_0=117.810536087614 +no_defs", /* or EPSG:32632 */
- NULL);
- // P = proj_create(C,"+proj=tmerc +ellps=WGS84 +datum=WGS84 +units=m +lat_0=28.3252659663377 +lon_0=117.810536087614 +no_defs");
- if (0 == P) {
- std::cout << "Failed to create transformation object." << stderr << std::endl;
- return 1;
- }//如果P中两个投影的字符串不符合proj定义,提示转换失败
- norm = proj_normalize_for_visualization(C, P);
- if (0 == norm) {
- fprintf(stderr, "Failed to normalize transformation object.\n");
- return 1;
- }
- proj_destroy(P);
- P = norm;
- }
- #endif
- glat0 = atof(strlat0.data());
- glon0 = atof(strlon0.data());
- ghead0 = atof(strhdg0.data());
- gvehiclewidth = atof(strvehiclewidth.data());
- if(strextendmap == "true")
- {
- gbExtendMap = true;
- }
- else
- {
- gbExtendMap = false;
- }
- if(strsideenable == "true")
- {
- gbSideEnable = true;
- }
- if(strsidelaneenable == "true")
- {
- gbSideLaneEnable = true;
- }
- LoadXODR(strmapth);
- iv::service::Server serviceroi("ServiceROI",ProcROIReq);
- (void)serviceroi;
- gpmap = iv::modulecomm::RegisterSend("tracemap",20000000,1);
- gpasimple = iv::modulecomm::RegisterSend("simpletrace",100000,1);
- gpanewtrace = iv::modulecomm::RegisterSend("newtracemap",20000000,1);
- gpamapglobal = iv::modulecomm::RegisterSend("mapglobal",20000000,1);
- gpa = iv::modulecomm::RegisterRecv("xodrreq",ListenCmd);
- gpasrc =iv::modulecomm::RegisterRecv("xodrsrc",ListenSrc);
- gpagps = iv::modulecomm::RegisterRecv(strgpsmsg.data(),UpdateGPSIMU);
- gpav2x = iv::modulecomm::RegisterRecv(strv2xmsg.data(),ListenV2X);
- double x_src,y_src,x_dst,y_dst;
- x_src = -26;y_src = 10;
- x_dst = -50;y_dst = -220;
- x_src = 0;y_src = 0;
- x_dst = -23;y_dst = -18;
- x_dst = 21;y_dst =-21;
- x_dst =5;y_dst = 0;
- x_src = -20; y_src = -1000;
- x_dst = 900; y_dst = -630;
- // x_dst = 450; y_dst = -640;
- // x_dst = -190; y_dst = -690;
- // x_src = 900; y_src = -610;
- // x_dst = -100; y_dst = -680;
- std::vector<PlanPoint> xPlan;
- double s;
- // int nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,3.14,x_dst,y_dst,s,30.0,100.0,1,xPlan);
- // ToGPSTrace(xPlan);
- // double lat = 39.1443880;
- // double lon = 117.0812543;
- // xodrobj xo;
- // xo.fhgdsrc = 340;
- // xo.flatsrc = lat; xo.flonsrc = lon;
- // xo.flat = 39.1490196;
- // xo.flon = 117.0806979;
- // xo.lane = 1;
- // SetPlan(xo);
- // void * pivexit = iv::ivexit::RegIVExitCall(ExitFunc);
- signal(SIGINT,signal_handler);
- int nrc = a.exec();
- std::cout<<"driver_map_xodr app exit. code :"<<nrc<<std::endl;
- return nrc;
- }
|