ivmapview.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032
  1. #include "ivmapview.h"
  2. #include <QFile>
  3. #define VIEW_WIDTH 1100
  4. #define VIEW_HEIGHT 900
  5. double glon0 = 117.0866293;
  6. double glat0 = 39.1364713;
  7. //double glon0 = 117;
  8. //double glat0 = 39;
  9. double ghdg0 = 360;
  10. #include "pos_def.h"
  11. extern std::vector<iv::pos_def> gvectorpos;
  12. extern std::string gstrmode;
  13. #include <math.h>
  14. //高斯投影由经纬度(Unit:DD)反算大地坐标(含带号,Unit:Metres)
  15. void GaussProjCal(double longitude, double latitude, double *X, double *Y)
  16. {
  17. int ProjNo = 0; int ZoneWide; ////带宽
  18. double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
  19. double a, f, e2, ee, NN, T, C, A, M, iPI;
  20. iPI = 0.0174532925199433; ////3.1415926535898/180.0;
  21. ZoneWide = 6; ////6度带宽
  22. a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
  23. ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
  24. ProjNo = (int)(longitude / ZoneWide);
  25. longitude0 = ProjNo * ZoneWide + ZoneWide / 2;
  26. longitude0 = longitude0 * iPI;
  27. latitude0 = 0;
  28. longitude1 = longitude * iPI; //经度转换为弧度
  29. latitude1 = latitude * iPI; //纬度转换为弧度
  30. e2 = 2 * f - f * f;
  31. ee = e2 * (1.0 - e2);
  32. NN = a / sqrt(1.0 - e2 * sin(latitude1)*sin(latitude1));
  33. T = tan(latitude1)*tan(latitude1);
  34. C = ee * cos(latitude1)*cos(latitude1);
  35. A = (longitude1 - longitude0)*cos(latitude1);
  36. 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
  37. *e2 / 1024)*sin(2 * latitude1)
  38. + (15 * e2*e2 / 256 + 45 * e2*e2*e2 / 1024)*sin(4 * latitude1) - (35 * e2*e2*e2 / 3072)*sin(6 * latitude1));
  39. 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);
  40. yval = M + NN * tan(latitude1)*(A*A / 2 + (5 - T + 9 * C + 4 * C*C)*A*A*A*A / 24
  41. + (61 - 58 * T + T * T + 600 * C - 330 * ee)*A*A*A*A*A*A / 720);
  42. X0 = 1000000L * (ProjNo + 1) + 500000L;
  43. Y0 = 0;
  44. xval = xval + X0; yval = yval + Y0;
  45. *X = xval;
  46. *Y = yval;
  47. }
  48. static bool LoadXODR(std::string strpath,OpenDrive & xxodr)
  49. {
  50. OpenDriveXmlParser xp(&xxodr);
  51. xp.ReadFile(strpath);
  52. return true;
  53. }
  54. static int getmnfac(OpenDrive & mxodr,double & fmovex,double & fmovey)
  55. {
  56. int nrtn = 1;
  57. int i;
  58. double fxmin,fxmax,fymin,fymax;
  59. fxmin = std::numeric_limits<double>::max() *(1.0);
  60. fxmax = std::numeric_limits<double>::max()*(-1.0);
  61. fymin = std::numeric_limits<double>::max() *(1.0);
  62. fymax = std::numeric_limits<double>::max()*(-1.0);
  63. bool bHaveRealRoad = false;
  64. for(i=0;i<mxodr.GetRoadCount();i++)
  65. {
  66. int j;
  67. Road * pRoad = mxodr.GetRoad(i);
  68. if(pRoad->GetRoadLength()<0.1)
  69. {
  70. continue;
  71. }
  72. bHaveRealRoad = true;
  73. for(j=0;j<mxodr.GetRoad(i)->GetGeometryBlockCount();j++)
  74. {
  75. GeometryBlock * pgeob = pRoad->GetGeometryBlock(j);
  76. double x,y;
  77. RoadGeometry * pg;
  78. pg = pgeob->GetGeometryAt(0);
  79. x = pg->GetX();
  80. y = pg->GetY();
  81. if(x>fxmax)fxmax = x;
  82. if(x<fxmin)fxmin = x;
  83. if(y>fymax)fymax = y;
  84. if(y<fymin)fymin = y;
  85. }
  86. double x,y,hdg;
  87. int nco = pRoad->GetGeometryCoords(pRoad->GetRoadLength()-0.1,x,y,hdg);
  88. if(nco >= 0)
  89. {
  90. if(x>fxmax)fxmax = x;
  91. if(x<fxmin)fxmin = x;
  92. if(y>fymax)fymax = y;
  93. if(y<fymin)fymin = y;
  94. }
  95. }
  96. if(bHaveRealRoad == false)
  97. {
  98. // std::cout<<"No Real Road."<<std::endl;
  99. return 1.0;
  100. }
  101. fmovex = 0;
  102. fmovey = 0;
  103. if(((fxmax>1000)&&(fxmin>1000))||((fxmax<-1000)&&(fxmin<-1000)))
  104. {
  105. fmovex = (fxmax + fxmin)/2.0;
  106. }
  107. if(((fymax>1000)&&(fymin>1000))||((fymax<-1000)&&(fymin<-1000)))
  108. {
  109. fmovey = (fymax + fymin)/2.0;
  110. }
  111. double fabsxmax = fabs(fxmax);
  112. if(fabsxmax < fabs(fxmin))fabsxmax = fabs(fxmin);
  113. double fabsymax = fabs(fymax);
  114. if(fabsymax < fabs(fymin))fabsymax = fabs(fymin);
  115. int nfacx=1;
  116. if(fabsxmax!= 0)
  117. {
  118. nfacx = (VIEW_WIDTH/2)/(fabsxmax*1.2);
  119. }
  120. int nfacy = 1;
  121. if(fabsymax != 0)
  122. {
  123. nfacy = (VIEW_HEIGHT/2)/(fabsymax*1.2);
  124. }
  125. if(nfacx<1)nfacx = 1;
  126. if(nfacy<1)nfacy = 1;
  127. if(nfacx < nfacy)nrtn = nfacx;
  128. else nrtn = nfacy;
  129. if(nrtn<=1)
  130. {
  131. nrtn = 1;
  132. return nrtn;
  133. }
  134. if((nrtn >(VIEW_WIDTH/1600))&&(VIEW_WIDTH>1600))
  135. {
  136. nrtn = nrtn/(VIEW_WIDTH/1600);
  137. }
  138. return nrtn;
  139. }
  140. ivmapview::ivmapview()
  141. {
  142. image = new QImage(VIEW_WIDTH, VIEW_HEIGHT, QImage::Format_RGB32);//画布的初始化大小设为300*300,使用32位颜色
  143. // mimagepaint = new QImage(VIEW_WIDTH, VIEW_HEIGHT, QImage::Format_RGB32);
  144. painter = new QPainter(image);
  145. painter->end();
  146. std::vector<iv::ObstacleBasic> * pobs = new std::vector<iv::ObstacleBasic>();
  147. mobs.reset(pobs);
  148. mnavigation_data.clear();
  149. #ifdef Android
  150. LoadXODR("/storage/emulated/0//map.xodr",mxodr);
  151. #else
  152. if(gstrmode == "false")
  153. LoadXODR("./map.xodr",mxodr);
  154. else
  155. {
  156. char * strhome = getenv("HOME");
  157. char strmappath[256];
  158. snprintf(strmappath,256,"%s/map/map.xodr",strhome);
  159. LoadXODR(strmappath,mxodr);
  160. }
  161. #endif
  162. // qDebug("run hear.");
  163. double fmovex,fmovey;
  164. mnfac = getmnfac(mxodr,fmovex,fmovey);
  165. mfViewMoveX = mfViewMoveX - fmovex;
  166. mfViewMoveY = mfViewMoveY - fmovey;
  167. mnMoveX = VIEW_WIDTH/2;
  168. mnMoveY = VIEW_HEIGHT/2;
  169. mnDefmnfac = mnfac;
  170. mnDefMoveX = mnMoveX;
  171. mnDefMoveY = mnMoveY;
  172. // mnfac = 100;
  173. // mnfac = 20;
  174. unsigned short int revMajor,revMinor;
  175. std::string name,date;
  176. float version;
  177. double north,south,east,west,lat0,lon0,hdg0;
  178. if(mxodr.GetHeader() != 0)
  179. {
  180. mxodr.GetHeader()->GetAllParams(revMajor,revMinor,name,version,date,north,south,east,west,lat0,lon0,hdg0);
  181. glat0 = lat0;
  182. glon0 = lon0;
  183. }
  184. GaussProjCal(glon0,glat0,&mx0,&my0);
  185. }
  186. void ivmapview::run()
  187. {
  188. while(!QThread::isInterruptionRequested())
  189. {
  190. bool bNeedUpdate = false;
  191. if(mnMapMode == 0 )
  192. {
  193. qint64 xTime = QDateTime::currentMSecsSinceEpoch();
  194. if(mnavigation_data.size()> 0)
  195. {
  196. if((xTime - mnTimeGPSUpdate)<3000)
  197. {
  198. bNeedUpdate = true;
  199. }
  200. }
  201. if((xTime - mnTimeLidarOBS)<3000)
  202. {
  203. bNeedUpdate = true;
  204. }
  205. if((xTime-mnTimeRADAR)<3000)
  206. {
  207. bNeedUpdate = true;
  208. }
  209. if(bNeedUpdate)paint();
  210. msleep(100);
  211. }
  212. else
  213. {
  214. mmutexxodrfile.lock();
  215. if(mbNeedReload)
  216. {
  217. mxodr.Clear();
  218. LoadXODR("./map.xodr",mxodr);
  219. mbNeedReload = false;
  220. }
  221. mmutexxodrfile.unlock();
  222. paintxodr();
  223. msleep(100);
  224. std::cout<<"paint."<<std::endl;
  225. }
  226. }
  227. }
  228. void ivmapview::paintxodr()
  229. {
  230. QTime x;
  231. x.start();
  232. // qDebug("painter.");
  233. qint64 xTime = QDateTime::currentMSecsSinceEpoch();
  234. std::vector<iv::MAP_GPS_INS> xnavigation_data;
  235. iv::gps::gpsimu xgpsimu;
  236. mMutexMap.lock();
  237. xnavigation_data = mnavigation_data;
  238. mMutexMap.unlock();
  239. mMutexPaint.lock();
  240. painter->begin(image);
  241. image->fill(QColor(255, 255, 255));//对画布进行填充
  242. // std::vector<iv::GPSData> navigation_data = brain->navigation_data;
  243. painter->setRenderHint(QPainter::Antialiasing, true);//设置反锯齿模式,好看一点
  244. painter->translate(mnMoveX,mnMoveY);
  245. painter->setPen(Qt::black);
  246. // painter->drawLine(VIEW_WIDTH/(-2),0,VIEW_WIDTH/2,0);
  247. // painter->drawLine(0,VIEW_HEIGHT/(-2),0,VIEW_HEIGHT/2);
  248. int i;
  249. // int nfac = 5;;
  250. painter->setPen(Qt::blue);
  251. int nfac = mnfac;
  252. for(i=0;i<mxodr.GetRoadCount();i++)
  253. {
  254. int j;
  255. Road * pRoad = mxodr.GetRoad(i);
  256. for(j=0;j<mxodr.GetRoad(i)->GetGeometryBlockCount();j++)
  257. {
  258. GeometryBlock * pgeob = pRoad->GetGeometryBlock(j);
  259. double x,y;
  260. double x_center,y_center;
  261. double R;
  262. RoadGeometry * pg;
  263. GeometryArc * parc;
  264. GeometryParamPoly3 * ppp3;
  265. GeometrySpiral *pSpiral;
  266. GeometryPoly3 *ppoly;
  267. double rel_x,rel_y,rel_hdg;
  268. pg = pgeob->GetGeometryAt(0);
  269. x = pg->GetX();
  270. y = pg->GetY();
  271. switch (pg->GetGeomType()) {
  272. case 0:
  273. x = x + mfViewMoveX;
  274. y = y + mfViewMoveY;
  275. painter->drawLine(QPoint(x*mnfac,y*mnfac*(-1)),
  276. QPoint((x + pg->GetLength() * cos(pg->GetHdg()))*mnfac,(y + pg->GetLength() * sin(pg->GetHdg()))*mnfac*(-1)));
  277. break;
  278. case 1:
  279. pSpiral = (GeometrySpiral * )pg;
  280. {
  281. int ncount = pSpiral->GetLength() * mnfac;
  282. double sstep = pSpiral->GetLength()/((double)ncount);
  283. int k;
  284. double x0,y0,hdg0,s0;
  285. x0 = pSpiral->GetX();
  286. y0 = pSpiral->GetY();
  287. s0 = pSpiral->GetS();
  288. hdg0 = pSpiral->GetHdg() ;
  289. // painter->setPen(Qt::red);
  290. for(k=0;k<ncount;k++)
  291. {
  292. pSpiral->GetCoords(s0+sstep*k,rel_x,rel_y,rel_hdg);
  293. x = rel_x;
  294. y = rel_y;
  295. x = x + mfViewMoveX;
  296. y = y + mfViewMoveY;
  297. painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
  298. }
  299. // painter->setPen(Qt::blue);
  300. }
  301. // qDebug("spi");
  302. break;
  303. case 2:
  304. {
  305. parc = (GeometryArc *)pg;
  306. R = abs(1.0/parc->GetCurvature());
  307. if(parc->GetCurvature() > 0)
  308. {
  309. x_center = pg->GetX() + R *cos(pg->GetHdg() + M_PI/2.0);
  310. y_center = pg->GetY() + R * sin(pg->GetHdg() + M_PI/2.0);
  311. }
  312. else
  313. {
  314. x_center = pg->GetX() + R *cos(pg->GetHdg() -M_PI/2.0);
  315. y_center = pg->GetY() + R * sin(pg->GetHdg() - M_PI/2.0);
  316. }
  317. int k;
  318. int ncount = parc->GetLength() * mnfac ;
  319. double curv = parc->GetCurvature();
  320. double hdgstep;
  321. double hdg0 = parc->GetHdg();
  322. double hdgnow = parc->GetHdg();
  323. if(ncount > 0) hdgstep= (parc->GetLength()/R)/ncount;
  324. for(k=0;k<ncount;k++)
  325. {
  326. double x_draw,y_draw;
  327. if(curv > 0)
  328. {
  329. hdgnow = hdg0 + k*hdgstep;
  330. x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
  331. y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
  332. }
  333. else
  334. {
  335. hdgnow = hdg0 - k * hdgstep;
  336. x_draw = x_center + R *cos(hdgnow + M_PI/2.0);
  337. y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
  338. }
  339. x_draw = x_draw + mfViewMoveX;
  340. y_draw = y_draw + mfViewMoveY;
  341. painter->drawPoint(x_draw * mnfac ,y_draw * mnfac *(-1));
  342. }
  343. }
  344. break;
  345. case 3:
  346. {
  347. painter->setPen(Qt::red);
  348. ppoly = (GeometryPoly3 *)pg;
  349. x = pg->GetX();
  350. y = pg->GetY();
  351. double A,B,C,D;
  352. A = ppoly->GetA();
  353. B = ppoly->GetB();
  354. C = ppoly->GetC();
  355. D = ppoly->GetD();
  356. const double steplim = 0.1;
  357. double du = steplim;
  358. double u = 0;
  359. double v = 0;
  360. double oldx,oldy;
  361. oldx = x;
  362. oldy = y;
  363. double xstart,ystart;
  364. xstart = x;
  365. ystart = y;
  366. double hdgstart = ppoly->GetHdg();
  367. double flen = 0;
  368. while(flen < ppoly->GetLength())
  369. {
  370. // double fdis = 0;
  371. // v = A + B*u + C*u*u + D*u*u*u;
  372. // x = xstart + u*cos(hdgstart) - v*sin(hdgstart);
  373. // y = ystart + u*sin(hdgstart) + v*cos(hdgstart);
  374. // fdis = sqrt(pow(x- oldx,2)+pow(y-oldy,2));
  375. // oldx = x;
  376. // oldy = y;
  377. // if(fdis>(steplim*2.0))du = du/2.0;
  378. // flen = flen + fdis;
  379. // u = u + du;
  380. double fHdg;
  381. ppoly->GetCoords(flen,x,y,fHdg);
  382. // std::cout<<" x: "<<x<<" y:"<<y<<std::endl;
  383. x = x + mfViewMoveX;
  384. y = y + mfViewMoveY;
  385. painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
  386. flen = flen + steplim;
  387. }
  388. // painter->setPen(Qt::blue);
  389. }
  390. break;
  391. case 4:
  392. {
  393. ppp3 = (GeometryParamPoly3 * )pg;
  394. int ncount = ppp3->GetLength()* mnfac;
  395. double sstep;
  396. if(ncount > 0)sstep = ppp3->GetLength()/ncount;
  397. else sstep = 10000.0;
  398. double s = 0;
  399. while(s < ppp3->GetLength())
  400. {
  401. double fhdg;
  402. ppp3->GetCoords(ppp3->GetS() + s,x,y,fhdg);
  403. // double xtem,ytem;
  404. // xtem = ppp3->GetuA() + ppp3->GetuB() * s + ppp3->GetuC() * s*s + ppp3->GetuD() * s*s*s;
  405. // ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
  406. // x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
  407. // y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
  408. x = x + mfViewMoveX;
  409. y = y + mfViewMoveY;
  410. painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
  411. s = s+ sstep;
  412. }
  413. }
  414. break;
  415. default:
  416. break;
  417. }
  418. // painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
  419. }
  420. }
  421. QPen pen;
  422. pen.setWidth(3);
  423. pen.setColor(Qt::green);
  424. painter->setPen(pen);
  425. double x0,y0;
  426. GaussProjCal(glon0,glat0,&x0,&y0);
  427. int nMapSize = xnavigation_data.size();
  428. for(i=0;i<nMapSize;i++)
  429. {
  430. double x,y;
  431. // GaussProjCal(xnavigation_data.at(i).gps_lng,xnavigation_data.at(i).gps_lat,&x,&y);
  432. x = xnavigation_data.at(i).gps_x;
  433. y = xnavigation_data.at(i).gps_y;
  434. x = x-x0;
  435. y= y-y0;
  436. x = x + mfViewMoveX;
  437. y = y + mfViewMoveY;
  438. painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
  439. }
  440. painter->setPen(Qt::blue);
  441. if((xTime - mnTimeGPSUpdate)<3000)
  442. {
  443. mMutexGPS.lock();
  444. xgpsimu.CopyFrom(mgpsimu);
  445. mMutexGPS.unlock();
  446. painter->setPen(Qt::green);
  447. QPoint xP[4];
  448. double x[4],y[4];
  449. double x0[4],y0[4];
  450. double xu = mnMarkSize*3;
  451. x0[0] = -xu;y0[0] = -xu;
  452. x0[1] = xu*2; y0[1] = 0;
  453. x0[2] = -xu;y0[2] =xu;
  454. x0[3] = 0; y0[3] = 0;
  455. double xnow,ynow,hdgnow;
  456. hdgnow = (90- xgpsimu.heading()) * M_PI/180.0;
  457. GaussProjCal(xgpsimu.lon(),xgpsimu.lat(),&xnow,&ynow);
  458. double xz,yz;
  459. GaussProjCal(glon0,glat0,&xz,&yz);
  460. xnow = xnow - xz;
  461. ynow = ynow - yz;
  462. double hr= hdgnow;
  463. for(i=0;i<4;i++)
  464. {
  465. x[i] = x0[i]*cos(hr) +y0[i]*sin(hr);
  466. y[i] = y0[i]*cos(hr) - x0[i]*sin(hr);
  467. xP[i].setX((xnow + mfViewMoveX)*mnfac + x[i]);
  468. xP[i].setY((ynow + mfViewMoveY)*mnfac*(-1) + y[i]);
  469. }
  470. // painter->drawRect(mfManualX*mnfac-5,mfManualY*mnfac*(-1)-5,10,10);
  471. painter->drawPolygon(xP,4);
  472. painter->setPen(Qt::black);
  473. }
  474. int nstationsize = gvectorpos.size();
  475. for(i=0;i<nstationsize;i++)
  476. {
  477. double xpos,ypos;
  478. GaussProjCal(gvectorpos[i].mflon,gvectorpos[i].mflat,&xpos,&ypos);
  479. double xz,yz;
  480. GaussProjCal(glon0,glat0,&xz,&yz);
  481. xpos = xpos - xz;
  482. ypos = ypos - yz;
  483. painter->setPen(Qt::red);
  484. painter->setBrush(Qt::red)
  485. ; if(i != mnStationIndex)
  486. painter->drawEllipse(QPoint((xpos + mfViewMoveX)*mnfac ,(ypos + mfViewMoveX)*mnfac*(-1)),mnMarkSize,mnMarkSize);
  487. else
  488. painter->drawEllipse(QPoint((xpos + mfViewMoveX)*mnfac ,(ypos + mfViewMoveX)*mnfac*(-1)),2*mnMarkSize,2*mnMarkSize);
  489. painter->setBrush(Qt::NoBrush);
  490. painter->setPen(Qt::black);
  491. }
  492. painter->end();
  493. mMutexPaint.unlock();
  494. mbImageUpdate = true;
  495. qDebug("time is %d",x.elapsed());
  496. // std::cout<<" draw map use: "<<(QDateTime::currentMSecsSinceEpoch() - xTime)<<std::endl;
  497. }
  498. void ivmapview::paint()
  499. {
  500. qint64 xTime = QDateTime::currentMSecsSinceEpoch();
  501. std::vector<iv::MAP_GPS_INS> xnavigation_data;
  502. iv::gps::gpsimu xgpsimu;
  503. mMutexMap.lock();
  504. xnavigation_data = mnavigation_data;
  505. mMutexMap.unlock();
  506. mMutexPaint.lock();
  507. painter->begin(image);
  508. image->fill(QColor(208,208,208));//对画布进行填充
  509. painter->setRenderHint(QPainter::Antialiasing, true);//设置反锯齿模式,好看一点
  510. int pointx = 450, pointy = 700;//确定坐标轴起点坐标,这里定义(35,280)
  511. QPen pen, penPoint;
  512. //先绘制车位置点及框图
  513. static const QPointF points1[2] = { QPointF(300, 700), QPointF(600, 700) };
  514. static const QPointF points2[2] = { QPointF(450, 0), QPointF(450, 900) };
  515. penPoint.setColor(Qt::red);
  516. penPoint.setWidth(2);
  517. painter->setPen(penPoint);
  518. painter->drawPoint(pointx, pointy);
  519. painter->drawPolyline(points1, 2);
  520. painter->drawPolyline(points2, 2);
  521. // std::cout<<"map size is "<<xnavigation_data.size()<<std::endl;
  522. if((xnavigation_data.size()>0)&&((xTime - mnTimeGPSUpdate)<3000))
  523. {
  524. mMutexGPS.lock();
  525. xgpsimu.CopyFrom(mgpsimu);
  526. mMutexGPS.unlock();
  527. double * x0, * y0, * lng, * x1, * y1, * x2, * y2;
  528. std::shared_ptr<double> ptrx0,ptry0,ptrlng,ptrx1,ptry1,ptrx2,ptry2;
  529. int nmapsize = xnavigation_data.size();
  530. x0 = new double[nmapsize];
  531. y0 = new double[nmapsize];
  532. lng = new double[nmapsize];
  533. x1 = new double[nmapsize];
  534. y1 = new double[nmapsize];
  535. x2 = new double[nmapsize];
  536. y2 = new double[nmapsize];
  537. ptrx0.reset(x0);
  538. ptry0.reset(y0);
  539. ptrlng.reset(lng);
  540. ptrx1.reset(x1);
  541. ptry1.reset(y1);
  542. ptrx2.reset(x2);
  543. ptry2.reset(y2);
  544. double xx = 0, yy = 0;
  545. double sumx = 0, sumy = 0;//, ave_x = 0, ave_y = 0;
  546. int sizeN = xnavigation_data.size();
  547. //int max_x_pos = 0, min_x_pos = 0, max_y_pos = 0, min_y_pos = 0;
  548. int x_max = 0, y_max = 0;//数组里的最大值
  549. int x_min = 0x3f3f3f3f, y_min = 0x3f3f3f3f;//inf为 #define inf 0x3f3f3f3f
  550. double k1, k2;
  551. // qDebug("y: %f ",xnavigation_data[1].gps_y);
  552. //路径点的预处理
  553. for (int i = 0; i < sizeN; i++)
  554. {
  555. x0[i] = xnavigation_data[i].gps_x;
  556. y0[i] = xnavigation_data[i].gps_y;
  557. lng[i] = xnavigation_data[i].ins_heading_angle;
  558. sumx = sumx + xnavigation_data[i].gps_x;
  559. sumy = sumy + xnavigation_data[i].gps_y;
  560. if (x0[i] > x_max) {
  561. x_max = x0[i];
  562. //max_x_pos = i;
  563. }
  564. if (x0[i] < x_min) {
  565. x_min = x0[i];
  566. //min_x_pos = i;
  567. }
  568. if (y0[i] > y_max) {
  569. y_max = y0[i];
  570. //max_y_pos = i;
  571. }
  572. if (y0[i] < y_min) {
  573. y_min = y0[i];
  574. //min_y_pos = i;
  575. }
  576. }
  577. //ave_x = sumx / sizeN;
  578. //ave_y = sumy / sizeN;
  579. //获取到实时 GPS信息,并做路径点的显示更新
  580. double gps_x = 0.0,gps_y = 0.0;
  581. // if(DataUI->mInfo.gps_lng!=0.0&&DataUI->mInfo.gps_lat != 0.0)
  582. // {
  583. // GaussProjCal(DataUI->mInfo.gps_lng, DataUI->mInfo.gps_lat, &gps_x, &gps_y);
  584. // }
  585. // if (gps_x == 0)
  586. // {
  587. // painter->drawText(rect(), Qt::AlignLeft, QStringLiteral("等待车辆实时GPS位置信息"));
  588. // }
  589. // else
  590. // {
  591. // x0[0] = gps_x;
  592. // y0[0] = gps_y;
  593. // lng[0] = DataUI->mInfo.gps_inshead;
  594. // }
  595. GaussProjCal(xgpsimu.lon(), xgpsimu.lat(), &gps_x, &gps_y);
  596. // qDebug("now lon:%f lat:%f %f %f ",xgpsimu.lon(),xgpsimu.lat(),xnavigation_data[0].gps_lng,xnavigation_data[0].gps_lat);
  597. x0[0] = gps_x;
  598. y0[0] = gps_y;
  599. lng[0] = xgpsimu.heading();
  600. // qDebug("%f %f %f %f",xnavigation_data[1].gps_x, xnavigation_data[1].gps_y,xnavigation_data[0].gps_lng,xnavigation_data[0].gps_lat);
  601. //根据标定原点的选取,对路径点进行转化
  602. for (int i = 1; i < sizeN; i++)
  603. {
  604. x0[i] = x0[i] - x0[0];
  605. y0[i] = y0[i] - y0[0];
  606. xx = x0[i];
  607. yy = y0[i];
  608. x0[i] = xx * cos(lng[0] * M_PI / 180) - yy * sin(lng[0] * M_PI / 180);
  609. y0[i] = xx * sin(lng[0] * M_PI / 180) + yy * cos(lng[0] * M_PI / 180);
  610. k1 = sin((90 + (lng[i] - lng[0])) * M_PI / 180);
  611. k2 = cos((90 + (lng[i] - lng[0])) * M_PI / 180);
  612. x1[i] = x0[i] + k1 * 5;
  613. y1[i] = y0[i] + k2 * 5;
  614. x2[i] = x0[i] - k1 * 5;
  615. y2[i] = y0[i] - k2 * 5;
  616. }
  617. double kx = (double)(600) / (abs(y_max - y_min));//x轴的系数
  618. double ky = (double)(600) / (abs(y_max - y_min));//y方向的比例系数
  619. //距离车正前方10m处画一条线
  620. static const QPointF points3[2] = { QPointF(0, 700 - 10 * ky), QPointF(900, 700 - 10 * ky) };
  621. painter->drawPolyline(points3, 2);
  622. //绘制路径点
  623. penPoint.setColor(Qt::black);
  624. penPoint.setWidth(1);
  625. for (int i = 1; i < sizeN - 1; i++)
  626. {
  627. painter->setPen(penPoint);//蓝色的笔,用于标记各个点
  628. painter->drawPoint(pointx + x0[i] * kx, pointy - y0[i] * ky);
  629. painter->drawPoint(pointx + x1[i] * kx, pointy - y1[i] * ky);
  630. painter->drawPoint(pointx + x2[i] * kx, pointy - y2[i] * ky);
  631. }
  632. painter->drawPoint(pointx + x0[sizeN - 1] * kx, pointy - y0[sizeN - 1] * ky);//绘制最后一个点
  633. penPoint.setColor(Qt::red);
  634. penPoint.setWidth(2);
  635. painter->drawPoint(pointx + x0[0] * kx, pointy - y0[0] * ky);
  636. }
  637. if(abs(xTime - mnTimeLidarOBS)<3000)
  638. {
  639. std::shared_ptr<std::vector<iv::ObstacleBasic>> xobs;
  640. mMutexOBS.lock();
  641. xobs = mobs;
  642. mMutexOBS.unlock();
  643. painter->setPen(QPen(Qt::red, 2));
  644. int nobssize = xobs->size();
  645. for (unsigned int i = 0; i <nobssize; i++)
  646. {
  647. painter->drawPoint(xobs->at(i).nomal_x*10+450,-xobs->at(i).nomal_y*10+700);
  648. // painter->drawPoint(mlidarpoint.lidar_point[x]* 10 + 450, -mlidarpoint.lidar_point[x+5000]* 10 + 700);
  649. }
  650. }
  651. if(abs(xTime-mnTimeFusion)<3000)
  652. {
  653. // qDebug("update show fusion.");
  654. iv::fusion::fusionobjectarray xfusion;
  655. mMutexFusion.lock();
  656. xfusion.CopyFrom(mfusion);
  657. mMutexFusion.unlock();
  658. painter->setPen(QColor(255,0,0));
  659. for(int a = 0; a < xfusion.obj_size(); a++)
  660. {
  661. for(int b = 0; b < xfusion.obj(a).nomal_centroid_size(); b++)
  662. {
  663. painter->drawPoint((xfusion.obj(a).nomal_centroid(b).nomal_x())*10 + 450, -(xfusion.obj(a).nomal_centroid(b).nomal_y() + 0)*10 + 700);
  664. }
  665. }
  666. }
  667. if(abs(xTime-mnTimeRADAR)<3000)
  668. {
  669. iv::radar::radarobjectarray xradarobj;
  670. mMutexRadar.lock();
  671. xradarobj.CopyFrom(mradarobj);
  672. mMutexRadar.unlock();
  673. painter->setPen(QPen(Qt::black, 2));
  674. painter->setBrush(Qt::yellow);
  675. QFont esr_font("Microsoft YaHei", 10, 75); //第一个属性是字体(微软雅黑),第二个是大小,第三个是加粗(权重是75)
  676. painter->setFont(esr_font);
  677. char coordinate_ear[20];
  678. for (unsigned int i = 0 ; i < xradarobj.obj_size(); i++)
  679. {
  680. iv::radar::radarobject * pobj = xradarobj.mutable_obj(i);
  681. if(pobj->bvalid())
  682. {
  683. painter->drawEllipse(pobj->x() * 10 + 450, -pobj->y() * 10 + 700, 10, 10);
  684. sprintf(coordinate_ear, "(%d, %d)", (int)pobj->x(), (int)pobj->y());
  685. painter->drawText(pobj->x() * 10 + 450, -pobj->y() * 10 + 700, QString(coordinate_ear));
  686. }
  687. }
  688. }
  689. QPixmap pix;
  690. //pix.load("car.png");
  691. pix.load(":/new/pic/car.png");
  692. painter->drawPixmap(435,667,30,67,pix);
  693. painter->end();
  694. mMutexPaint.unlock();
  695. mbImageUpdate = true;
  696. /*
  697. iv::vision::rawpic pic;
  698. mMutex.lock();
  699. pic.CopyFrom(mrawpic);
  700. mMutex.unlock();
  701. cv::Mat mat(pic.height(),pic.width(),pic.mattype());
  702. if(pic.type() == 1)
  703. memcpy(mat.data,pic.picdata().data(),mat.rows*mat.cols*mat.elemSize());
  704. else
  705. {
  706. // qDebug("jpg");
  707. std::vector<unsigned char> buff(pic.picdata().data(),pic.picdata().data()+pic.picdata().size());
  708. mat = cv::imdecode(buff,CV_LOAD_IMAGE_COLOR);
  709. }
  710. cv::cvtColor(mat, mat, CV_BGR2RGB);
  711. QImage image2 = QImage((uchar*)(mat.data), mat.cols, mat.rows, QImage::Format_RGB888);
  712. mMutexPaint.lock();
  713. // delete mimagepaint;
  714. // mimagepaint = new QImage(mat.cols, mat.rows, QImage::Format_RGB888);
  715. *mimagepaint = image2.copy();
  716. // *mimagepaint = image2;
  717. // mimagepaint = new QImage(image2);
  718. mMutexPaint.unlock();
  719. mat.release();
  720. */
  721. }
  722. QImage ivmapview::GetImage()
  723. {
  724. mMutexPaint.lock();
  725. // QImage imagertn(*mimagepaint);
  726. // QImage imagertn(mimagepaint->width(), mimagepaint->height(), QImage::Format_RGB32);
  727. QImage imagertn = image->copy();
  728. mMutexPaint.unlock();
  729. mbImageUpdate = false;
  730. return imagertn;
  731. }
  732. bool ivmapview::IsHaveNew()
  733. {
  734. return mbImageUpdate;
  735. }
  736. int ivmapview::GetType()
  737. {
  738. return 2;
  739. }
  740. void ivmapview::setmap(std::vector<iv::MAP_GPS_INS> xnavigation_data)
  741. {
  742. unsigned int i;
  743. for(i=0;i<xnavigation_data.size();i++)
  744. {
  745. double x,y;
  746. GaussProjCal(xnavigation_data[i].gps_lng,xnavigation_data[i].gps_lat,&x,&y);
  747. xnavigation_data[i].gps_x = x;
  748. xnavigation_data[i].gps_y = y;
  749. // qDebug("x %f y %f ",xnavigation_data[i].gps_lng,xnavigation_data[i].gps_lat);
  750. }
  751. mMutexMap.lock();
  752. mnavigation_data = xnavigation_data;
  753. mnTimeGPSUpdate = QDateTime::currentMSecsSinceEpoch();
  754. qDebug("map updata.");
  755. mMutexMap.unlock();
  756. }
  757. void ivmapview::setgps(iv::gps::gpsimu *pxgpsimu)
  758. {
  759. mMutexGPS.lock();
  760. mgpsimu.CopyFrom(*pxgpsimu);
  761. mnTimeGPSUpdate = QDateTime::currentMSecsSinceEpoch();
  762. mMutexGPS.unlock();
  763. }
  764. void ivmapview::setobs(std::shared_ptr<std::vector<iv::ObstacleBasic> > xobs)
  765. {
  766. mMutexOBS.lock();
  767. mobs = xobs;
  768. mMutexOBS.unlock();
  769. mnTimeLidarOBS = QDateTime::currentMSecsSinceEpoch();
  770. }
  771. void ivmapview::setradar(iv::radar::radarobjectarray *pradarobj)
  772. {
  773. mMutexRadar.lock();
  774. mradarobj.CopyFrom(*pradarobj);
  775. mMutexRadar.unlock();
  776. mnTimeRADAR = QDateTime::currentMSecsSinceEpoch();
  777. }
  778. void ivmapview::setfusion(iv::fusion::fusionobjectarray &xfusion)
  779. {
  780. // qDebug("set fusion.");
  781. mMutexFusion.lock();
  782. mfusion.CopyFrom(xfusion);
  783. mMutexFusion.unlock();
  784. mnTimeFusion = QDateTime::currentMSecsSinceEpoch();
  785. }
  786. void ivmapview::setMapMode(int nMode)
  787. {
  788. mnMapMode = nMode;
  789. }
  790. void ivmapview::setStationIndex(int nStationIndex)
  791. {
  792. mnStationIndex = nStationIndex;
  793. }
  794. void ivmapview::SetXodrRaw(const char * strdata,const unsigned int ndatasize)
  795. {
  796. bool bSave = false;
  797. QFile xFile;
  798. #ifdef ANDROID
  799. xFile.setFileName("/storage/emulated/0//map.xodr");
  800. #else
  801. xFile.setFileName("./map.xodr");
  802. #endif
  803. if(xFile.open(QIODevice::ReadOnly))
  804. {
  805. if(xFile.size() != ndatasize)
  806. {
  807. bSave = true;
  808. std::cout<<" old size: "<<xFile.size()<<" data size: "<<ndatasize<<std::endl;
  809. }
  810. else
  811. {
  812. QByteArray ba = xFile.readAll();
  813. unsigned int i;
  814. char * pold = ba.data();
  815. for(i=0;i<ndatasize;i++)
  816. {
  817. if(pold[i] != strdata[i])
  818. {
  819. bSave = true;
  820. break;
  821. }
  822. }
  823. if(bSave == false)
  824. std::cout<<" not need update . size is same.info is same."<<std::endl;
  825. else
  826. std::cout<<" size is same. but data info is diff."<<std::endl;
  827. }
  828. xFile.close();
  829. }
  830. else
  831. {
  832. if(!xFile.exists())
  833. {
  834. bSave = true;
  835. }
  836. }
  837. if(bSave == false)
  838. {
  839. return;
  840. }
  841. mmutexxodrfile.lock();
  842. if(xFile.open(QIODevice::ReadWrite))
  843. {
  844. xFile.resize(0);
  845. xFile.write(strdata,ndatasize);
  846. xFile.close();
  847. mbNeedReload = true;
  848. }
  849. mmutexxodrfile.unlock();
  850. }