mainwindow.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588
  1. #include "mainwindow.h"
  2. #include "ui_mainwindow.h"
  3. #include <iostream>
  4. #include <QDesktopWidget>
  5. extern char gstr_memname[256];
  6. //std::string gstrItem[] = {"Pitch","Roll","Heading","gyro_x","gyro_y","gyro_z","acce_x","acce_y",
  7. // "acce_z","lat","lon","hgt","vn","ve","vd","state","time","type",
  8. // "latstd","lonstd","hstd","vnstd","vestd","vdstd","rollstd",
  9. // "pitchstd","yawstd","temp","posstate","headstate","satnum","wheeldata"};
  10. std::string gstrItem[] = {"Pitch","Roll","Heading",
  11. "lat","lon","hgt","vn","ve","vd","insstate","rtkstate","satnum",
  12. "gyro_x","gyro_y","gyro_z","acc_x","acc_y","acc_z"};
  13. std::string gstrDiffItem[] ={"PitchDiff","RollDiff","HeadingDiff","latdiff","londiff","hgtdiff",
  14. "vndiff","vediff","vddiff","avglatdiff","avglondiff","avghgtdiff",
  15. "maxPitchDiff","maxRollDiff","maxHeadDiff",
  16. "maxlatdiff","maxlondiff","maxhgtdiff"};
  17. double gdiff[18];
  18. int gdiffcount = 0;
  19. double gdifftotal[6];
  20. std::string gstrCount[] = {"Total","Posstd","Velstd","Posestd","Devtemp","GPSState","WheelData"};
  21. int gcountRaw[] = {0,0,0,0,0,0,0,0};
  22. int gcountFusion[] = {0,0,0,0,0,0,0,0};
  23. MainWindow * gw;
  24. void ListenRaw(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  25. {
  26. (void)index;
  27. (void)dt;
  28. (void)strmemname;
  29. iv::gps::gpsimu xgpsimu;
  30. if(!xgpsimu.ParseFromArray(strdata,nSize))
  31. {
  32. std::cout<<"ListenRaw Parse error."<<std::endl;
  33. }
  34. gw->mMutexraw.lock();
  35. while(gw->mqueueraw.size() > 1000)
  36. {
  37. gw->mqueueraw.pop();
  38. }
  39. gw->mqueueraw.push(xgpsimu);
  40. gcountRaw[0]++;
  41. switch (xgpsimu.type()) {
  42. case 0:
  43. gcountRaw[1]++;
  44. break;
  45. case 1:
  46. gcountRaw[2]++;
  47. break;
  48. case 2:
  49. gcountRaw[3]++;
  50. break;
  51. case 22:
  52. gcountRaw[4]++;
  53. break;
  54. case 32:
  55. gcountRaw[5]++;
  56. break;
  57. case 33:
  58. gcountRaw[6]++;
  59. break;
  60. default:
  61. break;
  62. }
  63. gw->mMutexraw.unlock();
  64. }
  65. void ListenFusion(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  66. {
  67. (void)index;
  68. (void)dt;
  69. (void)strmemname;
  70. iv::gps::gpsimu xgpsimu;
  71. if(!xgpsimu.ParseFromArray(strdata,nSize))
  72. {
  73. std::cout<<"ListenRaw Parse error."<<std::endl;
  74. }
  75. gw->mMutexfusion.lock();
  76. while(gw->mqueuefusion.size() > 1000)
  77. {
  78. gw->mqueuefusion.pop();
  79. }
  80. gw->mqueuefusion.push(xgpsimu);
  81. gcountRaw[0]++;
  82. switch (xgpsimu.type()) {
  83. case 0:
  84. gcountRaw[1]++;
  85. break;
  86. case 1:
  87. gcountRaw[2]++;
  88. break;
  89. case 2:
  90. gcountRaw[3]++;
  91. break;
  92. case 22:
  93. gcountRaw[4]++;
  94. break;
  95. case 32:
  96. gcountRaw[5]++;
  97. break;
  98. case 33:
  99. gcountRaw[6]++;
  100. break;
  101. default:
  102. break;
  103. }
  104. gw->mMutexfusion.unlock();
  105. }
  106. MainWindow::MainWindow(QWidget *parent) :
  107. QMainWindow(parent),
  108. ui(new Ui::MainWindow)
  109. {
  110. ui->setupUi(this);
  111. gw = this;
  112. CreateView();
  113. void * paraw = iv::modulecomm::RegisterRecv(gstr_memname,ListenRaw);
  114. void * pafusion = iv::modulecomm::RegisterRecv("fusion_gpsimu",ListenFusion);
  115. (void)paraw;
  116. (void)pafusion;
  117. QTimer * timer = new QTimer(this);
  118. connect(timer,SIGNAL(timeout()),this,SLOT(onTimer()));
  119. timer->start(5);
  120. setWindowTitle("view_gps");
  121. this->setFixedSize(1300, 500);
  122. QDesktopWidget *deskdop = QApplication::desktop();
  123. QRect rect = deskdop->screenGeometry();
  124. move(rect.width() * 0.75, rect.height() * 0.3);
  125. mparaw = paraw;
  126. mpafusion = pafusion;
  127. }
  128. MainWindow::~MainWindow()
  129. {
  130. iv::modulecomm::Unregister(mpafusion);
  131. iv::modulecomm::Unregister(mparaw);
  132. delete ui;
  133. }
  134. void MainWindow::CreateView()
  135. {
  136. QTabWidget * p = new QTabWidget(ui->centralWidget);
  137. p->setGeometry(30,30,300,300);
  138. CreateTab1View(p);
  139. // CreateTab2View(p);
  140. // CreateTab3View(p);
  141. mTabMain = p;
  142. }
  143. void MainWindow::CreateTab1View(QTabWidget * p)
  144. {
  145. QGroupBox * pGroup = new QGroupBox();
  146. pGroup->setGeometry(0,0,1300,800);
  147. const int TWidth = 1300;
  148. const int nRowDis = 50;
  149. const int nColDis = 200;
  150. const int nIWidth = 95;
  151. const int nIHeight = 30;
  152. int i;
  153. int j;
  154. i=1;j = 0;
  155. int index = 0;
  156. for(auto x : gstrItem)
  157. {
  158. QLabel * pLabel;
  159. QLineEdit * pLineEdit;
  160. pLabel = new QLabel(pGroup);
  161. std::string strname = x;
  162. pLabel->setText(strname.data());
  163. pLineEdit = new QLineEdit(pGroup);
  164. pLabel->setGeometry(10+j*nColDis,i*nRowDis,nIWidth,nIHeight);
  165. pLineEdit->setGeometry(10+j*nColDis+nColDis/2,i*nRowDis,nIWidth,nIHeight);
  166. pLabel->setAlignment(Qt::AlignRight|Qt::AlignCenter);
  167. mpLabelRaw[index] = pLabel;
  168. mpLERaw[index] = pLineEdit;
  169. j++;
  170. if((j+1)*nColDis>TWidth)
  171. {
  172. j= 0;
  173. i++;
  174. }
  175. index++;
  176. }
  177. i++;
  178. i++;
  179. j = 0;
  180. mnCountIndexBase = index;
  181. QScrollArea * pScroll = new QScrollArea();
  182. pScroll->setWidget(pGroup);
  183. p->addTab(pScroll,"gpsimu");
  184. }
  185. void MainWindow::CreateTab2View(QTabWidget * p)
  186. {
  187. QGroupBox * pGroup = new QGroupBox();
  188. pGroup->setGeometry(0,0,1300,800);
  189. const int TWidth = 1300;
  190. const int nRowDis = 50;
  191. const int nColDis = 200;
  192. const int nIWidth = 95;
  193. const int nIHeight = 30;
  194. int i;
  195. int j;
  196. i=1;j = 0;
  197. int index = 0;
  198. for(auto x : gstrItem)
  199. {
  200. QLabel * pLabel;
  201. QLineEdit * pLineEdit;
  202. pLabel = new QLabel(pGroup);
  203. std::string strname = x;
  204. pLabel->setText(strname.data());
  205. pLineEdit = new QLineEdit(pGroup);
  206. pLabel->setGeometry(10+j*nColDis,i*nRowDis,nIWidth,nIHeight);
  207. pLineEdit->setGeometry(10+j*nColDis+nColDis/2,i*nRowDis,nIWidth,nIHeight);
  208. pLabel->setAlignment(Qt::AlignRight|Qt::AlignCenter);
  209. mpLabelFusion[index] = pLabel;
  210. mpLEFusion[index] = pLineEdit;
  211. j++;
  212. if((j+1)*nColDis>TWidth)
  213. {
  214. j= 0;
  215. i++;
  216. }
  217. index++;
  218. }
  219. i++;i++;j= 0;
  220. for(auto x : gstrCount)
  221. {
  222. QLabel * pLabel;
  223. QLineEdit * pLineEdit;
  224. pLabel = new QLabel(pGroup);
  225. std::string strname = x;
  226. pLabel->setText(strname.data());
  227. pLineEdit = new QLineEdit(pGroup);
  228. pLabel->setGeometry(10+j*nColDis,i*nRowDis,nIWidth,nIHeight);
  229. pLineEdit->setGeometry(10+j*nColDis+nColDis/2,i*nRowDis,nIWidth,nIHeight);
  230. pLabel->setAlignment(Qt::AlignRight|Qt::AlignCenter);
  231. mpLabelFusion[index] = pLabel;
  232. mpLEFusion[index] = pLineEdit;
  233. j++;
  234. if((j+1)*nColDis>TWidth)
  235. {
  236. j= 0;
  237. i++;
  238. }
  239. index++;
  240. }
  241. QScrollArea * pScroll = new QScrollArea();
  242. pScroll->setWidget(pGroup);
  243. p->addTab(pScroll,"Fusion");
  244. }
  245. void MainWindow::CreateTab3View(QTabWidget * p)
  246. {
  247. QGroupBox * pGroup = new QGroupBox();
  248. pGroup->setGeometry(0,0,1300,800);
  249. const int TWidth = 1300;
  250. const int nRowDis = 50;
  251. const int nColDis = 200;
  252. const int nIWidth = 95;
  253. const int nIHeight = 30;
  254. int i;
  255. int j;
  256. i=1;j = 0;
  257. int index = 0;
  258. for(auto x : gstrDiffItem)
  259. {
  260. QLabel * pLabel;
  261. QLineEdit * pLineEdit;
  262. pLabel = new QLabel(pGroup);
  263. std::string strname = x;
  264. pLabel->setText(strname.data());
  265. pLineEdit = new QLineEdit(pGroup);
  266. pLabel->setGeometry(10+j*nColDis,i*nRowDis,nIWidth,nIHeight);
  267. pLineEdit->setGeometry(10+j*nColDis+nColDis/2,i*nRowDis,nIWidth,nIHeight);
  268. pLabel->setAlignment(Qt::AlignRight|Qt::AlignCenter);
  269. mpLabelDiff[index] = pLabel;
  270. mpLEDiff[index] = pLineEdit;
  271. j++;
  272. if((j+1)*nColDis>TWidth)
  273. {
  274. j= 0;
  275. i++;
  276. }
  277. index++;
  278. }
  279. QScrollArea * pScroll = new QScrollArea();
  280. pScroll->setWidget(pGroup);
  281. p->addTab(pScroll,"Diff");
  282. }
  283. void MainWindow::resizeEvent(QResizeEvent *event)
  284. {
  285. (void)event;
  286. // qDebug("resize");
  287. QSize sizemain = ui->centralWidget->size();
  288. // qDebug("size x = %d y=%d",sizemain.width(),sizemain.height());
  289. AdjustWPos(sizemain);
  290. }
  291. void MainWindow::AdjustWPos(QSize sizemain)
  292. {
  293. mTabMain->setGeometry(10,10,sizemain.width() - 20,sizemain.height()-10);
  294. }
  295. inline void MainWindow::SetLEView(int nTab, const char *strName, double value, const char * strvalue,const int nType)
  296. {
  297. int i;
  298. QLineEdit * pLE = 0;
  299. int nBase = 0;
  300. if(nType == 3)nBase = mnCountIndexBase;
  301. if(nTab == 0)
  302. {
  303. i = 0;
  304. if(nBase == 0)
  305. {
  306. for(auto x : gstrItem)
  307. {
  308. std::string str = x;
  309. const char * y = str.data();
  310. (void)y;
  311. if(strcmp(str.data(), strName) == 0)
  312. {
  313. pLE = mpLERaw[i+nBase];
  314. break;
  315. }
  316. i++;
  317. }
  318. }
  319. else
  320. {
  321. for(auto x : gstrCount)
  322. {
  323. std::string str = x;
  324. const char * y = str.data();
  325. (void)y;
  326. if(strcmp(str.data(), strName) == 0)
  327. {
  328. pLE = mpLERaw[i+nBase];
  329. break;
  330. }
  331. i++;
  332. }
  333. }
  334. }
  335. if(nTab == 1)
  336. {
  337. i = 0;
  338. if(nBase == 0)
  339. {
  340. for(auto x : gstrItem)
  341. {
  342. std::string str = x;
  343. if(strcmp(str.data(),strName) == 0)
  344. {
  345. pLE = mpLEFusion[i+nBase];
  346. break;
  347. }
  348. i++;
  349. }
  350. }
  351. else
  352. {
  353. for(auto x : gstrCount)
  354. {
  355. std::string str = x;
  356. const char * y = str.data();
  357. (void)y;
  358. if(strcmp(str.data(), strName) == 0)
  359. {
  360. pLE = mpLEFusion[i+nBase];
  361. break;
  362. }
  363. i++;
  364. }
  365. }
  366. }
  367. if(nTab == 2)
  368. {
  369. i = 0;
  370. for(auto x : gstrDiffItem)
  371. {
  372. std::string str = x;
  373. if(strcmp(str.data(), strName) == 0)
  374. {
  375. pLE = mpLEFusion[i];
  376. break;
  377. }
  378. i++;
  379. }
  380. }
  381. if(pLE == 0)
  382. {
  383. return;
  384. }
  385. if(nType == 0)
  386. {
  387. pLE->setText(QString::number(value));
  388. }
  389. if(nType == 1)
  390. {
  391. pLE->setText(QString::number(value,'f',7));
  392. }
  393. if(nType == 2)
  394. {
  395. pLE->setText(strvalue);
  396. }
  397. if(nType == 3)
  398. {
  399. pLE->setText(QString::number(value));
  400. }
  401. }
  402. void MainWindow::UpdateCompView()
  403. {
  404. const int tab = 2;
  405. int i;
  406. for(i=0;i<18;i++)SetLEView(tab,gstrDiffItem[i].data(),gdiff[i]);
  407. }
  408. void MainWindow::UpdateGPSView(const int tab,iv::gps::gpsimu xgpsimu)
  409. {
  410. SetLEView(tab,gstrItem[0].data(),xgpsimu.pitch());
  411. SetLEView(tab,gstrItem[1].data(),xgpsimu.roll());
  412. SetLEView(tab,gstrItem[2].data(),xgpsimu.heading());
  413. SetLEView(tab,gstrItem[3].data(),xgpsimu.lat(),0,1);
  414. SetLEView(tab,gstrItem[4].data(),xgpsimu.lon(),0,1);
  415. SetLEView(tab,gstrItem[5].data(),xgpsimu.height());
  416. SetLEView(tab,gstrItem[6].data(),xgpsimu.vn());
  417. SetLEView(tab,gstrItem[7].data(),xgpsimu.ve());
  418. SetLEView(tab,gstrItem[8].data(),xgpsimu.vd());
  419. SetLEView(tab,gstrItem[9].data(),xgpsimu.ins_state());
  420. SetLEView(tab,gstrItem[10].data(),xgpsimu.rtk_state());
  421. SetLEView(tab,gstrItem[11].data(),xgpsimu.satnum1());
  422. SetLEView(tab,gstrItem[12].data(),xgpsimu.gyro_x());
  423. SetLEView(tab,gstrItem[13].data(),xgpsimu.gyro_y());
  424. SetLEView(tab,gstrItem[14].data(),xgpsimu.gyro_z());
  425. SetLEView(tab,gstrItem[15].data(),xgpsimu.acce_x());
  426. SetLEView(tab,gstrItem[16].data(),xgpsimu.acce_y());
  427. SetLEView(tab,gstrItem[17].data(),xgpsimu.acce_z());
  428. if(fabs(xgpsimu.acce_z()+1.0)>0.1)
  429. {
  430. qDebug("acc is %f gyro z is %f h:%f",xgpsimu.acce_z(),xgpsimu.gyro_z(),
  431. xgpsimu.height());
  432. }
  433. if(fabs(xgpsimu.vd())>0.5)
  434. {
  435. qDebug("vd is %f",xgpsimu.vd());
  436. }
  437. // qDebug("state is %d %d %d",xgpsimu.gps_state().pos_state(),xgpsimu.gps_state().heading_state(),xgpsimu.gps_state().satnum());
  438. // SetLEView(tab,gstrItem[12].data(),xgpsimu.);
  439. }
  440. void MainWindow::CompareData(iv::gps::gpsimu gi, iv::gps::gpsimu gf)
  441. {
  442. gdiff[0] = fabs(gf.pitch() - gi.pitch());
  443. gdiff[1] = fabs(gf.roll() - gi.roll());
  444. gdiff[2] = fabs(gf.heading() - gi.heading());
  445. gdiff[3] = fabs(gf.lat() - gi.lat());
  446. gdiff[4] = fabs(gf.lon() - gi.lon());
  447. gdiff[5] = fabs(gf.height() - gi.height());
  448. gdiff[6] = fabs(gf.vn() - gi.vn());
  449. gdiff[7] = fabs(gf.ve() - gi.ve());
  450. gdiff[8] = fabs(gf.vd() - gi.vd());
  451. gdiffcount++;
  452. gdifftotal[0] += gdiff[3];
  453. gdifftotal[1] += gdiff[4];
  454. gdifftotal[2] += gdiff[5];
  455. gdiff[9] = gdifftotal[0]/gdiffcount;
  456. gdiff[10] = gdifftotal[1]/gdiffcount;
  457. gdiff[11] = gdifftotal[2]/gdiffcount;
  458. int i;
  459. for(i=0;i<6;i++)
  460. if(gdiff[i] > gdiff[12+i])gdiff[12+i]= gdiff[i];
  461. }
  462. void MainWindow::onTimer()
  463. {
  464. static int nLastRaw = 0;
  465. static int nLastFusion = 0;
  466. bool bRawGet = false;
  467. bool bFusionGet = false;
  468. (void)bFusionGet;
  469. iv::gps::gpsimu rawgpsimu,fusiongpsimu;
  470. if(nLastRaw < gcountRaw[0])
  471. {
  472. mMutexraw.lock();
  473. while(mqueueraw.size() > 0)
  474. {
  475. rawgpsimu = mqueueraw.front();
  476. mqueueraw.pop();
  477. mqueuecpraw.push(rawgpsimu);
  478. bRawGet = true;
  479. }
  480. nLastRaw = gcountRaw[0];
  481. mMutexraw.unlock();
  482. }
  483. if(nLastFusion < gcountFusion[0])
  484. {
  485. mMutexfusion.lock();
  486. while(mqueuefusion.size() > 0)
  487. {
  488. rawgpsimu = mqueuefusion.front();
  489. mqueuefusion.pop();
  490. mqueuecpfusion.push(fusiongpsimu);
  491. bFusionGet = true;
  492. }
  493. nLastFusion = gcountFusion[0];
  494. mMutexfusion.unlock();
  495. }
  496. if(bRawGet)UpdateGPSView(0,rawgpsimu);
  497. // if(bFusionGet)UpdateGPSView(1,fusiongpsimu);
  498. // if(bRawGet && bFusionGet)
  499. // {
  500. // while((mqueuecpfusion.size()>0)&&(mqueuecpraw.size()>0))
  501. // {
  502. // iv::gps::gpsimu gi,fi;
  503. // gi = mqueuecpraw.front();
  504. // fi = mqueuecpfusion.front();
  505. // if(gi.time() == fi.time())
  506. // {
  507. // //Compare
  508. // CompareData(gi,fi);
  509. // mqueuecpfusion.pop();
  510. // mqueuecpraw.pop();
  511. // continue;
  512. // }
  513. // if(gi.time() > fi.time())
  514. // {
  515. // mqueuecpfusion.pop();
  516. // }
  517. // if(gi.time() < fi.time())
  518. // {
  519. // mqueuecpraw.pop();
  520. // }
  521. // }
  522. // }
  523. }