main.cpp 47 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606
  1. #include <QCoreApplication>
  2. #include <math.h>
  3. #include <string>
  4. #include <thread>
  5. #include <QFile>
  6. #include "OpenDrive/OpenDrive.h"
  7. #include "OpenDrive/OpenDriveXmlParser.h"
  8. #include "globalplan.h"
  9. #include "gpsimu.pb.h"
  10. #include "mapdata.pb.h"
  11. #include "mapglobal.pb.h"
  12. #include "v2x.pb.h"
  13. #include "modulecomm.h"
  14. #include "xmlparam.h"
  15. #include "gps_type.h"
  16. #include "xodrdijkstra.h"
  17. #include "gnss_coordinate_convert.h"
  18. #include "ivexit.h"
  19. #include "ivversion.h"
  20. #include "ivbacktrace.h"
  21. #include <signal.h>
  22. #include "service_roi_xodr.h"
  23. #include "ivservice.h"
  24. #ifdef USE_TMERS
  25. #include "proj.h"
  26. //#include "projects.h"
  27. PJ_CONTEXT *C;//用于处理多线程程序
  28. PJ *P;//初始化投影目标
  29. PJ *norm;//初始化投影目标
  30. #endif
  31. OpenDrive mxodr;
  32. xodrdijkstra * gpxd;
  33. bool gmapload = false;
  34. double glat0,glon0,ghead0;
  35. double gvehiclewidth = 2.0;
  36. bool gbExtendMap = true;
  37. static bool gbSideEnable = false;
  38. static bool gbSideLaneEnable = false;
  39. static std::string gstrcdata;
  40. static void * gpa;
  41. static void * gpasrc;
  42. static void * gpmap;
  43. static void * gpagps;
  44. static void * gpasimple;
  45. static void * gpav2x;
  46. static void * gpanewtrace;
  47. static void * gpamapglobal;
  48. iv::Ivfault *gfault = nullptr;
  49. iv::Ivlog *givlog = nullptr;
  50. static QCoreApplication * gApp;
  51. service_roi_xodr gsrx;
  52. namespace iv {
  53. struct simpletrace
  54. {
  55. double gps_lat = 0;//纬度
  56. double gps_lng = 0;//经度
  57. double gps_x = 0;
  58. double gps_y = 0;
  59. double gps_z = 0;
  60. double ins_heading_angle = 0; //航向角
  61. };
  62. }
  63. /**
  64. *
  65. *
  66. *
  67. *
  68. * */
  69. bool LoadXODR(std::string strpath)
  70. {
  71. OpenDriveXmlParser xp(&mxodr);
  72. xp.ReadFile(strpath);
  73. std::cout<<"road cout is "<<mxodr.GetRoadCount()<<std::endl;
  74. if(mxodr.GetRoadCount() < 1)
  75. {
  76. gmapload = true;
  77. return false;
  78. }
  79. xodrdijkstra * pxd = new xodrdijkstra(&mxodr);
  80. gpxd = pxd;
  81. // std::vector<int> xpath = pxd->getpath(10001,2,30012,2);
  82. // pxd->getgpspoint(10001,2,30012,2,xpath);
  83. int i;
  84. double nlenth = 0;
  85. int nroadsize = mxodr.GetRoadCount();
  86. for(i=0;i<nroadsize;i++)
  87. {
  88. Road * px = mxodr.GetRoad(i);
  89. nlenth = nlenth + px->GetRoadLength();
  90. int bloksize = px->GetGeometryBlockCount();
  91. if(px->GetGeometryBlock(0)->GetGeometryAt(0)->GetGeomType() == 4)
  92. {
  93. GeometryParamPoly3 * p = (GeometryParamPoly3 *) px->GetGeometryBlock(0)->GetGeometryAt(0);
  94. double a = p->GetuA();
  95. a = p->GetuB();
  96. a = p->GetuC();
  97. a = p->GetuD();
  98. a = p->GetvA();
  99. }
  100. }
  101. // void Header::GetAllParams(unsigned short int &revMajor, unsigned short int &revMinor, string &name, float &version, string &date,
  102. // double &north, double &south, double &east,double &west,double &lat0,double &lon0, double & hdg0)
  103. unsigned short int revMajor,revMinor;
  104. std::string name,date;
  105. float version;
  106. double north,south,east,west,lat0,lon0,hdg0;
  107. if(mxodr.GetHeader() != 0)
  108. {
  109. mxodr.GetHeader()->GetAllParams(revMajor,revMinor,name,version,date,north,south,east,west,lat0,lon0,hdg0);
  110. glat0 = lat0;
  111. glon0 = lon0;
  112. }
  113. Road * proad1 = mxodr.GetRoad(0);
  114. givlog->info("road name is %s",proad1->GetRoadName().data());
  115. std::cout<<" road name is "<<proad1->GetRoadName()<<std::endl;
  116. gsrx.SetXODR(&mxodr);
  117. }
  118. class roadx
  119. {
  120. public:
  121. roadx * para;
  122. std::vector<roadx> child;
  123. int nlen;
  124. };
  125. #define EARTH_RADIUS 6370856.0
  126. //从1到2的距离和方向
  127. int CalcDisAngle(double lat1,double lon1,double lat2,double lon2,double * pLatDis,double * pLonDis,double * pDis,double * pangle)
  128. {
  129. double a,b;
  130. double LonDis,LatDis;
  131. double LonRadius;
  132. double Dis;
  133. double angle;
  134. if((lat1 == lat2)&&(lon1 == lon2))return -1;
  135. LonRadius = EARTH_RADIUS * cos(lat2/(180.0/M_PI));
  136. a = (EARTH_RADIUS * M_PI*2.0/360.0)/(100000.0);
  137. b = lat2 - lat1; b = b*100000.0;
  138. LatDis = a*b;
  139. a = (LonRadius * M_PI*2.0/360.0)/100000.0;
  140. b = lon2 - lon1; b = b*100000.0;
  141. LonDis = a*b;
  142. Dis = sqrt(LatDis*LatDis + LonDis *LonDis);
  143. angle = acos(fabs(LonDis)/Dis);
  144. angle = angle * 180.0/M_PI;
  145. if(LonDis > 0)
  146. {
  147. if(LatDis > 0)angle = 90.0 - angle;
  148. else angle= 90.0+angle;
  149. }
  150. else
  151. {
  152. if(LatDis > 0)angle = 270.0+angle;
  153. else angle = 270.0-angle;
  154. }
  155. if(pLatDis != 0)*pLatDis = LatDis;
  156. if(pLonDis != 0)*pLonDis = LonDis;
  157. if(pDis != 0)*pDis = Dis;
  158. if(pangle != 0)*pangle = angle;
  159. }
  160. //==========================================================
  161. //高斯投影由经纬度(Unit:DD)反算大地坐标(含带号,Unit:Metres)
  162. //void GaussProjCal(double longitude, double latitude, double *X, double *Y)
  163. //{
  164. // int ProjNo = 0; int ZoneWide; ////带宽
  165. // double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
  166. // double a, f, e2, ee, NN, T, C, A, M, iPI;
  167. // iPI = 0.0174532925199433; ////3.1415926535898/180.0;
  168. // ZoneWide = 6; ////6度带宽
  169. // a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
  170. // ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
  171. // ProjNo = (int)(longitude / ZoneWide);
  172. // longitude0 = ProjNo * ZoneWide + ZoneWide / 2;
  173. // longitude0 = longitude0 * iPI;
  174. // latitude0 = 0;
  175. // longitude1 = longitude * iPI; //经度转换为弧度
  176. // latitude1 = latitude * iPI; //纬度转换为弧度
  177. // e2 = 2 * f - f * f;
  178. // ee = e2 * (1.0 - e2);
  179. // NN = a / sqrt(1.0 - e2 * sin(latitude1)*sin(latitude1));
  180. // T = tan(latitude1)*tan(latitude1);
  181. // C = ee * cos(latitude1)*cos(latitude1);
  182. // A = (longitude1 - longitude0)*cos(latitude1);
  183. // 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
  184. // *e2 / 1024)*sin(2 * latitude1)
  185. // + (15 * e2*e2 / 256 + 45 * e2*e2*e2 / 1024)*sin(4 * latitude1) - (35 * e2*e2*e2 / 3072)*sin(6 * latitude1));
  186. // 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);
  187. // yval = M + NN * tan(latitude1)*(A*A / 2 + (5 - T + 9 * C + 4 * C*C)*A*A*A*A / 24
  188. // + (61 - 58 * T + T * T + 600 * C - 330 * ee)*A*A*A*A*A*A / 720);
  189. // X0 = 1000000L * (ProjNo + 1) + 500000L;
  190. // Y0 = 0;
  191. // xval = xval + X0; yval = yval + Y0;
  192. // *X = xval;
  193. // *Y = yval;
  194. //}
  195. #include <math.h>
  196. static void OffLngLat(double fLat0,double fLng0,double & fLat,double & fLng,double fHeading,double x,double y)
  197. {
  198. double fxdiff,fydiff;
  199. double xoff = y*(-1);
  200. double yoff = x;
  201. fxdiff = 0+xoff * cos(fHeading*M_PI/180.0)+ yoff*sin(fHeading*M_PI/180.0); //East
  202. fydiff = 0-xoff * sin(fHeading*M_PI/180.0)+ yoff*cos(fHeading*M_PI/180.0); //South
  203. double fEarthRadius = 6378245.0;
  204. double ns1d = fEarthRadius*2*M_PI/360.0;
  205. double fewRadius = fEarthRadius * cos(fLat0*M_PI/180.0);
  206. double ew1d = fewRadius * 2*M_PI/360.0;
  207. fLat = fLat0 + fydiff/ns1d;
  208. fLng = fLng0 + fxdiff/ew1d;
  209. }
  210. void CalcXY(const double lat0,const double lon0,const double hdg0,
  211. const double lat,const double lon,
  212. double & x,double & y)
  213. {
  214. double x0,y0;
  215. GaussProjCal(lon0,lat0,&x0,&y0);
  216. GaussProjCal(lon,lat,&x,&y);
  217. x = x - x0;
  218. y = y- y0;
  219. // double ang,dis;
  220. // CalcDisAngle(lat0,lon0,lat,lon,0,0,&dis,&ang);
  221. // double xang = hdg0 - ang;
  222. // while(xang<0)xang = xang + 360.0;
  223. // x = dis * cos(xang * M_PI/180.0);
  224. // y = dis * sin(xang * M_PI/180.0);
  225. }
  226. //void CalcLatLon(const double lat0,const double lon0,const double hdg0,
  227. // const double x,const double y,const double xyhdg,
  228. // double &lat,double & lon, double & hdg)
  229. //{
  230. // OffLngLat(lat0,lon0,lat,lon,hdg0,x,y);
  231. // hdg = hdg0 - xyhdg * 180.0/M_PI;
  232. // while(hdg < 0)hdg = hdg + 360;
  233. // while(hdg >= 360)hdg = hdg - 360;
  234. //}
  235. void CalcLatLon(const double lat0,const double lon0,
  236. const double x,const double y,
  237. double &lat,double & lon)
  238. {
  239. double x0,y0;
  240. GaussProjCal(lon0,lat0,&x0,&y0);
  241. double x_gps,y_gps;
  242. x_gps = x0+x;
  243. y_gps = y0+y;
  244. GaussProjInvCal(x_gps,y_gps,&lon,&lat);
  245. }
  246. void CalcLatLon(const double lat0,const double lon0,const double hdg0,
  247. const double x,const double y,const double xyhdg,
  248. double &lat,double & lon, double & hdg)
  249. {
  250. double x0,y0;
  251. GaussProjCal(lon0,lat0,&x0,&y0);
  252. double x_gps,y_gps;
  253. x_gps = x0+x;
  254. y_gps = y0+y;
  255. GaussProjInvCal(x_gps,y_gps,&lon,&lat);
  256. // hdg = hdg0 -xyhdg * 270/M_PI;
  257. hdg = 90 - xyhdg* 180.0/M_PI;
  258. // OffLngLat(lat0,lon0,lat,lon,hdg0,x,y);
  259. // hdg = hdg0 - xyhdg * 180.0/M_PI;
  260. while(hdg < 0)hdg = hdg + 360;
  261. while(hdg >= 360)hdg = hdg - 360;
  262. #ifdef USE_TMERS
  263. if(gstrcdata.length()>3)
  264. {
  265. PJ_COORD cp;//初始化投影坐标
  266. cp.enu.e = x;
  267. cp.enu.n = y;
  268. cp = proj_trans(P, PJ_INV, cp);//xy坐标转化为经纬度坐标
  269. lon = cp.lp.lam;
  270. lat = cp.lp.phi;
  271. }
  272. #endif
  273. }
  274. class xodrobj
  275. {
  276. public:
  277. double flatsrc;
  278. double flonsrc;
  279. double fhgdsrc;
  280. double flat;
  281. double flon;
  282. int lane;
  283. };
  284. static xodrobj gsrc;
  285. void ShareMapGlobal(std::vector<PlanPoint> & xvectorPlan)
  286. {
  287. iv::map::mapglobal xglobal;
  288. unsigned int i;
  289. unsigned int nsize = static_cast<unsigned int >(xvectorPlan.size());
  290. for(i=0;i<nsize;i++)
  291. {
  292. iv::map::pointglobal * ppoint = xglobal.add_point();
  293. double gps_lon,gps_lat,gps_heading;
  294. CalcLatLon(glat0,glon0,ghead0,xvectorPlan[i].x,xvectorPlan[i].y,xvectorPlan[i].hdg,gps_lat,
  295. gps_lon,gps_heading);
  296. ppoint->set_gps_lat(gps_lat);
  297. ppoint->set_gps_lng(gps_lon);
  298. ppoint->set_ins_heading_angle(gps_heading);
  299. double gps_x,gps_y;
  300. GaussProjCal(gps_lon,gps_lat,&gps_x,&gps_y);
  301. ppoint->set_gps_x(gps_x);
  302. ppoint->set_gps_y(gps_y);
  303. ppoint->set_gps_z(0);
  304. ppoint->set_mfcurvature(xvectorPlan[i].mfCurvature);
  305. ppoint->set_mfdistolaneleft(xvectorPlan[i].mfDisToLaneLeft);
  306. ppoint->set_mfdistoroadleft(xvectorPlan[i].mfDisToRoadLeft);
  307. ppoint->set_mflanewidth(xvectorPlan[i].mWidth);
  308. ppoint->set_mfroadwidth(xvectorPlan[i].mfRoadWidth);
  309. ppoint->set_speed(xvectorPlan[i].speed);
  310. unsigned int nlanecount = static_cast<unsigned int>(xvectorPlan[i].mVectorLaneWidth.size());
  311. unsigned int j;
  312. for(j=0;j<nlanecount;j++)
  313. {
  314. ppoint->add_mfvectorlanewidth(xvectorPlan[i].mVectorLaneWidth[j]);
  315. }
  316. ppoint->set_mlanecount(xvectorPlan[i].mLaneCount);
  317. ppoint->set_mlanecur(xvectorPlan[i].mLaneCur);
  318. }
  319. int bytesize = static_cast<int>(xglobal.ByteSize()) ;
  320. std::shared_ptr<char> pstr_ptr = std::shared_ptr<char>(new char[bytesize]);
  321. if(xglobal.SerializePartialToArray(pstr_ptr.get(),bytesize))
  322. {
  323. iv::modulecomm::ModuleSendMsg(gpamapglobal,pstr_ptr.get(),static_cast<unsigned int>(bytesize) );
  324. }
  325. else
  326. {
  327. std::cout<<" ShareMapGlobal Serialzie Fail."<<std::endl;
  328. }
  329. }
  330. void ShareMap(std::vector<iv::GPSData> navigation_data)
  331. {
  332. if(navigation_data.size()<1)return;
  333. iv::GPS_INS x;
  334. x = *(navigation_data.at(0));
  335. char * data = new char[sizeof(iv::GPS_INS)*navigation_data.size()];
  336. int gpssize = sizeof(iv::GPS_INS);
  337. int i;
  338. for(i=0;i<navigation_data.size();i++)
  339. {
  340. x = *(navigation_data.at(i));
  341. memcpy(data+i*gpssize,&x,gpssize);
  342. }
  343. iv::modulecomm::ModuleSendMsg(gpmap,data,navigation_data.size()*gpssize);
  344. int nsize = 100;
  345. int nstep = 1;
  346. if(navigation_data.size() < 100)
  347. {
  348. nsize = navigation_data.size();
  349. }
  350. else
  351. {
  352. nstep = navigation_data.size()/100;
  353. }
  354. iv::simpletrace psim[100];
  355. for(i=0;i<nsize;i++)
  356. {
  357. x = *(navigation_data.at(i*nstep));
  358. psim[i].gps_lat = x.gps_lat;
  359. psim[i].gps_lng = x.gps_lng;
  360. psim[i].gps_z = x.gps_z;
  361. psim[i].gps_x = x.gps_x;
  362. psim[i].gps_y = x.gps_y;
  363. psim[i].ins_heading_angle = x.ins_heading_angle;
  364. }
  365. if(navigation_data.size()>100)
  366. {
  367. int nlast = 99;
  368. x = *(navigation_data.at(navigation_data.size()-1));
  369. psim[nlast].gps_lat = x.gps_lat;
  370. psim[nlast].gps_lng = x.gps_lng;
  371. psim[nlast].gps_z = x.gps_z;
  372. psim[nlast].gps_x = x.gps_x;
  373. psim[nlast].gps_y = x.gps_y;
  374. psim[nlast].ins_heading_angle = x.ins_heading_angle;
  375. }
  376. iv::modulecomm::ModuleSendMsg(gpasimple,(char *)psim,nsize * sizeof(iv::simpletrace));
  377. delete data;
  378. }
  379. static void ToGPSTrace(std::vector<PlanPoint> xPlan)
  380. {
  381. // double x_src,y_src,x_dst,y_dst;
  382. // x_src = -26;y_src = 10;
  383. // x_dst = -50;y_dst = -220;
  384. int i;
  385. int nSize = xPlan.size();
  386. std::vector<iv::GPSData> mapdata;
  387. QFile xfile;
  388. QString strpath;
  389. strpath = getenv("HOME");
  390. strpath = strpath + "/map/maptrace.txt";
  391. xfile.setFileName(strpath);
  392. bool bFileOpen = xfile.open(QIODevice::ReadWrite);
  393. for(i=0;i<nSize;i++)
  394. {
  395. iv::GPSData data(new iv::GPS_INS);
  396. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  397. data->gps_lng,data->ins_heading_angle);
  398. data->index = i;
  399. data->speed = xPlan[i].speed;
  400. GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  401. givlog->debug(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  402. data->gps_lng,data->ins_heading_angle);
  403. data->roadSum = xPlan[i].mnLaneTotal;
  404. data->roadMode = 0;
  405. data->roadOri = xPlan[i].mnLaneori;
  406. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  407. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  408. data->mfLaneWidth = xPlan[i].mWidth;
  409. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  410. data->mnLaneChangeMark = xPlan[i].lanmp;
  411. if(xPlan[i].lanmp == -1)data->roadMode = 15;
  412. if(xPlan[i].lanmp == 1)data->roadMode = 14;
  413. mapdata.push_back(data);
  414. char strline[255];
  415. 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",
  416. i,data->gps_lng,data->gps_lat,0,0,data->ins_heading_angle,0,0,0,0);
  417. if(bFileOpen) xfile.write(strline);
  418. // 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;
  419. }
  420. if(bFileOpen)xfile.close();
  421. ShareMap(mapdata);
  422. }
  423. int avoidroadid[] = {10002,10019,10003,10098,10099,10063,10099,10100,10104,10110,10111};
  424. inline bool isboringroad(int nroadid)
  425. {
  426. int i;
  427. bool brtn = false;
  428. for(i=0;i<11;i++)
  429. {
  430. if(avoidroadid[i] == nroadid)
  431. {
  432. brtn = true;
  433. break;
  434. }
  435. }
  436. return brtn;
  437. }
  438. void CalcLaneSide(std::vector<PlanPoint> & xPlan)
  439. {
  440. const double fsidedis = 0.3;
  441. const int nChangePoint = 350;
  442. const int nStopPoint = 150;
  443. if(xPlan.size()<nChangePoint)return;
  444. int i;
  445. int nsize = xPlan.size();
  446. bool bChangeLane = false;
  447. for(i=(nsize-1);i>=(nsize - nStopPoint);i--)
  448. {
  449. double fMove = xPlan[i].mfRoadWidth - xPlan[i].mfDisToRoadLeft - (gvehiclewidth/2.0 + fsidedis);
  450. // double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
  451. double xold = xPlan[i].x;
  452. double yold = xPlan[i].y;
  453. xPlan[i].x = xold + fMove*cos(xPlan[i].hdg - M_PI/2.0);
  454. xPlan[i].y = yold + fMove*sin(xPlan[i].hdg - M_PI/2.0);
  455. xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fMove;
  456. if(fMove>2.0)
  457. {
  458. bChangeLane = true;
  459. }
  460. if(bChangeLane)
  461. xPlan[i].nlrchange = 2;
  462. }
  463. for(i=(nsize-nStopPoint-1);i>=(nsize - nChangePoint);i--)
  464. {
  465. double fMove = xPlan[i].mfRoadWidth - xPlan[i].mfDisToRoadLeft - (gvehiclewidth/2.0 + fsidedis);
  466. // double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
  467. double xold = xPlan[i].x;
  468. double yold = xPlan[i].y;
  469. double fRatio = 1.0 - ((nsize-nStopPoint) -i )*1.0/(nChangePoint-nStopPoint);
  470. xPlan[i].x = xold + fRatio*fMove*cos(xPlan[i].hdg - M_PI/2.0);
  471. xPlan[i].y = yold + fRatio*fMove*sin(xPlan[i].hdg - M_PI/2.0);
  472. xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fRatio*fMove;
  473. if(bChangeLane)xPlan[i].nlrchange = 2;
  474. }
  475. return;
  476. }
  477. void CalcSide(std::vector<PlanPoint> & xPlan)
  478. {
  479. const double fsidedis = 0.3;
  480. const int nChangePoint = 150;
  481. const int nStopPoint = 50;
  482. if(xPlan.size()<nChangePoint)return;
  483. bool bChange = true;
  484. int i;
  485. int nsize = xPlan.size();
  486. for(i=(nsize-1);i>=(nsize - nChangePoint);i--)
  487. {
  488. if(xPlan[i].mWidth<(2.0*(gvehiclewidth/2.0+fsidedis)))
  489. {
  490. std::cout<<" Because Lane is narrow, not change."<<std::endl;
  491. bChange = false;
  492. break;
  493. }
  494. }
  495. if(bChange == false)return;
  496. for(i=(nsize-1);i>=(nsize - nStopPoint);i--)
  497. {
  498. double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
  499. double xold = xPlan[i].x;
  500. double yold = xPlan[i].y;
  501. xPlan[i].x = xold + fMove*cos(xPlan[i].hdg - M_PI/2.0);
  502. xPlan[i].y = yold + fMove*sin(xPlan[i].hdg - M_PI/2.0);
  503. xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fMove;
  504. }
  505. for(i=(nsize-nStopPoint-1);i>=(nsize - nChangePoint);i--)
  506. {
  507. double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
  508. double xold = xPlan[i].x;
  509. double yold = xPlan[i].y;
  510. double fRatio = 1.0 - ((nsize-nStopPoint) -i )*1.0/(nChangePoint-nStopPoint);
  511. xPlan[i].x = xold + fRatio*fMove*cos(xPlan[i].hdg - M_PI/2.0);
  512. xPlan[i].y = yold + fRatio*fMove*sin(xPlan[i].hdg - M_PI/2.0);
  513. xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fRatio*fMove;
  514. }
  515. return;
  516. }
  517. #ifdef TESTSPEEDPLAN
  518. #include <math.h>
  519. #include <limits>
  520. double valuemin(double a,double b)
  521. {
  522. if(a<b)return a;
  523. return b;
  524. }
  525. int getPlanSpeed(std::vector<iv::GPSData> MapTrace)
  526. {
  527. int mode0to5count=0,mode0to18count=0,mode0to5countSum=0,mode0to18countSum=0,mode18count=0,mode18countSum=0,mode0to5flash=0,mode18flash=0;
  528. double straightSpeed=40;
  529. double straightCurveSpeed=30;
  530. double Curve_SmallSpeed=15;
  531. double Curve_LargeSpeed=8;
  532. std::vector<std::vector<double>> doubledata;
  533. doubledata.clear();
  534. for (int i = 0; i < MapTrace.size(); i++) { // 1225/14:25
  535. std::vector<double> temp;
  536. temp.clear();
  537. temp.push_back(0);temp.push_back(0);temp.push_back(0);temp.push_back(0);temp.push_back(0);//先push四个空量,然后就可以给量赋值了
  538. doubledata.push_back(temp);
  539. doubledata[i][0] = MapTrace.at(i)->gps_x;
  540. doubledata[i][1] = MapTrace.at(i)->gps_y;
  541. doubledata[i][2] = (MapTrace.at(i)->ins_heading_angle) / 180 * M_PI;
  542. doubledata[i][3]=0;
  543. doubledata[i][4]=0;
  544. }
  545. for(int i=0;i<doubledata.size();i++)
  546. {
  547. if((MapTrace[i]->mfCurvature>-0.02)&&(MapTrace[i]->mfCurvature<0.02)){
  548. MapTrace[i]->roadMode=5;
  549. }else if(((MapTrace[i]->mfCurvature>=0.02)&&(MapTrace[i]->mfCurvature<=0.16))||((MapTrace[i]->mfCurvature>=-0.16)&&(MapTrace[i]->mfCurvature<=-0.02))){
  550. MapTrace[i]->roadMode=18;
  551. }else if(((MapTrace[i]->mfCurvature>0.16))||((MapTrace[i]->mfCurvature<-0.16))){
  552. MapTrace[i]->roadMode=14;
  553. }
  554. }
  555. for(int i=0;i<MapTrace.size();i++)
  556. {
  557. if(MapTrace[i]->roadMode==0){
  558. doubledata[i][4]=straightSpeed;
  559. mode0to5count++;
  560. //mode0to18count++;
  561. mode18count=0;
  562. mode0to5flash=mode0to5count;
  563. }else if(MapTrace[i]->roadMode==5){
  564. doubledata[i][4]=straightCurveSpeed;
  565. mode0to5count++;
  566. //mode0to18count++;
  567. mode18count=0;
  568. mode0to5flash=mode0to5count;
  569. }else if(MapTrace[i]->roadMode==18){
  570. mode0to5countSum=mode0to5count;
  571. doubledata[i][4]=Curve_SmallSpeed;
  572. double brake_distance_double=(pow((straightCurveSpeed/3.6),2)-pow((Curve_SmallSpeed/3.6),2))*10/0.6;
  573. int brake_distance=(int)brake_distance_double;
  574. int step_count=0;
  575. if((i>brake_distance)&&(mode0to5countSum>brake_distance))
  576. {
  577. double step_speed=(straightCurveSpeed-Curve_SmallSpeed)/brake_distance;
  578. for(int j=i;j>i-brake_distance;j--){
  579. doubledata[j][4]=valuemin((Curve_SmallSpeed+step_count*step_speed),straightCurveSpeed);
  580. step_count++;
  581. }
  582. }else if(mode0to5countSum>0){
  583. for(int j=i;j>=i-mode0to5countSum;j--){
  584. doubledata[j][4]=Curve_SmallSpeed;
  585. step_count++;
  586. }
  587. }else{
  588. doubledata[i][4]=Curve_SmallSpeed;
  589. }
  590. mode0to5count=0;
  591. //mode0to18count++;
  592. mode18count++;
  593. mode18flash=mode18count;
  594. }else if(MapTrace[i]->roadMode==14){
  595. mode0to18countSum=mode0to5flash+mode18flash;
  596. mode18countSum=mode18count;
  597. double brake_distanceLarge_double=(pow((Curve_SmallSpeed/3.6),2)-pow((Curve_LargeSpeed/3.6),2))*10/0.6;
  598. double brake_distance0to18_double=(pow((straightCurveSpeed/3.6),2)-pow((Curve_LargeSpeed/3.6),2))*10/0.6;
  599. int brake_distanceLarge=(int)brake_distanceLarge_double;
  600. int brake_distance0to18=(int)brake_distance0to18_double;
  601. int step_count=0;
  602. doubledata[i][4]=Curve_LargeSpeed;
  603. if(mode18countSum>brake_distanceLarge)
  604. {
  605. double step_speed=(Curve_SmallSpeed-Curve_LargeSpeed)/brake_distanceLarge;
  606. for(int j=i;j>i-brake_distanceLarge;j--){
  607. doubledata[j][4]=valuemin((Curve_LargeSpeed+step_count*step_speed),Curve_SmallSpeed);
  608. step_count++;
  609. }
  610. }else if(mode0to18countSum>brake_distance0to18){
  611. double step_speed=(straightCurveSpeed-Curve_LargeSpeed)/brake_distance0to18;
  612. for(int j=i;j>i-brake_distance0to18;j--){
  613. doubledata[j][4]=valuemin((Curve_LargeSpeed+step_count*step_speed),straightCurveSpeed);
  614. step_count++;
  615. }
  616. }else{
  617. doubledata[i][4]=Curve_LargeSpeed;
  618. }
  619. mode0to5count=0;
  620. mode18count=0;
  621. mode0to5flash=0;
  622. mode18flash=0;
  623. }
  624. }
  625. return 0;
  626. }
  627. #endif
  628. void SetPlan(xodrobj xo)
  629. {
  630. double x_src,y_src,x_dst,y_dst;
  631. CalcXY(glat0,glon0,ghead0,xo.flatsrc,xo.flonsrc,x_src,y_src);
  632. CalcXY(glat0,glon0,ghead0,xo.flat,xo.flon,x_dst,y_dst);
  633. std::vector<PlanPoint> xPlan;
  634. double s;
  635. // x_src = -5;y_src = 6;
  636. // x_dst = -60;y_src = -150;
  637. 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);
  638. if(nRtn < 0)
  639. {
  640. qDebug("plan fail.");
  641. return;
  642. }
  643. int i;
  644. int nSize = xPlan.size();
  645. if(gbSideLaneEnable)
  646. {
  647. CalcLaneSide(xPlan);
  648. }
  649. else
  650. {
  651. if(gbSideEnable)
  652. {
  653. CalcSide(xPlan);
  654. }
  655. }
  656. if(nSize<1)
  657. {
  658. qDebug("plan fail.");
  659. return;
  660. }
  661. PlanPoint xLastPoint = xPlan[nSize -1];
  662. for(i=0;i<600;i++)
  663. {
  664. PlanPoint pp = xLastPoint;
  665. double fdis = 0.1*(i+1);
  666. pp.mS = pp.mS + i*0.1;
  667. pp.x = pp.x + fdis * cos(pp.hdg);
  668. pp.y = pp.y + fdis * sin(pp.hdg);
  669. pp.nSignal = 23;
  670. if(gbExtendMap)
  671. {
  672. xPlan.push_back(pp);
  673. }
  674. }
  675. iv::map::tracemap xtrace;
  676. nSize = xPlan.size();
  677. std::vector<iv::GPSData> mapdata;
  678. //maptrace
  679. QFile xfile;
  680. QString strpath;
  681. strpath = getenv("HOME");
  682. strpath = strpath + "/map/maptrace.txt";
  683. xfile.setFileName(strpath);
  684. xfile.open(QIODevice::ReadWrite);
  685. //maptrace_add
  686. QFile xfile_1;
  687. QString strpath_1;
  688. strpath_1 = getenv("HOME");
  689. strpath_1 = strpath_1 + "/map/mapadd.txt";
  690. xfile_1.setFileName(strpath_1);
  691. xfile_1.open(QIODevice::ReadWrite);
  692. double fpointdis = 0.1;
  693. if(nSize > 2)
  694. {
  695. fpointdis = sqrt(pow(xPlan[0].x - xPlan[1].x,2)+pow(xPlan[0].y - xPlan[1].y,2));
  696. }
  697. if(fpointdis < 0.1)fpointdis = 0.1;
  698. for(i=0;i<nSize;i++)
  699. {
  700. iv::map::mappoint * pmappoint = xtrace.add_point();
  701. double gps_lon,gps_lat,gps_lon_avoidleft,gps_lat_avoidleft,gps_lat_avoidright,gps_lon_avoidright,gps_heading;
  702. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,gps_lat,
  703. gps_lon,gps_heading);
  704. CalcLatLon(glat0,glon0,xPlan[i].mx_left,xPlan[i].my_left,
  705. gps_lat_avoidleft,gps_lon_avoidleft);
  706. CalcLatLon(glat0,glon0,xPlan[i].mx_right,xPlan[i].my_right,
  707. gps_lat_avoidright,gps_lon_avoidright);
  708. pmappoint->set_gps_lat(gps_lat);
  709. pmappoint->set_gps_lat_avoidleft(gps_lat_avoidleft);
  710. pmappoint->set_gps_lat_avoidright(gps_lat_avoidright);
  711. pmappoint->set_gps_lng(gps_lon);
  712. pmappoint->set_gps_lat_avoidleft(gps_lat_avoidleft);
  713. pmappoint->set_gps_lng_avoidright(gps_lon_avoidright);
  714. pmappoint->set_ins_heading_angle(gps_heading);
  715. double gps_x,gps_y,gps_x_avoidleft,gps_y_avoidleft,gps_x_avoidright,gps_y_avoidright;
  716. GaussProjCal(gps_lon,gps_lat,&gps_x,&gps_y);
  717. GaussProjCal(gps_lon_avoidleft,gps_lat_avoidleft,&gps_x_avoidleft,&gps_y_avoidleft);
  718. GaussProjCal(gps_lon_avoidright,gps_lat_avoidright,&gps_x_avoidright,&gps_y_avoidright);
  719. pmappoint->set_gps_x(gps_x);
  720. pmappoint->set_gps_x_avoidleft(gps_x_avoidleft);
  721. pmappoint->set_gps_x_avoidright(gps_x_avoidright);
  722. pmappoint->set_gps_y(gps_y);
  723. pmappoint->set_gps_y_avoidleft(gps_y_avoidleft);
  724. pmappoint->set_gps_y_avoidright(gps_y_avoidright);
  725. pmappoint->set_speed(xPlan[i].speed);
  726. pmappoint->set_index(i);
  727. pmappoint->set_roadori(xPlan[i].mnLaneori);
  728. pmappoint->set_roadsum(xPlan[i].mnLaneTotal);
  729. pmappoint->set_mfdistolaneleft(xPlan[i].mfDisToLaneLeft);
  730. pmappoint->set_mfdistoroadleft(xPlan[i].mfDisToRoadLeft);
  731. pmappoint->set_mflanewidth(xPlan[i].mWidth);
  732. pmappoint->set_mfroadwidth(xPlan[i].mfRoadWidth);
  733. pmappoint->set_mbinlaneavoid(xPlan[i].bInlaneAvoid);
  734. iv::GPSData data(new iv::GPS_INS);
  735. data->roadMode = 0;
  736. static int nChangeCount = 0;
  737. static int nlrmode = -1;
  738. if(nChangeCount == 0)
  739. {
  740. }
  741. else
  742. {
  743. data->roadMode = nlrmode;
  744. nChangeCount--;
  745. }
  746. // std::cout<<"i:"<<i<<" lr:"<<xPlan[i].nlrchange<<std::endl;
  747. // if(xPlan[i].nlrchange == 1)
  748. // {
  749. // data->roadMode = 14;
  750. // }
  751. // if(xPlan[i].nlrchange == 2)
  752. // {
  753. // data->roadMode = 15;
  754. // }
  755. if(i>50)
  756. {
  757. if((xPlan[i-1].nlrchange == 0)&&(xPlan[i].nlrchange != 0))
  758. {
  759. int j;
  760. for(j=(i-1);j>=(i-50);j--)
  761. {
  762. if(xPlan[i].nlrchange == 1)
  763. {
  764. mapdata[j]->roadMode = 14;
  765. }
  766. if(xPlan[i].nlrchange == 2)
  767. {
  768. mapdata[j]->roadMode = 15;
  769. }
  770. if(j <=0)break;
  771. }
  772. int nChangeCount = 0;
  773. for(j=i;j<(nSize-1);j++)
  774. {
  775. if((xPlan[j].nlrchange != 0)&&(xPlan[j+1].nlrchange != 0))
  776. {
  777. nChangeCount++;
  778. }
  779. }
  780. if(nChangeCount < static_cast<int>(10.0/fpointdis)) //Fast Change road.
  781. {
  782. nChangeCount = nChangeCount + static_cast<int>(3.0/fpointdis);
  783. }
  784. else
  785. {
  786. nChangeCount = static_cast<int>(5.0/fpointdis);
  787. }
  788. if(xPlan[i].nlrchange == 1)
  789. {
  790. nlrmode = 14;
  791. }
  792. if(xPlan[i].nlrchange == 2)
  793. {
  794. nlrmode = 15;
  795. }
  796. }
  797. }
  798. // if(data->roadMode != 0)
  799. // {
  800. // std::cout<<"i: "<<i<<std::endl;
  801. // }
  802. data->gps_lat = gps_lat;
  803. data->gps_lat_avoidleft = gps_lat_avoidleft;
  804. data->gps_lat_avoidright = gps_lat_avoidright;
  805. data->gps_lng = gps_lon;
  806. data->gps_lng_avoidleft = gps_lon_avoidleft;
  807. data->gps_lng_avoidright = gps_lon_avoidright;
  808. data->ins_heading_angle = gps_heading;
  809. data->gps_x = gps_x;
  810. data->gps_x_avoidleft = gps_x_avoidleft;
  811. data->gps_x_avoidright = gps_x_avoidright;
  812. data->gps_y = gps_y;
  813. data->gps_y_avoidleft = gps_y_avoidleft;
  814. data->gps_y_avoidright = gps_y_avoidright;
  815. pmappoint->set_mbnoavoid(xPlan[i].mbNoavoid);
  816. pmappoint->set_mfcurvature(xPlan[i].mfCurvature);
  817. // CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  818. // data->gps_lng,data->ins_heading_angle);
  819. // CalcLatLon(glat0,glon0,xPlan[i].mx_left,xPlan[i].my_left,
  820. // data->gps_lat_avoidleft,data->gps_lng_avoidleft);
  821. // CalcLatLon(glat0,glon0,xPlan[i].mx_right,xPlan[i].my_right,
  822. // data->gps_lat_avoidright,data->gps_lng_avoidright);
  823. data->index = i;
  824. data->speed = xPlan[i].speed;
  825. // ZBGaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  826. // GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  827. // GaussProjCal(data->gps_lng_avoidleft,data->gps_lat_avoidleft,&data->gps_x_avoidleft,&data->gps_y_avoidleft);
  828. // GaussProjCal(data->gps_lng_avoidright,data->gps_lat_avoidright,&data->gps_x_avoidright,&data->gps_y_avoidright);
  829. givlog->verbose(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  830. data->gps_lng,data->ins_heading_angle);
  831. data->roadOri = xPlan[i].mnLaneori;
  832. data->roadSum = xPlan[i].mnLaneTotal;
  833. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  834. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  835. data->mfLaneWidth = xPlan[i].mWidth;
  836. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  837. data->mbInLaneAvoid = xPlan[i].bInlaneAvoid;
  838. if(xPlan[i].mbBoringRoad)
  839. {
  840. data->roadOri = 0;
  841. data->roadSum = 2;
  842. pmappoint->set_roadori(0);
  843. pmappoint->set_roadsum(2);
  844. }
  845. data->mbnoavoid = xPlan[i].mbNoavoid;
  846. if(data->mbnoavoid)
  847. {
  848. qDebug("no avoid i = %d",i);
  849. }
  850. data->mfCurvature = xPlan[i].mfCurvature;
  851. data->mode2 = xPlan[i].nSignal;
  852. if(data->mode2 == 3000)
  853. {
  854. int k;
  855. for(k=(mapdata.size()-1);k>(mapdata.size()-150);k--)
  856. {
  857. if(k<0)break;
  858. if((mapdata.at(k)->mode2 != -1)&&(mapdata.at(k)->mode2 !=3000))
  859. {
  860. continue;
  861. }
  862. mapdata.at(k)->mode2 = 3000;
  863. }
  864. }
  865. if(data->mode2 == 1000001)
  866. {
  867. int k;
  868. for(k=(mapdata.size()-1);k>(mapdata.size()-10);k--)
  869. {
  870. if(k<0)break;
  871. if((mapdata.at(k)->mode2 != -1)&&(mapdata.at(k)->mode2 !=1000001))
  872. {
  873. continue;
  874. }
  875. mapdata.at(k)->mode2 = 1000001;
  876. }
  877. }
  878. pmappoint->set_mode2(data->mode2);
  879. pmappoint->set_rel_x(xPlan[i].x);
  880. pmappoint->set_rel_y(xPlan[i].y);
  881. pmappoint->set_rel_z(0);
  882. pmappoint->set_rel_yaw(xPlan[i].hdg);
  883. pmappoint->set_laneid(-1);
  884. pmappoint->set_roadid(xPlan[i].nRoadID);
  885. #ifdef BOAVOID
  886. if(isboringroad(xPlan[i].nRoadID))
  887. {
  888. const int nrangeavoid = 300;
  889. if((i+(nrangeavoid + 10))<nSize)
  890. {
  891. double fhdg1 = xPlan[i].hdg;
  892. bool bavoid = true;
  893. // int k;
  894. // for(k=0;k<=10;k++)
  895. // {
  896. // double fhdg5 = xPlan[i+nrangeavoid*k/10].hdg;
  897. // double fhdgdiff1 = fhdg5 - fhdg1;
  898. // while(fhdgdiff1<0)fhdgdiff1 = fhdgdiff1 + 2.0*M_PI;
  899. // if((fhdgdiff1>(M_PI/3.0))&&(fhdgdiff1<(5.0*M_PI/3.0)))
  900. // {
  901. // bavoid = false;
  902. // break;
  903. // }
  904. // }
  905. if(bavoid)
  906. {
  907. data->roadSum = 2;
  908. data->roadOri = 0;
  909. }
  910. }
  911. else
  912. {
  913. int a = 1;
  914. a++;
  915. }
  916. }
  917. #endif
  918. mapdata.push_back(data);
  919. // char strline[255];
  920. // // 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",
  921. // // i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,data->roadOri,data->roadSum,data->mode2,data->mfCurvature);
  922. // 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",
  923. // i,data->gps_lng,data->gps_lat,0,0,data->ins_heading_angle,0,0,data->roadSum,data->roadOri,data->mode2);
  924. // xfile.write(strline);
  925. }
  926. for(int j=0;j<nSize;j++)
  927. {
  928. char strline[255];
  929. 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",
  930. 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);
  931. xfile.write(strline);
  932. //mapttrace1
  933. char strline_1[255];
  934. 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",
  935. 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);
  936. xfile_1.write(strline_1);
  937. }
  938. xfile.close();
  939. xfile_1.close();
  940. ShareMap(mapdata);
  941. #ifdef TESTSPEEDPLAN
  942. getPlanSpeed(mapdata);
  943. #endif
  944. ShareMapGlobal(xPlan);
  945. int nnewmapsize = xtrace.ByteSize();
  946. std::shared_ptr<char> str_ptr = std::shared_ptr<char>(new char[nnewmapsize]);
  947. if(xtrace.SerializeToArray(str_ptr.get(),nnewmapsize))
  948. {
  949. iv::modulecomm::ModuleSendMsg(gpanewtrace ,str_ptr.get(),nnewmapsize);
  950. }
  951. else
  952. {
  953. std::cout<<" new trace map serialize fail."<<std::endl;
  954. }
  955. s = 1;
  956. }
  957. void MultiStationPlan(iv::v2x::v2x * pxv2x,double fsrclat,double fsrclon,double fsrcheading,int nlane)
  958. {
  959. std::vector<PlanPoint> xPlan;
  960. int i;
  961. double fLastHdg = 0;
  962. int ndeflane =nlane;
  963. for(i=0;i<pxv2x->stgps_size();i++)
  964. {
  965. double x_src,y_src,x_dst,y_dst;
  966. if(i==0)
  967. {
  968. CalcXY(glat0,glon0,ghead0,fsrclat,fsrclon,x_src,y_src);
  969. }
  970. else
  971. {
  972. CalcXY(glat0,glon0,ghead0,pxv2x->stgps(i-1).lat(),pxv2x->stgps(i-1).lon(),x_src,y_src);
  973. }
  974. CalcXY(glat0,glon0,ghead0,pxv2x->stgps(i).lat(),pxv2x->stgps(i).lon(),x_dst,y_dst);
  975. std::vector<PlanPoint> xPlanPart;
  976. double s;
  977. // x_src = -5;y_src = 6;
  978. // x_dst = -60;y_src = -150;
  979. int nRtn = -1;
  980. if(i==0)
  981. {
  982. 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);
  983. }
  984. else
  985. {
  986. nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,fLastHdg,x_dst,y_dst,s,30.0,100.0,ndeflane,xPlanPart);
  987. }
  988. if(nRtn < 0)
  989. {
  990. qDebug("plan fail.");
  991. return;
  992. }
  993. int j;
  994. for(j=0;j<xPlanPart.size();j++)xPlan.push_back(xPlanPart.at(j));
  995. fLastHdg = xPlanPart.at(xPlanPart.size()-1).hdg;
  996. }
  997. int nSize = xPlan.size();
  998. std::vector<iv::GPSData> mapdata;
  999. QFile xfile;
  1000. QString strpath;
  1001. strpath = getenv("HOME");
  1002. strpath = strpath + "/map/maptrace.txt";
  1003. xfile.setFileName(strpath);
  1004. xfile.open(QIODevice::ReadWrite);
  1005. for(i=0;i<nSize;i++)
  1006. {
  1007. iv::GPSData data(new iv::GPS_INS);
  1008. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  1009. data->gps_lng,data->ins_heading_angle);
  1010. data->index = i;
  1011. data->speed = xPlan[i].speed;
  1012. // ZBGaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  1013. GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  1014. givlog->verbose(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  1015. data->gps_lng,data->ins_heading_angle);
  1016. // data->roadSum = 1;
  1017. // data->roadMode = 0;
  1018. // data->roadOri = 0;
  1019. // if(xPlan[i].lanmp == -1)data->roadMode = 15;
  1020. // if(xPlan[i].lanmp == 1)data->roadMode = 14;
  1021. data->roadOri = xPlan[i].mnLaneori;
  1022. data->roadSum = xPlan[i].mnLaneTotal;
  1023. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  1024. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  1025. data->mfLaneWidth = xPlan[i].mWidth;
  1026. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  1027. data->mode2 = xPlan[i].nSignal;
  1028. if(data->mode2 == 3000)
  1029. {
  1030. int k;
  1031. for(k=(mapdata.size()-1);k>(mapdata.size()-150);k--)
  1032. {
  1033. if(k<0)break;
  1034. mapdata.at(k)->mode2 = 3000;
  1035. }
  1036. }
  1037. mapdata.push_back(data);
  1038. char strline[255];
  1039. 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",
  1040. i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,0,0);
  1041. xfile.write(strline);
  1042. }
  1043. xfile.close();
  1044. ShareMap(mapdata);
  1045. }
  1046. void ListenCmd(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  1047. {
  1048. if(nSize<sizeof(xodrobj))
  1049. {
  1050. std::cout<<"ListenCmd small."<<std::endl;
  1051. return;
  1052. }
  1053. xodrobj xo;
  1054. memcpy(&xo,strdata,sizeof(xodrobj));
  1055. givlog->debug("lat is %f", xo.flat);
  1056. xo.fhgdsrc = gsrc.fhgdsrc;
  1057. xo.flatsrc = gsrc.flatsrc;
  1058. xo.flonsrc = gsrc.flonsrc;
  1059. SetPlan(xo);
  1060. }
  1061. void ListenV2X(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  1062. {
  1063. iv::v2x::v2x xv2x;
  1064. if(!xv2x.ParseFromArray(strdata,nSize))
  1065. {
  1066. givlog->warn("ListernV2X Parse Error.");
  1067. std::cout<<"ListenV2X Parse Error."<<std::endl;
  1068. return;
  1069. }
  1070. if(xv2x.stgps_size()<1)
  1071. {
  1072. givlog->debug("ListenV2X no gps station.");
  1073. std::cout<<"ListenV2X no gps station."<<std::endl;
  1074. return;
  1075. }
  1076. MultiStationPlan(&xv2x,gsrc.flatsrc,gsrc.flonsrc,gsrc.fhgdsrc,1);
  1077. }
  1078. void ListenSrc(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  1079. {
  1080. if(nSize<sizeof(xodrobj))
  1081. {
  1082. givlog->warn("ListenSrc small");
  1083. std::cout<<"ListenSrc small."<<std::endl;
  1084. return;
  1085. }
  1086. memcpy(&gsrc,strdata,sizeof(xodrobj));
  1087. givlog->debug("src hdg is %f", gsrc.fhgdsrc);
  1088. std::cout<<"src hdg is "<<gsrc.fhgdsrc<<std::endl;
  1089. }
  1090. void UpdateGPSIMU(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  1091. {
  1092. iv::gps::gpsimu xgpsimu;
  1093. if(!xgpsimu.ParseFromArray(strdata,nSize))
  1094. {
  1095. givlog->warn("ADCIntelligentVehicle::UpdateGPSIMU parse error. nSize is %d",nSize);
  1096. return;
  1097. }
  1098. xodrobj xo;
  1099. xo.fhgdsrc = xgpsimu.heading();
  1100. xo.flatsrc = xgpsimu.lat();
  1101. xo.flonsrc = xgpsimu.lon();
  1102. gsrc = xo;
  1103. givlog->debug("src hdg is %f", gsrc.fhgdsrc);
  1104. std::cout<<"src hdg is "<<gsrc.fhgdsrc<<std::endl;
  1105. }
  1106. void ExitFunc()
  1107. {
  1108. // gApp->quit();
  1109. iv::modulecomm::Unregister(gpasimple);
  1110. iv::modulecomm::Unregister(gpav2x);
  1111. iv::modulecomm::Unregister(gpagps);
  1112. iv::modulecomm::Unregister(gpasrc);
  1113. iv::modulecomm::Unregister(gpmap);
  1114. iv::modulecomm::Unregister(gpa);
  1115. std::cout<<"driver_map_xodrload exit."<<std::endl;
  1116. gApp->quit();
  1117. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  1118. // std::this_thread::sleep_for(std::chrono::milliseconds(900));
  1119. }
  1120. void signal_handler(int sig)
  1121. {
  1122. if(sig == SIGINT)
  1123. {
  1124. ExitFunc();
  1125. }
  1126. }
  1127. void ProcROIReq(std::shared_ptr<char> pstr_req,const int nreqsize,std::shared_ptr<char> & pstr_res,int & nressize)
  1128. {
  1129. (void)pstr_req;
  1130. (void)nreqsize;
  1131. std::shared_ptr<iv::roi::request> pstr_roireq = std::shared_ptr<iv::roi::request>(new iv::roi::request);
  1132. if(pstr_roireq->ParseFromArray(pstr_req.get(),nreqsize))
  1133. {
  1134. std::shared_ptr<iv::roi::resultarray> pstr_roires;
  1135. gsrx.GetROI(pstr_roireq,pstr_roires);
  1136. int nbytesize = pstr_roires->ByteSize();
  1137. pstr_res = std::shared_ptr<char>(new char[nbytesize]);
  1138. if(pstr_roires->SerializeToArray(pstr_res.get(),nbytesize))
  1139. {
  1140. nressize = nbytesize;
  1141. std::cout<<"return res."<<std::endl;
  1142. return;
  1143. }
  1144. else
  1145. {
  1146. std::cout<<" ProcROIReq fail serizlizetoarray"<<std::endl;
  1147. }
  1148. }
  1149. else
  1150. {
  1151. std::cout<<" ProcROIReq parse pstr_req fail."<<std::endl;
  1152. return;
  1153. }
  1154. }
  1155. int main(int argc, char *argv[])
  1156. {
  1157. showversion("driver_map_xodrload");
  1158. QCoreApplication a(argc, argv);
  1159. gApp = &a;
  1160. RegisterIVBackTrace();
  1161. gfault = new iv::Ivfault("driver_map_xodrload");
  1162. givlog = new iv::Ivlog("driver_map_xodrload");
  1163. std::string strmapth,strparapath;
  1164. if(argc<3)
  1165. {
  1166. // strmapth = "./map.xodr";
  1167. strmapth = getenv("HOME");
  1168. strmapth = strmapth + "/map/map.xodr";
  1169. // strmapth = "/home/yuchuli/1226.xodr";
  1170. strparapath = "./driver_map_xodrload.xml";
  1171. }
  1172. else
  1173. {
  1174. strmapth = argv[1];
  1175. strparapath = argv[2];
  1176. }
  1177. iv::xmlparam::Xmlparam xp(strparapath);
  1178. xp.GetParam(std::string("he"),std::string("1"));
  1179. std::string strlat0 = xp.GetParam("lat0","39");
  1180. std::string strlon0 = xp.GetParam("lon0","117.0");
  1181. std::string strhdg0 = xp.GetParam("hdg0","360.0");
  1182. std::string strgpsmsg = xp.GetParam("gpsmsg","hcp2_gpsimu");
  1183. std::string strv2xmsg = xp.GetParam("v2xmsg","v2x");
  1184. std::string strvehiclewidth = xp.GetParam("vehiclewidth","2.0");
  1185. std::string strextendmap = xp.GetParam("extendmap","false");
  1186. std::string strsideenable = xp.GetParam("sideenable","false");
  1187. std::string strsidelaneenable = xp.GetParam("sidelaneenable","false");
  1188. gstrcdata = xp.GetParam("cdata","");
  1189. std::cout<<" cdata: "<<gstrcdata.data()<<std::endl;
  1190. #ifdef USE_TMERS
  1191. if(gstrcdata.length()>3)
  1192. {
  1193. C = proj_context_create();//创建多线程,由于本示例为单线程,此处为展示作用
  1194. P = proj_create_crs_to_crs (C,
  1195. "WGS84",
  1196. "+proj=tmerc +ellps=WGS84 +datum=WGS84 +units=m +lat_0=28.3252659663377 +lon_0=117.810536087614 +no_defs", /* or EPSG:32632 */
  1197. NULL);
  1198. // P = proj_create(C,"+proj=tmerc +ellps=WGS84 +datum=WGS84 +units=m +lat_0=28.3252659663377 +lon_0=117.810536087614 +no_defs");
  1199. if (0 == P) {
  1200. std::cout << "Failed to create transformation object." << stderr << std::endl;
  1201. return 1;
  1202. }//如果P中两个投影的字符串不符合proj定义,提示转换失败
  1203. norm = proj_normalize_for_visualization(C, P);
  1204. if (0 == norm) {
  1205. fprintf(stderr, "Failed to normalize transformation object.\n");
  1206. return 1;
  1207. }
  1208. proj_destroy(P);
  1209. P = norm;
  1210. }
  1211. #endif
  1212. glat0 = atof(strlat0.data());
  1213. glon0 = atof(strlon0.data());
  1214. ghead0 = atof(strhdg0.data());
  1215. gvehiclewidth = atof(strvehiclewidth.data());
  1216. if(strextendmap == "true")
  1217. {
  1218. gbExtendMap = true;
  1219. }
  1220. else
  1221. {
  1222. gbExtendMap = false;
  1223. }
  1224. if(strsideenable == "true")
  1225. {
  1226. gbSideEnable = true;
  1227. }
  1228. if(strsidelaneenable == "true")
  1229. {
  1230. gbSideLaneEnable = true;
  1231. }
  1232. LoadXODR(strmapth);
  1233. iv::service::Server serviceroi("ServiceROI",ProcROIReq);
  1234. (void)serviceroi;
  1235. gpmap = iv::modulecomm::RegisterSend("tracemap",20000000,1);
  1236. gpasimple = iv::modulecomm::RegisterSend("simpletrace",100000,1);
  1237. gpanewtrace = iv::modulecomm::RegisterSend("newtracemap",20000000,1);
  1238. gpamapglobal = iv::modulecomm::RegisterSend("mapglobal",20000000,1);
  1239. gpa = iv::modulecomm::RegisterRecv("xodrreq",ListenCmd);
  1240. gpasrc =iv::modulecomm::RegisterRecv("xodrsrc",ListenSrc);
  1241. gpagps = iv::modulecomm::RegisterRecv(strgpsmsg.data(),UpdateGPSIMU);
  1242. gpav2x = iv::modulecomm::RegisterRecv(strv2xmsg.data(),ListenV2X);
  1243. double x_src,y_src,x_dst,y_dst;
  1244. x_src = -26;y_src = 10;
  1245. x_dst = -50;y_dst = -220;
  1246. x_src = 0;y_src = 0;
  1247. x_dst = -23;y_dst = -18;
  1248. x_dst = 21;y_dst =-21;
  1249. x_dst =5;y_dst = 0;
  1250. x_src = -20; y_src = -1000;
  1251. x_dst = 900; y_dst = -630;
  1252. // x_dst = 450; y_dst = -640;
  1253. // x_dst = -190; y_dst = -690;
  1254. // x_src = 900; y_src = -610;
  1255. // x_dst = -100; y_dst = -680;
  1256. std::vector<PlanPoint> xPlan;
  1257. double s;
  1258. // int nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,3.14,x_dst,y_dst,s,30.0,100.0,1,xPlan);
  1259. // ToGPSTrace(xPlan);
  1260. // double lat = 39.1443880;
  1261. // double lon = 117.0812543;
  1262. // xodrobj xo;
  1263. // xo.fhgdsrc = 340;
  1264. // xo.flatsrc = lat; xo.flonsrc = lon;
  1265. // xo.flat = 39.1490196;
  1266. // xo.flon = 117.0806979;
  1267. // xo.lane = 1;
  1268. // SetPlan(xo);
  1269. // void * pivexit = iv::ivexit::RegIVExitCall(ExitFunc);
  1270. signal(SIGINT,signal_handler);
  1271. int nrc = a.exec();
  1272. std::cout<<"driver_map_xodr app exit. code :"<<nrc<<std::endl;
  1273. return nrc;
  1274. }