main.cpp 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841
  1. #include <QCoreApplication>
  2. #include <math.h>
  3. #include <string>
  4. #include <QFile>
  5. #include "OpenDrive/OpenDrive.h"
  6. #include "OpenDrive/OpenDriveXmlParser.h"
  7. #include "globalplan.h"
  8. #include "gpsimu.pb.h"
  9. #include "v2x.pb.h"
  10. #include "modulecomm.h"
  11. #include "xmlparam.h"
  12. #include "gps_type.h"
  13. #include "xodrdijkstra.h"
  14. #include "gnss_coordinate_convert.h"
  15. #include "ivexit.h"
  16. #include "ivversion.h"
  17. OpenDrive mxodr;
  18. xodrdijkstra * gpxd;
  19. bool gmapload = false;
  20. double glat0,glon0,ghead0;
  21. double gvehiclewidth = 2.0;
  22. void * gpa;
  23. void * gpasrc;
  24. void * gpmap;
  25. void * gpagps;
  26. void * gpasimple;
  27. void * gpav2x;
  28. iv::Ivfault *gfault = nullptr;
  29. iv::Ivlog *givlog = nullptr;
  30. namespace iv {
  31. struct simpletrace
  32. {
  33. double gps_lat = 0;//纬度
  34. double gps_lng = 0;//经度
  35. double gps_x = 0;
  36. double gps_y = 0;
  37. double gps_z = 0;
  38. double ins_heading_angle = 0; //航向角
  39. };
  40. }
  41. /**
  42. *
  43. *
  44. *
  45. *
  46. * */
  47. bool LoadXODR(std::string strpath)
  48. {
  49. OpenDriveXmlParser xp(&mxodr);
  50. xp.ReadFile(strpath);
  51. std::cout<<"road cout is "<<mxodr.GetRoadCount()<<std::endl;
  52. if(mxodr.GetRoadCount() < 1)
  53. {
  54. gmapload = true;
  55. return false;
  56. }
  57. xodrdijkstra * pxd = new xodrdijkstra(&mxodr);
  58. gpxd = pxd;
  59. // std::vector<int> xpath = pxd->getpath(10001,2,30012,2);
  60. // pxd->getgpspoint(10001,2,30012,2,xpath);
  61. int i;
  62. double nlenth = 0;
  63. int nroadsize = mxodr.GetRoadCount();
  64. for(i=0;i<nroadsize;i++)
  65. {
  66. Road * px = mxodr.GetRoad(i);
  67. nlenth = nlenth + px->GetRoadLength();
  68. int bloksize = px->GetGeometryBlockCount();
  69. if(px->GetGeometryBlock(0)->GetGeometryAt(0)->GetGeomType() == 4)
  70. {
  71. GeometryParamPoly3 * p = (GeometryParamPoly3 *) px->GetGeometryBlock(0)->GetGeometryAt(0);
  72. double a = p->GetuA();
  73. a = p->GetuB();
  74. a = p->GetuC();
  75. a = p->GetuD();
  76. a = p->GetvA();
  77. }
  78. }
  79. // void Header::GetAllParams(unsigned short int &revMajor, unsigned short int &revMinor, string &name, float &version, string &date,
  80. // double &north, double &south, double &east,double &west,double &lat0,double &lon0, double & hdg0)
  81. unsigned short int revMajor,revMinor;
  82. std::string name,date;
  83. float version;
  84. double north,south,east,west,lat0,lon0,hdg0;
  85. if(mxodr.GetHeader() != 0)
  86. {
  87. mxodr.GetHeader()->GetAllParams(revMajor,revMinor,name,version,date,north,south,east,west,lat0,lon0,hdg0);
  88. glat0 = lat0;
  89. glon0 = lon0;
  90. }
  91. Road * proad1 = mxodr.GetRoad(0);
  92. givlog->info("road name is %s",proad1->GetRoadName().data());
  93. std::cout<<" road name is "<<proad1->GetRoadName()<<std::endl;
  94. }
  95. class roadx
  96. {
  97. public:
  98. roadx * para;
  99. std::vector<roadx> child;
  100. int nlen;
  101. };
  102. #define EARTH_RADIUS 6370856.0
  103. //从1到2的距离和方向
  104. int CalcDisAngle(double lat1,double lon1,double lat2,double lon2,double * pLatDis,double * pLonDis,double * pDis,double * pangle)
  105. {
  106. double a,b;
  107. double LonDis,LatDis;
  108. double LonRadius;
  109. double Dis;
  110. double angle;
  111. if((lat1 == lat2)&&(lon1 == lon2))return -1;
  112. LonRadius = EARTH_RADIUS * cos(lat2/(180.0/M_PI));
  113. a = (EARTH_RADIUS * M_PI*2.0/360.0)/(100000.0);
  114. b = lat2 - lat1; b = b*100000.0;
  115. LatDis = a*b;
  116. a = (LonRadius * M_PI*2.0/360.0)/100000.0;
  117. b = lon2 - lon1; b = b*100000.0;
  118. LonDis = a*b;
  119. Dis = sqrt(LatDis*LatDis + LonDis *LonDis);
  120. angle = acos(fabs(LonDis)/Dis);
  121. angle = angle * 180.0/M_PI;
  122. if(LonDis > 0)
  123. {
  124. if(LatDis > 0)angle = 90.0 - angle;
  125. else angle= 90.0+angle;
  126. }
  127. else
  128. {
  129. if(LatDis > 0)angle = 270.0+angle;
  130. else angle = 270.0-angle;
  131. }
  132. if(pLatDis != 0)*pLatDis = LatDis;
  133. if(pLonDis != 0)*pLonDis = LonDis;
  134. if(pDis != 0)*pDis = Dis;
  135. if(pangle != 0)*pangle = angle;
  136. }
  137. //==========================================================
  138. //高斯投影由经纬度(Unit:DD)反算大地坐标(含带号,Unit:Metres)
  139. //void GaussProjCal(double longitude, double latitude, double *X, double *Y)
  140. //{
  141. // int ProjNo = 0; int ZoneWide; ////带宽
  142. // double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
  143. // double a, f, e2, ee, NN, T, C, A, M, iPI;
  144. // iPI = 0.0174532925199433; ////3.1415926535898/180.0;
  145. // ZoneWide = 6; ////6度带宽
  146. // a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
  147. // ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
  148. // ProjNo = (int)(longitude / ZoneWide);
  149. // longitude0 = ProjNo * ZoneWide + ZoneWide / 2;
  150. // longitude0 = longitude0 * iPI;
  151. // latitude0 = 0;
  152. // longitude1 = longitude * iPI; //经度转换为弧度
  153. // latitude1 = latitude * iPI; //纬度转换为弧度
  154. // e2 = 2 * f - f * f;
  155. // ee = e2 * (1.0 - e2);
  156. // NN = a / sqrt(1.0 - e2 * sin(latitude1)*sin(latitude1));
  157. // T = tan(latitude1)*tan(latitude1);
  158. // C = ee * cos(latitude1)*cos(latitude1);
  159. // A = (longitude1 - longitude0)*cos(latitude1);
  160. // 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
  161. // *e2 / 1024)*sin(2 * latitude1)
  162. // + (15 * e2*e2 / 256 + 45 * e2*e2*e2 / 1024)*sin(4 * latitude1) - (35 * e2*e2*e2 / 3072)*sin(6 * latitude1));
  163. // 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);
  164. // yval = M + NN * tan(latitude1)*(A*A / 2 + (5 - T + 9 * C + 4 * C*C)*A*A*A*A / 24
  165. // + (61 - 58 * T + T * T + 600 * C - 330 * ee)*A*A*A*A*A*A / 720);
  166. // X0 = 1000000L * (ProjNo + 1) + 500000L;
  167. // Y0 = 0;
  168. // xval = xval + X0; yval = yval + Y0;
  169. // *X = xval;
  170. // *Y = yval;
  171. //}
  172. #include <math.h>
  173. static void OffLngLat(double fLat0,double fLng0,double & fLat,double & fLng,double fHeading,double x,double y)
  174. {
  175. double fxdiff,fydiff;
  176. double xoff = y*(-1);
  177. double yoff = x;
  178. fxdiff = 0+xoff * cos(fHeading*M_PI/180.0)+ yoff*sin(fHeading*M_PI/180.0); //East
  179. fydiff = 0-xoff * sin(fHeading*M_PI/180.0)+ yoff*cos(fHeading*M_PI/180.0); //South
  180. double fEarthRadius = 6378245.0;
  181. double ns1d = fEarthRadius*2*M_PI/360.0;
  182. double fewRadius = fEarthRadius * cos(fLat0*M_PI/180.0);
  183. double ew1d = fewRadius * 2*M_PI/360.0;
  184. fLat = fLat0 + fydiff/ns1d;
  185. fLng = fLng0 + fxdiff/ew1d;
  186. }
  187. void CalcXY(const double lat0,const double lon0,const double hdg0,
  188. const double lat,const double lon,
  189. double & x,double & y)
  190. {
  191. double x0,y0;
  192. GaussProjCal(lon0,lat0,&x0,&y0);
  193. GaussProjCal(lon,lat,&x,&y);
  194. x = x - x0;
  195. y = y- y0;
  196. // double ang,dis;
  197. // CalcDisAngle(lat0,lon0,lat,lon,0,0,&dis,&ang);
  198. // double xang = hdg0 - ang;
  199. // while(xang<0)xang = xang + 360.0;
  200. // x = dis * cos(xang * M_PI/180.0);
  201. // y = dis * sin(xang * M_PI/180.0);
  202. }
  203. //void CalcLatLon(const double lat0,const double lon0,const double hdg0,
  204. // const double x,const double y,const double xyhdg,
  205. // double &lat,double & lon, double & hdg)
  206. //{
  207. // OffLngLat(lat0,lon0,lat,lon,hdg0,x,y);
  208. // hdg = hdg0 - xyhdg * 180.0/M_PI;
  209. // while(hdg < 0)hdg = hdg + 360;
  210. // while(hdg >= 360)hdg = hdg - 360;
  211. //}
  212. void CalcLatLon(const double lat0,const double lon0,
  213. const double x,const double y,
  214. double &lat,double & lon)
  215. {
  216. double x0,y0;
  217. GaussProjCal(lon0,lat0,&x0,&y0);
  218. double x_gps,y_gps;
  219. x_gps = x0+x;
  220. y_gps = y0+y;
  221. GaussProjInvCal(x_gps,y_gps,&lon,&lat);
  222. }
  223. void CalcLatLon(const double lat0,const double lon0,const double hdg0,
  224. const double x,const double y,const double xyhdg,
  225. double &lat,double & lon, double & hdg)
  226. {
  227. double x0,y0;
  228. GaussProjCal(lon0,lat0,&x0,&y0);
  229. double x_gps,y_gps;
  230. x_gps = x0+x;
  231. y_gps = y0+y;
  232. GaussProjInvCal(x_gps,y_gps,&lon,&lat);
  233. // hdg = hdg0 -xyhdg * 270/M_PI;
  234. hdg = 90 - xyhdg* 180.0/M_PI;
  235. // OffLngLat(lat0,lon0,lat,lon,hdg0,x,y);
  236. // hdg = hdg0 - xyhdg * 180.0/M_PI;
  237. while(hdg < 0)hdg = hdg + 360;
  238. while(hdg >= 360)hdg = hdg - 360;
  239. }
  240. class xodrobj
  241. {
  242. public:
  243. double flatsrc;
  244. double flonsrc;
  245. double fhgdsrc;
  246. double flat;
  247. double flon;
  248. int lane;
  249. };
  250. xodrobj gsrc;
  251. void ShareMap(std::vector<iv::GPSData> navigation_data)
  252. {
  253. if(navigation_data.size()<1)return;
  254. iv::GPS_INS x;
  255. x = *(navigation_data.at(0));
  256. char * data = new char[sizeof(iv::GPS_INS)*navigation_data.size()];
  257. int gpssize = sizeof(iv::GPS_INS);
  258. int i;
  259. for(i=0;i<navigation_data.size();i++)
  260. {
  261. x = *(navigation_data.at(i));
  262. memcpy(data+i*gpssize,&x,gpssize);
  263. }
  264. iv::modulecomm::ModuleSendMsg(gpmap,data,navigation_data.size()*gpssize);
  265. int nsize = 100;
  266. int nstep = 1;
  267. if(navigation_data.size() < 100)
  268. {
  269. nsize = navigation_data.size();
  270. }
  271. else
  272. {
  273. nstep = navigation_data.size()/100;
  274. }
  275. iv::simpletrace psim[100];
  276. for(i=0;i<nsize;i++)
  277. {
  278. x = *(navigation_data.at(i*nstep));
  279. psim[i].gps_lat = x.gps_lat;
  280. psim[i].gps_lng = x.gps_lng;
  281. psim[i].gps_z = x.gps_z;
  282. psim[i].gps_x = x.gps_x;
  283. psim[i].gps_y = x.gps_y;
  284. psim[i].ins_heading_angle = x.ins_heading_angle;
  285. }
  286. if(navigation_data.size()>100)
  287. {
  288. int nlast = 99;
  289. x = *(navigation_data.at(navigation_data.size()-1));
  290. psim[nlast].gps_lat = x.gps_lat;
  291. psim[nlast].gps_lng = x.gps_lng;
  292. psim[nlast].gps_z = x.gps_z;
  293. psim[nlast].gps_x = x.gps_x;
  294. psim[nlast].gps_y = x.gps_y;
  295. psim[nlast].ins_heading_angle = x.ins_heading_angle;
  296. }
  297. iv::modulecomm::ModuleSendMsg(gpasimple,(char *)psim,nsize * sizeof(iv::simpletrace));
  298. delete data;
  299. }
  300. static void ToGPSTrace(std::vector<PlanPoint> xPlan)
  301. {
  302. // double x_src,y_src,x_dst,y_dst;
  303. // x_src = -26;y_src = 10;
  304. // x_dst = -50;y_dst = -220;
  305. int i;
  306. int nSize = xPlan.size();
  307. std::vector<iv::GPSData> mapdata;
  308. QFile xfile;
  309. QString strpath;
  310. strpath = getenv("HOME");
  311. strpath = strpath + "/map/maptrace.txt";
  312. xfile.setFileName(strpath);
  313. xfile.open(QIODevice::ReadWrite);
  314. for(i=0;i<nSize;i++)
  315. {
  316. iv::GPSData data(new iv::GPS_INS);
  317. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  318. data->gps_lng,data->ins_heading_angle);
  319. data->index = i;
  320. data->speed = xPlan[i].speed;
  321. GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  322. givlog->debug(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  323. data->gps_lng,data->ins_heading_angle);
  324. data->roadSum = xPlan[i].mnLaneTotal;
  325. data->roadMode = 0;
  326. data->roadOri = xPlan[i].mnLaneori;
  327. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  328. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  329. data->mfLaneWidth = xPlan[i].mWidth;
  330. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  331. data->mnLaneChangeMark = xPlan[i].lanmp;
  332. if(xPlan[i].lanmp == -1)data->roadMode = 15;
  333. if(xPlan[i].lanmp == 1)data->roadMode = 14;
  334. mapdata.push_back(data);
  335. char strline[255];
  336. 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",
  337. i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,0,0);
  338. xfile.write(strline);
  339. // 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;
  340. }
  341. xfile.close();
  342. ShareMap(mapdata);
  343. }
  344. void SetPlan(xodrobj xo)
  345. {
  346. double x_src,y_src,x_dst,y_dst;
  347. CalcXY(glat0,glon0,ghead0,xo.flatsrc,xo.flonsrc,x_src,y_src);
  348. CalcXY(glat0,glon0,ghead0,xo.flat,xo.flon,x_dst,y_dst);
  349. std::vector<PlanPoint> xPlan;
  350. double s;
  351. // x_src = -5;y_src = 6;
  352. // x_dst = -60;y_src = -150;
  353. 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);
  354. if(nRtn < 0)
  355. {
  356. qDebug("plan fail.");
  357. return;
  358. }
  359. int i;
  360. int nSize = xPlan.size();
  361. std::vector<iv::GPSData> mapdata;
  362. QFile xfile;
  363. QString strpath;
  364. strpath = getenv("HOME");
  365. strpath = strpath + "/map/maptrace.txt";
  366. xfile.setFileName(strpath);
  367. xfile.open(QIODevice::ReadWrite);
  368. for(i=0;i<nSize;i++)
  369. {
  370. iv::GPSData data(new iv::GPS_INS);
  371. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  372. data->gps_lng,data->ins_heading_angle);
  373. CalcLatLon(glat0,glon0,xPlan[i].mx_left,xPlan[i].my_left,
  374. data->gps_lat_avoidleft,data->gps_lng_avoidleft);
  375. CalcLatLon(glat0,glon0,xPlan[i].mx_right,xPlan[i].my_right,
  376. data->gps_lat_avoidright,data->gps_lng_avoidright);
  377. data->index = i;
  378. data->speed = xPlan[i].speed;
  379. // ZBGaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  380. GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  381. GaussProjCal(data->gps_lng_avoidleft,data->gps_lat_avoidleft,&data->gps_x_avoidleft,&data->gps_y_avoidleft);
  382. GaussProjCal(data->gps_lng_avoidright,data->gps_lat_avoidright,&data->gps_x_avoidright,&data->gps_y_avoidright);
  383. givlog->verbose(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  384. data->gps_lng,data->ins_heading_angle);
  385. data->roadOri = xPlan[i].mnLaneori;
  386. data->roadSum = xPlan[i].mnLaneTotal;
  387. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  388. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  389. data->mfLaneWidth = xPlan[i].mWidth;
  390. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  391. data->mbInLaneAvoid = xPlan[i].bInlaneAvoid;
  392. data->mode2 = xPlan[i].nSignal;
  393. if(data->mode2 == 3000)
  394. {
  395. int k;
  396. for(k=(mapdata.size()-1);k>(mapdata.size()-150);k--)
  397. {
  398. if(k<0)break;
  399. mapdata.at(k)->mode2 = 3000;
  400. }
  401. }
  402. // data->roadSum = 1;
  403. // data->roadMode = 0;
  404. // data->roadOri = 0;
  405. // if(xPlan[i].lanmp == -1)data->roadMode = 15;
  406. // if(xPlan[i].lanmp == 1)data->roadMode = 14;
  407. mapdata.push_back(data);
  408. char strline[255];
  409. 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",
  410. i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,0,0);
  411. xfile.write(strline);
  412. }
  413. xfile.close();
  414. ShareMap(mapdata);
  415. s = 1;
  416. }
  417. void MultiStationPlan(iv::v2x::v2x * pxv2x,double fsrclat,double fsrclon,double fsrcheading,int nlane)
  418. {
  419. std::vector<PlanPoint> xPlan;
  420. int i;
  421. double fLastHdg = 0;
  422. int ndeflane =nlane;
  423. for(i=0;i<pxv2x->stgps_size();i++)
  424. {
  425. double x_src,y_src,x_dst,y_dst;
  426. if(i==0)
  427. {
  428. CalcXY(glat0,glon0,ghead0,fsrclat,fsrclon,x_src,y_src);
  429. }
  430. else
  431. {
  432. CalcXY(glat0,glon0,ghead0,pxv2x->stgps(i-1).lat(),pxv2x->stgps(i-1).lon(),x_src,y_src);
  433. }
  434. CalcXY(glat0,glon0,ghead0,pxv2x->stgps(i).lat(),pxv2x->stgps(i).lon(),x_dst,y_dst);
  435. std::vector<PlanPoint> xPlanPart;
  436. double s;
  437. // x_src = -5;y_src = 6;
  438. // x_dst = -60;y_src = -150;
  439. int nRtn = -1;
  440. if(i==0)
  441. {
  442. 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);
  443. }
  444. else
  445. {
  446. nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,fLastHdg,x_dst,y_dst,s,30.0,100.0,ndeflane,xPlanPart);
  447. }
  448. if(nRtn < 0)
  449. {
  450. qDebug("plan fail.");
  451. return;
  452. }
  453. int j;
  454. for(j=0;j<xPlanPart.size();j++)xPlan.push_back(xPlanPart.at(j));
  455. fLastHdg = xPlanPart.at(xPlanPart.size()-1).hdg;
  456. }
  457. int nSize = xPlan.size();
  458. std::vector<iv::GPSData> mapdata;
  459. QFile xfile;
  460. QString strpath;
  461. strpath = getenv("HOME");
  462. strpath = strpath + "/map/maptrace.txt";
  463. xfile.setFileName(strpath);
  464. xfile.open(QIODevice::ReadWrite);
  465. for(i=0;i<nSize;i++)
  466. {
  467. iv::GPSData data(new iv::GPS_INS);
  468. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  469. data->gps_lng,data->ins_heading_angle);
  470. data->index = i;
  471. data->speed = xPlan[i].speed;
  472. // ZBGaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  473. GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  474. givlog->verbose(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  475. data->gps_lng,data->ins_heading_angle);
  476. // data->roadSum = 1;
  477. // data->roadMode = 0;
  478. // data->roadOri = 0;
  479. // if(xPlan[i].lanmp == -1)data->roadMode = 15;
  480. // if(xPlan[i].lanmp == 1)data->roadMode = 14;
  481. data->roadOri = xPlan[i].mnLaneori;
  482. data->roadSum = xPlan[i].mnLaneTotal;
  483. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  484. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  485. data->mfLaneWidth = xPlan[i].mWidth;
  486. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  487. data->mode2 = xPlan[i].nSignal;
  488. if(data->mode2 == 3000)
  489. {
  490. int k;
  491. for(k=(mapdata.size()-1);k>(mapdata.size()-150);k--)
  492. {
  493. if(k<0)break;
  494. mapdata.at(k)->mode2 = 3000;
  495. }
  496. }
  497. mapdata.push_back(data);
  498. char strline[255];
  499. 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",
  500. i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,0,0);
  501. xfile.write(strline);
  502. }
  503. xfile.close();
  504. ShareMap(mapdata);
  505. }
  506. void ListenCmd(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  507. {
  508. if(nSize<sizeof(xodrobj))
  509. {
  510. std::cout<<"ListenCmd small."<<std::endl;
  511. return;
  512. }
  513. xodrobj xo;
  514. memcpy(&xo,strdata,sizeof(xodrobj));
  515. givlog->debug("lat is %f", xo.flat);
  516. xo.fhgdsrc = gsrc.fhgdsrc;
  517. xo.flatsrc = gsrc.flatsrc;
  518. xo.flonsrc = gsrc.flonsrc;
  519. SetPlan(xo);
  520. }
  521. void ListenV2X(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  522. {
  523. iv::v2x::v2x xv2x;
  524. if(!xv2x.ParseFromArray(strdata,nSize))
  525. {
  526. givlog->warn("ListernV2X Parse Error.");
  527. std::cout<<"ListenV2X Parse Error."<<std::endl;
  528. return;
  529. }
  530. if(xv2x.stgps_size()<1)
  531. {
  532. givlog->debug("ListenV2X no gps station.");
  533. std::cout<<"ListenV2X no gps station."<<std::endl;
  534. return;
  535. }
  536. MultiStationPlan(&xv2x,gsrc.flatsrc,gsrc.flonsrc,gsrc.fhgdsrc,1);
  537. }
  538. void ListenSrc(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  539. {
  540. if(nSize<sizeof(xodrobj))
  541. {
  542. givlog->warn("ListenSrc small");
  543. std::cout<<"ListenSrc small."<<std::endl;
  544. return;
  545. }
  546. memcpy(&gsrc,strdata,sizeof(xodrobj));
  547. givlog->debug("src hdg is %f", gsrc.fhgdsrc);
  548. std::cout<<"src hdg is "<<gsrc.fhgdsrc<<std::endl;
  549. }
  550. void UpdateGPSIMU(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  551. {
  552. iv::gps::gpsimu xgpsimu;
  553. if(!xgpsimu.ParseFromArray(strdata,nSize))
  554. {
  555. givlog->warn("ADCIntelligentVehicle::UpdateGPSIMU parse error. nSize is %d",nSize);
  556. return;
  557. }
  558. xodrobj xo;
  559. xo.fhgdsrc = xgpsimu.heading();
  560. xo.flatsrc = xgpsimu.lat();
  561. xo.flonsrc = xgpsimu.lon();
  562. gsrc = xo;
  563. givlog->debug("src hdg is %f", gsrc.fhgdsrc);
  564. std::cout<<"src hdg is "<<gsrc.fhgdsrc<<std::endl;
  565. }
  566. int main(int argc, char *argv[])
  567. {
  568. showversion("driver_map_xodrload");
  569. QCoreApplication a(argc, argv);
  570. gfault = new iv::Ivfault("driver_map_xodrload");
  571. givlog = new iv::Ivlog("driver_map_xodrload");
  572. std::string strmapth,strparapath;
  573. if(argc<3)
  574. {
  575. // strmapth = "./map.xodr";
  576. strmapth = getenv("HOME");
  577. strmapth = strmapth + "/map/map.xodr";
  578. // strmapth = "/home/yuchuli/1226.xodr";
  579. strparapath = "./ADCIntelligentVehicle-xodrload.xml";
  580. }
  581. else
  582. {
  583. strmapth = argv[1];
  584. strparapath = argv[2];
  585. }
  586. iv::xmlparam::Xmlparam xp(strparapath);
  587. xp.GetParam(std::string("he"),std::string("1"));
  588. std::string strlat0 = xp.GetParam("lat0","39");
  589. std::string strlon0 = xp.GetParam("lon0","117.0");
  590. std::string strhdg0 = xp.GetParam("hdg0","360.0");
  591. std::string strgpsmsg = xp.GetParam("gpsmsg","hcp2_gpsimu");
  592. std::string strv2xmsg = xp.GetParam("v2xmsg","v2x");
  593. std::string strvehiclewidth = xp.GetParam("vehiclewidth","2.0");
  594. glat0 = atof(strlat0.data());
  595. glon0 = atof(strlon0.data());
  596. ghead0 = atof(strhdg0.data());
  597. gvehiclewidth = atof(strvehiclewidth.data());
  598. LoadXODR(strmapth);
  599. gpmap = iv::modulecomm::RegisterSend("tracemap",20000000,1);
  600. gpa = iv::modulecomm::RegisterRecv("xodrreq",ListenCmd);
  601. gpasrc =iv::modulecomm::RegisterRecv("xodrsrc",ListenSrc);
  602. gpagps = iv::modulecomm::RegisterRecv(strgpsmsg.data(),UpdateGPSIMU);
  603. gpav2x = iv::modulecomm::RegisterRecv(strv2xmsg.data(),ListenV2X);
  604. gpasimple = iv::modulecomm::RegisterSend("simpletrace",100000,1);
  605. double x_src,y_src,x_dst,y_dst;
  606. x_src = -26;y_src = 10;
  607. x_dst = -50;y_dst = -220;
  608. x_src = 0;y_src = 0;
  609. x_dst = -23;y_dst = -18;
  610. x_dst = 21;y_dst =-21;
  611. x_dst =5;y_dst = 0;
  612. x_src = -20; y_src = -1000;
  613. x_dst = 900; y_dst = -630;
  614. // x_dst = 450; y_dst = -640;
  615. // x_dst = -190; y_dst = -690;
  616. // x_src = 900; y_src = -610;
  617. // x_dst = -100; y_dst = -680;
  618. std::vector<PlanPoint> xPlan;
  619. double s;
  620. // int nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,3.14,x_dst,y_dst,s,30.0,100.0,1,xPlan);
  621. // ToGPSTrace(xPlan);
  622. // double lat = 39.1443880;
  623. // double lon = 117.0812543;
  624. // xodrobj xo;
  625. // xo.fhgdsrc = 340;
  626. // xo.flatsrc = lat; xo.flonsrc = lon;
  627. // xo.flat = 39.1490196;
  628. // xo.flon = 117.0806979;
  629. // xo.lane = 1;
  630. // SetPlan(xo);
  631. void * pivexit = iv::ivexit::RegIVExitCall(0);
  632. return a.exec();
  633. }