mainwindow.cpp 30 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057
  1. #include "mainwindow.h"
  2. #include "ui_mainwindow.h"
  3. #include "pos_def.h"
  4. #include "remotectrlini.h"
  5. MainWindow * gw;
  6. //#include "QStringLiteral"
  7. #ifdef NVIDIA_AGX
  8. #include "opencv2/imgcodecs/legacy/constants_c.h" //OpenCV4 use this line
  9. #include <opencv2/imgproc/types_c.h> //OpenCV4 use this line
  10. #endif
  11. #include <opencv2/opencv.hpp>
  12. #include <opencv2/core.hpp>
  13. iv::gps::gpsimu ggpsimu;
  14. qint64 gTimeGPSIMUUpdate = 0;
  15. iv::vision::rawpic grawpic[CAMERA_NUM];
  16. qint64 gTimeRawPic[CAMERA_NUM] = {0,0,0,0};
  17. QMutex gMutexPic[CAMERA_NUM];
  18. extern std::string gstrmem_gpsimu;
  19. extern std::string gstrmem_pic[CAMERA_NUM];
  20. extern std::vector<iv::pos_def> gvectorpos;
  21. extern std::string gstryaml_path;
  22. class xodrobj
  23. {
  24. public:
  25. double flatsrc;
  26. double flonsrc;
  27. double fhgdsrc;
  28. double flat;
  29. double flon;
  30. int lane;
  31. };
  32. namespace iv {
  33. struct simpletrace
  34. {
  35. double gps_lat = 0;//纬度
  36. double gps_lng = 0;//经度
  37. double gps_x = 0;
  38. double gps_y = 0;
  39. double gps_z = 0;
  40. double ins_heading_angle = 0; //航向角
  41. };
  42. }
  43. std::vector<iv::simpletrace> gvectorsimplerace;
  44. QMutex gMutexTrace;
  45. qint64 gTimeTrace = 0;
  46. void * gpaframe;
  47. void Listenpic(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  48. {
  49. if(nSize<50)return;
  50. int * pnhead = (int * )strdata;
  51. std::cout<<" pac count: "<<*pnhead<<" first pac size: "<<*(pnhead + 1)<<std::endl;
  52. std::cout<<" pic name : "<<strmemname<<std::endl;
  53. int npaccount = *pnhead;
  54. int j;
  55. int ndatapos = 0;
  56. char * strfdata = (char *)(strdata + 11*sizeof(int));
  57. for(j=0;j<npaccount;j++)
  58. {
  59. int ndatasize = *(pnhead +j +1);
  60. char * strframedata = new char[ndatasize];
  61. memcpy(strframedata,strfdata + ndatapos,ndatasize);
  62. ndatapos = ndatapos + ndatasize;
  63. iv::modulecomm::ModuleSendMsg(gpaframe, strframedata,ndatasize);
  64. std::this_thread::sleep_for(std::chrono::milliseconds(15));
  65. }
  66. return;
  67. iv::vision::rawpic pic;
  68. if(false == pic.ParseFromArray(strdata,nSize))
  69. {
  70. std::cout<<"picview Listenpic fail."<<std::endl;
  71. return;
  72. }
  73. int indexpic = -1;
  74. for(int i =0;i<CAMERA_NUM;i++)
  75. {
  76. if(strncmp(strmemname,gstrmem_pic[i].data(),256) == 0)
  77. {
  78. indexpic = i;
  79. break;
  80. }
  81. }
  82. if(indexpic >= 0)
  83. {
  84. gMutexPic[indexpic].lock();
  85. grawpic[indexpic].CopyFrom(pic);
  86. gTimeRawPic[indexpic] = QDateTime::currentMSecsSinceEpoch();
  87. gMutexPic[indexpic].unlock();
  88. gw->saveavi(indexpic);
  89. }
  90. }
  91. void Listensimpletrace(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  92. {
  93. int npoint = nSize/sizeof(iv::simpletrace);
  94. if(npoint < 1)
  95. {
  96. std::cout<<"simple trace is very smalll"<<std::endl;
  97. return;
  98. }
  99. gMutexTrace.lock();
  100. gvectorsimplerace.clear();
  101. gvectorsimplerace.resize(npoint);
  102. memcpy(gvectorsimplerace.data(),strdata,npoint*sizeof(iv::simpletrace));
  103. gTimeTrace = QDateTime::currentMSecsSinceEpoch();
  104. gMutexTrace.unlock();
  105. }
  106. void Listengpsimu(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  107. {
  108. // ggpsimu->UpdateGPSIMU(strdata,nSize);
  109. iv::gps::gpsimu xgpsimu;
  110. if(!xgpsimu.ParseFromArray(strdata,nSize))
  111. {
  112. std::cout<<"ListenRaw Parse error."<<std::endl;
  113. }
  114. ggpsimu.CopyFrom(xgpsimu);
  115. gTimeGPSIMUUpdate = QDateTime::currentMSecsSinceEpoch();
  116. }
  117. MainWindow::MainWindow(QWidget *parent)
  118. : QMainWindow(parent)
  119. , ui(new Ui::MainWindow)
  120. {
  121. gpaframe = iv::modulecomm::RegisterSend("h264frame",1000000,1);
  122. gw = this;
  123. ui->setupUi(this);
  124. mstrserverip = ServiceRCIni.GetServerIP();
  125. mstrserverport = ServiceRCIni.GetServerPort();
  126. mstruploadinterval = ServiceRCIni.GetInterval();
  127. mstrVehVIN = ServiceRCIni.GetVIN();
  128. mstrqueryMD5 = ServiceRCIni.GetQueryMD5();
  129. mstrctrlMD5 = ServiceRCIni.GetCtrlMD5();
  130. mpJRT = new JoyReadThread();
  131. mpJRT->start();
  132. int i;
  133. CreateView();
  134. mpPicView = new IVPicView();
  135. mpPicView->start();
  136. int nstation = gvectorpos.size();
  137. for(i=0;i<nstation;i++)
  138. {
  139. ui->comboBox_Station->addItem(gvectorpos[i].mstrstationname.data());
  140. }
  141. ui->radioButton_auto->setChecked(true);
  142. mpa = iv::modulecomm::RegisterSend("remotectrl",10000,1);
  143. mpTimerManual = new QTimer(this);
  144. connect(mpTimerManual,SIGNAL(timeout()),this,SLOT(onTimerManual()));
  145. mpTimerRemote = new QTimer(this);
  146. connect(mpTimerRemote,SIGNAL(timeout()),this,SLOT(onTimerRemote()));
  147. mpTimerRemote->start(10);
  148. mpTimerUpdateView = new QTimer(this);
  149. connect(mpTimerUpdateView,SIGNAL(timeout()),this,SLOT(onTimerUpdateView()));
  150. mpTimerUpdateView->start(1000);
  151. QTimer * timer = new QTimer(this);
  152. connect(timer,SIGNAL(timeout()),this,SLOT(onTimerUpdatePic()));
  153. timer->start(10);
  154. mpadst = iv::modulecomm::RegisterSend("xodrreq",1000,1);
  155. mgrpcpc = new grpcpc(gstryaml_path);
  156. mgrpcpc->setserverip(mstrserverip);
  157. mgrpcpc->setserverport(mstrserverport);
  158. mgrpcpc->setqueryinterval(mstruploadinterval);
  159. mgrpcpc->setVIN(mstrVehVIN);
  160. mgrpcpc->setqueryMD5(mstrqueryMD5);
  161. mgrpcpc->setctrlMD5(mstrctrlMD5);
  162. mgrpcpc->start();
  163. for(i=0;i<NUM_CAM;i++)
  164. {
  165. mpImageCam[i] = new QImage(640, 360, QImage::Format_RGB32);
  166. mbCamUpdate[i] = false;
  167. mph264decode[i] = new ivh264framedecode(mnframewidth,mnframeheight);
  168. mpthreadframe[i] = new std::thread(&MainWindow::threadframe,this,i);
  169. mpthreadpic[i] = new std::thread(&MainWindow::threadpic,this,i);
  170. }
  171. mstrVIN = mgrpcpc->GetVIN().data();
  172. mstrVIN = " VIN:"+ mstrVIN+" ";
  173. mpPicSave[0] = new ivpicsave("./","front",mstrVIN.toStdString());
  174. mpPicSave[1] = new ivpicsave("./","rear",mstrVIN.toStdString());
  175. mpPicSave[2] = new ivpicsave("./","left",mstrVIN.toStdString());
  176. mpPicSave[3] = new ivpicsave("./","right",mstrVIN.toStdString());
  177. for(i=0;i<4;i++)
  178. {
  179. mpPicSave[i]->start();
  180. }
  181. mppicdlg = new DialogPic(this);
  182. mppicdlg->setModal(false);
  183. connect(mppicdlg,SIGNAL(finished(int)),this,SLOT(onCloseDlg()));
  184. mpbigpicdlg = new DialogBigPic(this);
  185. mpbigpicdlg->setModal(false);
  186. connect(mpbigpicdlg,SIGNAL(finished(int)),this,SLOT(onCloseBigDlg()));
  187. QLabel * pLabel = new QLabel();
  188. pLabel->setFixedWidth(600);
  189. pLabel->setText("Latency");
  190. mpLabelLatency = pLabel;
  191. ui->statusbar->addPermanentWidget(pLabel);
  192. mpasimpletrace = iv::modulecomm::RegisterRecv("simpletrace",Listensimpletrace);
  193. void * pa = iv::modulecomm::RegisterRecv(gstrmem_gpsimu.data(),Listengpsimu);
  194. for(i=0;i<CAMERA_NUM;i++)
  195. pa = iv::modulecomm::RegisterRecv(gstrmem_pic[i].data(),Listenpic);
  196. connect(this,SIGNAL(CamUpdate(int)),this,SLOT(onCamUpdate(int)));
  197. // mpbaiduapp = new pluginapp(this->winId(),"baidu","baidumapshow","/home/yuchuli/qt/modularization/src/plugin/build-baidumapshow-Debug");
  198. // mppicshow = new pluginapp(this->winId(),"main","plugin_picshow","/home/yuchuli/qt/modularization/src/plugin/build-plugin_picshow-Debug");
  199. // mppicshow->SetAttr("rawpicmsgname",gstrmem_pic[0].data(),gstrmem_pic[0].size());
  200. setWindowTitle(mstrProgName +mstrVIN+ mstrGPSTime + mstrPicTime);
  201. }
  202. MainWindow::~MainWindow()
  203. {
  204. // delete mppicshow;
  205. // delete mpbaiduapp;
  206. mbThreadrun = false;
  207. int i;
  208. for(i=0;i<NUM_CAM;i++)
  209. {
  210. // mph264decode[i] = new ivh264framedecode(mnframewidth,mnframeheight);
  211. mpthreadframe[i]->join();
  212. mpthreadpic[i]->join();
  213. }
  214. delete ui;
  215. }
  216. void MainWindow::CreateView()
  217. {
  218. mMapview = new QWebEngineView(ui->centralwidget);
  219. // qDebug((QDir::currentPath()).toLatin1().data());
  220. mMapview->load(QUrl(QString("file:///%1/%2").arg(QApplication::applicationDirPath()).arg("BaiDuMap.html")));
  221. mMapview->setGeometry(10,10,800,800);
  222. // mMapview->page()->runJavaScript("theLocation(117.355,39.066);"); //117.355,39.066
  223. mpWheel = new Speed(ui->groupBox_rem);
  224. mpWheel->settitle(QStringLiteral("方向盘"));
  225. mpAcc = new Speed(ui->groupBox_rem);
  226. mpAcc->settitle(QStringLiteral("油门"));
  227. mpAcc->updatevalue(0);
  228. mpAcc->setminvalue(0);
  229. mpAcc->setmaxvalue(100);
  230. mpBrake = new Speed(ui->groupBox_rem);
  231. mpBrake->settitle(QStringLiteral("刹车"));
  232. mpBrake->updatevalue(0);
  233. mpBrake->setminvalue(0);
  234. mpBrake->setmaxvalue(100);
  235. mmyview = new MyView(ui->centralwidget);
  236. mmyview->setObjectName(QStringLiteral("graphicsView"));
  237. mmyview->setGeometry(QRect(30, 30, 600, 600));
  238. mmyview->setCacheMode(mmyview->CacheBackground);
  239. mscene = new QGraphicsScene;
  240. ui->radioButton_Null->setChecked(true);
  241. ui->radioButton_picfront->setChecked(true);
  242. }
  243. void MainWindow::keyPressEvent(QKeyEvent *event)
  244. {
  245. //按键按下,key值放入容器,如果是长按触发的repeat就不判断
  246. if(!event->isAutoRepeat())
  247. mPressKeys.insert(event->key());
  248. }
  249. void MainWindow::keyReleaseEvent(QKeyEvent *event)
  250. {
  251. if(!event->isAutoRepeat())mPressKeys.remove(event->key());
  252. qDebug("key count is %d",mPressKeys.count());
  253. }
  254. void MainWindow::resizeEvent(QResizeEvent *event)
  255. {
  256. QSize sizemain = ui->centralwidget->size();
  257. qDebug("size x = %d y=%d",sizemain.width(),sizemain.height());
  258. mMapview->setVisible(false);
  259. // mMapview->setGeometry(10,10,sizemain.width()/2,sizemain.height()*3/5);
  260. // mpbaiduapp->SetGeometry(10,30,sizemain.width()/2,sizemain.height()*3/5);
  261. mmyview->setGeometry(10+sizemain.width()/2+10,10,sizemain.width()/2-30,sizemain.height()*3/5);
  262. int nfrontpos_x = sizemain.width()/6;
  263. int nfrontpos_y = sizemain.height()/3;
  264. int nfrontsize_x = sizemain.width()*2/3;
  265. int nfrontsize_y = sizemain.height() * 2/3;
  266. mmyview->setGeometry(nfrontpos_x,nfrontpos_y,nfrontsize_x,nfrontsize_y);
  267. // mppicshow->SetGeometry(10+sizemain.width()/2+10,10,sizemain.width()/2-30,sizemain.height()*3/5);
  268. // ui->lineEdit_lat->setGeometry(sizemain.width()-100,10,90,30);
  269. // ui->lineEdit_lon->setGeometry(sizemain.width()-100,50,90,30);
  270. // ui->pushButton_test->setGeometry(sizemain.width()-100,90,90,30);
  271. ui->lineEdit_lat->setVisible(false);
  272. ui->lineEdit_lon->setVisible(false);
  273. ui->pushButton_test->setVisible(false);
  274. // mpWheel->setGeometry(sizemain.width()/2 + 20,10,200,200);
  275. int grouppos_x = sizemain.width()*5/6;
  276. int grouppos_y = sizemain.height()/3;
  277. int grouppos_width = sizemain.width()*1/6;
  278. int grouppos_height = sizemain.height() * 2/3;
  279. // int speed_width = grouppos_height-40;
  280. // if((speed_width*3 + 150)>grouppos_width)speed_width = (grouppos_width - 150)/3;
  281. int speed_width = grouppos_width;
  282. if(speed_width*3 > (sizemain.height()/2))speed_width = sizemain.height()/6;
  283. mpWheel->setGeometry(0,sizemain.height()/6 ,speed_width,speed_width);
  284. mpBrake->setGeometry(0,sizemain.height()/6 + sizemain.height()/6,speed_width,speed_width);
  285. mpAcc->setGeometry(0 ,sizemain.height()/6 + sizemain.height()/3,speed_width,speed_width);
  286. ui->groupBox_rem->setGeometry(grouppos_x,grouppos_y,grouppos_width,grouppos_height);
  287. // int grouppic_x = 10 + sizemain.width()*6/10 + 10;
  288. // int grouppic_y = 20 + sizemain.height() *3/5;
  289. // int grouppic_width = sizemain.width()*4/10 - 30;
  290. // int grouppic_height = sizemain.height()*1/10;
  291. // ui->groupBox_picsel->setGeometry(grouppic_x,grouppic_y,grouppic_width,grouppic_height);
  292. ui->groupBox_picsel->setVisible(false);
  293. int groupmap_x = 0;
  294. int groupmap_y = sizemain.height()*1/3;
  295. int groupmap_width = sizemain.width()/6;
  296. int groupmap_height = sizemain.height()*1/10;
  297. ui->comboBox_Station->setGeometry(10,30,groupmap_width*3/5,30);
  298. ui->pushButton_Go->setGeometry(20 + groupmap_width*3/5,30,groupmap_width*2/5 - 30,30);
  299. ui->groupBox_map->setGeometry(groupmap_x,groupmap_y,groupmap_width,groupmap_height);
  300. int groupgps_x = 0;
  301. int groupgps_y = sizemain.height()/2;
  302. int groupgps_width = sizemain.width()/6;
  303. int groupgps_height = sizemain.height()/2;
  304. ui->groupBox_gps->setGeometry(groupgps_x,groupgps_y,groupgps_width,groupgps_height);
  305. int lablewidth = (groupgps_width-50)*2/10;
  306. int lewidth = (groupgps_width-50)*3/10;
  307. int leheight = 26;
  308. int nypos = 40;
  309. ui->label_gpsins->setGeometry(10,nypos,lablewidth,leheight);
  310. ui->lineEdit_gpsins->setGeometry(20+lablewidth,nypos,lewidth,leheight);
  311. ui->label_gpsrtk->setGeometry(30+lablewidth+lewidth,nypos,lablewidth,leheight);
  312. ui->lineEdit_gpsrtk->setGeometry(40+2*lablewidth +lewidth,nypos,lewidth,leheight);
  313. nypos = nypos + leheight*11/10;
  314. ui->label_gpslon->setGeometry(10,nypos,lablewidth,leheight);
  315. ui->lineEdit_gpslon->setGeometry(20+lablewidth,nypos,lewidth,leheight);
  316. ui->label_gpslat->setGeometry(30+lablewidth+lewidth,nypos,lablewidth,leheight);
  317. ui->lineEdit_gpslat->setGeometry(40+2*lablewidth +lewidth,nypos,lewidth,leheight);
  318. nypos = nypos + leheight*11/10;
  319. ui->label_gpsheading->setGeometry(10,nypos,lablewidth,leheight);
  320. ui->lineEdit_gpsheading->setGeometry(20+lablewidth,nypos,lewidth,leheight);
  321. ui->label_gpsheight->setGeometry(30+lablewidth+lewidth,nypos,lablewidth,leheight);
  322. ui->lineEdit_gpsheight->setGeometry(40+2*lablewidth +lewidth,nypos,lewidth,leheight);
  323. nypos = nypos + leheight*11/10;
  324. ui->label_gpsspeed->setGeometry(10,nypos,lablewidth,leheight);
  325. ui->lineEdit_gpsspeed->setGeometry(20+lablewidth,nypos,lewidth,leheight);
  326. ui->label_gpssat->setGeometry(30+lablewidth+lewidth,nypos,lablewidth,leheight);
  327. ui->lineEdit_gpssat->setGeometry(40+2*lablewidth +lewidth,nypos,lewidth,leheight);
  328. double fscale = (sizemain.width()*2/3)/1920.0;
  329. double fscale2 = (sizemain.height()*2/3)/1080.0;
  330. if(fscale > fscale2) fscale = fscale2;
  331. mmyview->viewscaleto(fscale);
  332. }
  333. void MainWindow::on_pushButton_test_clicked()
  334. {
  335. double flat = ui->lineEdit_lat->text().toDouble();
  336. double flon = ui->lineEdit_lon->text().toDouble();
  337. char strscript[256];
  338. snprintf(strscript,255,"theLocation(%11.7f,%11.7f);",flon,flat);
  339. mMapview->page()->runJavaScript(strscript);
  340. }
  341. void MainWindow::on_radioButton_manual_clicked()
  342. {
  343. ui->radioButton_manual->setChecked(true);
  344. mPressKeys.clear();
  345. mfAcc = 0;
  346. mfWheel = 0;
  347. mfBrake = 0;
  348. mpWheel->updatevalue(mfWheel);
  349. mpAcc->updatevalue(mfAcc);
  350. mpBrake->updatevalue(mfBrake);
  351. mManualTime.restart();
  352. mnLastTime = mManualTime.elapsed();
  353. mpTimerManual->start(10);
  354. }
  355. void MainWindow::onTimerManual()
  356. {
  357. double fOldWheel = mfWheel;
  358. double fOldAcc = mfAcc;
  359. double fOldBrake = mfBrake;
  360. int timediff = mManualTime.elapsed() - mnLastTime;
  361. mnLastTime = mManualTime.elapsed();
  362. int nOldShift = mnShift;
  363. if(mpJRT->isOK())
  364. {
  365. mfWheel = mpJRT->GetWheel() * (-100.0)/32768.0;
  366. mfAcc = ((mpJRT->GetAcc()-32767.0)/65535)*(-100.0);
  367. mfBrake = ((mpJRT->GetBrake()-32767.0)/65535)*(-100.0);
  368. if(mfWheel != fOldWheel)mpWheel->updatevalue(mfWheel);
  369. if(mfAcc != fOldAcc)mpAcc->updatevalue(mfAcc);
  370. if(mfBrake != fOldBrake)mpBrake->updatevalue(mfBrake);
  371. int x = mpJRT->GetShift();
  372. if(x > 0)mnShift = 1;
  373. if(x == 0)mnShift = 0;
  374. if(x < 0)mnShift = -1;
  375. if(mnShift != nOldShift)
  376. {
  377. switch (mnShift) {
  378. case 1:
  379. ui->radioButton_Drive->setChecked(true);
  380. ui->radioButton_picfront->setChecked(true);
  381. on_radioButton_picfront_clicked();
  382. break;
  383. case 0:
  384. ui->radioButton_Null->setChecked(true);
  385. break;
  386. case -1:
  387. ui->radioButton_Rear->setChecked(true);
  388. ui->radioButton_picrear->setChecked(true);
  389. on_radioButton_picrear_clicked();
  390. break;
  391. default:
  392. break;
  393. }
  394. }
  395. return;
  396. }
  397. if(mPressKeys.contains(Qt::Key_A)&&(mPressKeys.contains((Qt::Key_D))))
  398. {
  399. mfWheel = mfWheel;
  400. }
  401. else
  402. {
  403. if(mPressKeys.contains(Qt::Key_A))
  404. {
  405. if(mfWheel<0)mfWheel = 0;
  406. else
  407. {
  408. mfWheel = mfWheel + timediff*mfWheelSpeed/1000;
  409. if(mfWheel < -100)mfWheel = -100;
  410. if(mfWheel > 100 )mfWheel = 100;
  411. }
  412. }
  413. if(mPressKeys.contains(Qt::Key_D))
  414. {
  415. if(mfWheel>0)mfWheel = 0;
  416. else
  417. {
  418. mfWheel = mfWheel - timediff*mfWheelSpeed/1000;
  419. if(mfWheel < -100)mfWheel = -100;
  420. if(mfWheel > 100 )mfWheel = 100;
  421. }
  422. }
  423. }
  424. if(!mPressKeys.contains(Qt::Key_A)&&(!mPressKeys.contains((Qt::Key_D))))
  425. {
  426. if(mfWheel != 0)
  427. {
  428. if(mfWheel > 0)mfWheel = mfWheel - timediff*mfWheelAutoDownSpeed/1000;
  429. else mfWheel = mfWheel + timediff*mfWheelAutoDownSpeed/1000;
  430. if(fabs(mfWheel)< 10)mfWheel =0;
  431. }
  432. }
  433. if(mPressKeys.contains(Qt::Key_W)&&(mPressKeys.contains((Qt::Key_S))))
  434. {
  435. mfAcc = 0;
  436. mfBrake = mfBrake + timediff*mfBrakeSpeed/1000;
  437. if(mfBrake<0)mfBrake = 0;
  438. if(mfBrake > 100)mfBrake = 100;
  439. }
  440. else
  441. {
  442. if(mPressKeys.contains(Qt::Key_W))
  443. {
  444. mfBrake = 0;
  445. mfAcc = mfAcc + timediff*mfAccSpeed/1000;
  446. if(mfAcc<0)mfAcc = 0;
  447. if(mfAcc > 100)mfAcc = 100;
  448. }
  449. if(mPressKeys.contains(Qt::Key_S))
  450. {
  451. mfAcc = 0;
  452. mfBrake = mfBrake + timediff*mfBrakeSpeed/1000;
  453. if(mfBrake<0)mfBrake = 0;
  454. if(mfBrake > 100)mfBrake = 100;
  455. }
  456. }
  457. if(!mPressKeys.contains(Qt::Key_W)&&(!mPressKeys.contains((Qt::Key_S))))
  458. {
  459. if(mfBrake != 0)
  460. {
  461. mfBrake = mfBrake - timediff*mfBrakeAutoDownSpeed/1000;
  462. if(mfBrake<0)mfBrake = 0;
  463. if(mfBrake > 100)mfBrake = 100;
  464. }
  465. if(mfAcc != 0)
  466. {
  467. mfAcc = mfAcc - timediff*mfAccAutoDownSpeed/1000;
  468. if(mfAcc<0)mfAcc = 0;
  469. if(mfAcc > 100)mfAcc = 100;
  470. }
  471. }
  472. if(mfWheel != fOldWheel)mpWheel->updatevalue(mfWheel);
  473. if(mfAcc != fOldAcc)mpAcc->updatevalue(mfAcc);
  474. if(mfBrake != fOldBrake)mpBrake->updatevalue(mfBrake);
  475. }
  476. void MainWindow::on_radioButton_auto_clicked()
  477. {
  478. ui->radioButton_auto->setChecked(true);
  479. mPressKeys.clear();
  480. mpTimerManual->stop();
  481. }
  482. void MainWindow::onTimerRemote()
  483. {
  484. if(ui->radioButton_auto->isChecked())
  485. {
  486. mremotectrl.set_ntype(iv::remotectrl_CtrlType_AUTO);
  487. // mfAcc = 0;
  488. // mfBrake = 0;
  489. // mfWheel =0;
  490. // mpWheel->updatevalue(mfWheel);
  491. // mpAcc->updatevalue(mfAcc);
  492. // mpBrake->updatevalue(mfBrake);
  493. }
  494. else
  495. {
  496. mremotectrl.set_ntype(iv::remotectrl_CtrlType_REMOTE);
  497. }
  498. mremotectrl.set_acc(mfAcc);
  499. mremotectrl.set_brake(mfBrake);
  500. mremotectrl.set_wheel(mfWheel);
  501. mremotectrl.set_shift(mnShift);
  502. int nsersize = mremotectrl.ByteSize();
  503. char * strbuf = new char[nsersize];
  504. if(mremotectrl.SerializeToArray(strbuf,nsersize))
  505. {
  506. iv::modulecomm::ModuleSendMsg(mpa,strbuf,nsersize);
  507. }
  508. delete strbuf;
  509. }
  510. void MainWindow::onTimerUpdatePic()
  511. {
  512. static qint64 time_pic = 0;
  513. static qint64 time_trace = 0;
  514. static int pos = 0;
  515. static std::vector<iv::simpletrace> xvectorsimpletrace;
  516. if((mnSelPic>=0)&&(mnSelPic<4))
  517. {
  518. if((gTimeRawPic[mnSelPic] != time_pic) && (gTimeRawPic[mnSelPic] != 0))
  519. // if((gTimeRawPic[mnSelPic] != time_pic))
  520. {
  521. time_pic = gTimeRawPic[mnSelPic];
  522. iv::vision::rawpic xpic;
  523. gMutexPic[mnSelPic].lock();
  524. xpic.CopyFrom(grawpic[mnSelPic]);
  525. gMutexPic[mnSelPic].unlock();
  526. mpPicView->SetPic(xpic);
  527. }
  528. }
  529. if(mpPicView->IsHaveNew())update();
  530. if(gTimeTrace != time_trace)
  531. {
  532. time_trace = gTimeTrace;
  533. gMutexTrace.lock();
  534. xvectorsimpletrace = gvectorsimplerace;
  535. gMutexTrace.unlock();
  536. pos = 0;
  537. if(xvectorsimpletrace.size()> 0)
  538. {
  539. QJsonArray num_json,num2_json; //声明QJsonArray
  540. QJsonDocument num_document,num2_document; //将QJsonArray改为QJsonDocument类
  541. QByteArray num_byteArray,num2_byteArray; //
  542. int i=0;
  543. for(i=0;i<xvectorsimpletrace.size();i++) //将数组传入压入num_json
  544. {
  545. num_json.append(xvectorsimpletrace[i].gps_lng);
  546. num2_json.append(xvectorsimpletrace[i].gps_lat);
  547. }
  548. num_document.setArray(num_json);
  549. num2_document.setArray(num2_json);
  550. num_byteArray = num_document.toJson(QJsonDocument::Compact);
  551. num2_byteArray = num2_document.toJson(QJsonDocument::Compact);
  552. QString numJson(num_byteArray); //再转为QString
  553. QString num2Json(num2_byteArray); //再转为QString
  554. QString cmd = QString("settrace(\"%1\",\"%2\")").arg(numJson).arg(num2Json);
  555. mMapview->page()->runJavaScript(cmd);
  556. }
  557. }
  558. // if(pos<xvectorsimpletrace.size())
  559. // {
  560. // if(pos == 0)
  561. // {
  562. // mMapview->page()->runJavaScript("clear()");
  563. // }
  564. // char strscript[256];
  565. // snprintf(strscript,255,"mapLocation(%11.7f,%11.7f);",xvectorsimpletrace[pos].gps_lng,xvectorsimpletrace[pos].gps_lat);
  566. // mMapview->page()->runJavaScript(strscript);
  567. // pos++;
  568. // }
  569. }
  570. void MainWindow::onTimerUpdateView()
  571. {
  572. static qint64 time_gps = 0;
  573. unsigned int i;
  574. char strlatency[1000];
  575. char strtem[100];
  576. snprintf(strlatency,1000,"Latency(Up|FrameRate|Down): ");
  577. snprintf(strtem,100,"FT(%d|%d|%d) ",mgrpcpc->GetPicLatency(0),mgrpcpc->GetFrameRate(0),mgrpcpc->GetPicDownLatency(0));strncat(strlatency,strtem,1000);
  578. snprintf(strtem,100,"RR(%d|%d|%d) ",mgrpcpc->GetPicLatency(1),mgrpcpc->GetFrameRate(1),mgrpcpc->GetPicDownLatency(1));strncat(strlatency,strtem,1000);
  579. snprintf(strtem,100,"LT(%d|%d|%d) ",mgrpcpc->GetPicLatency(2),mgrpcpc->GetFrameRate(2),mgrpcpc->GetPicDownLatency(2));strncat(strlatency,strtem,1000);
  580. snprintf(strtem,100,"RT(%d|%d|%d) ",mgrpcpc->GetPicLatency(3),mgrpcpc->GetFrameRate(3),mgrpcpc->GetPicDownLatency(3));strncat(strlatency,strtem,1000);
  581. mpLabelLatency->setText(strlatency);
  582. if(gTimeGPSIMUUpdate != time_gps)
  583. {
  584. time_gps = gTimeGPSIMUUpdate;
  585. char strscript[256];
  586. snprintf(strscript,255,"theLocation(%11.7f,%11.7f,%11.3f);",ggpsimu.lon(),ggpsimu.lat(),ggpsimu.heading());
  587. mMapview->page()->runJavaScript(strscript);
  588. iv::gps::gpsimu xgpsimu;
  589. xgpsimu.CopyFrom(ggpsimu);
  590. ui->lineEdit_gpsins->setText(QString::number(xgpsimu.ins_state()));
  591. ui->lineEdit_gpsrtk->setText(QString::number(xgpsimu.rtk_state()));
  592. ui->lineEdit_gpslon->setText(QString::number(xgpsimu.lon(),'f',7));
  593. ui->lineEdit_gpslat->setText(QString::number(xgpsimu.lat(),'f',7));
  594. ui->lineEdit_gpsheading->setText(QString::number(xgpsimu.heading(),'f',2));
  595. ui->lineEdit_gpsheight->setText(QString::number(xgpsimu.height(),'f',2));
  596. ui->lineEdit_gpsspeed->setText(QString::number(xgpsimu.speed(),'f',2));
  597. ui->lineEdit_gpssat->setText(QString::number(xgpsimu.satnum1()));
  598. mstrGPSTime = QDateTime::fromMSecsSinceEpoch(xgpsimu.msgtime()).toString("GPS: yyyy-MM-dd hh:mm:ss ");
  599. setWindowTitle(mstrProgName + mstrVIN + mstrGPSTime + mstrPicTime);
  600. }
  601. }
  602. void MainWindow::paintEvent(QPaintEvent *)
  603. {
  604. if(mbCamUpdate[0])
  605. {
  606. std::cout<<" copy image. "<<std::endl;
  607. mMutexCam[0].lock();
  608. QImage image = mpImageCam[0]->copy();
  609. mbCamUpdate[0] = false;
  610. mMutexCam[0].unlock();
  611. // QImage image = mpPicView->GetImage();
  612. mscene->clear();
  613. mscene->addPixmap(QPixmap::fromImage(image));
  614. mmyview->setScene(mscene);
  615. mmyview->show();
  616. }
  617. if(!mpPicView->IsHaveNew())
  618. {
  619. return;
  620. }
  621. else
  622. {
  623. }
  624. }
  625. void MainWindow::on_pushButton_Go_clicked()
  626. {
  627. if(ui->comboBox_Station->currentIndex() < 0)return;
  628. int index = ui->comboBox_Station->currentIndex();
  629. if(index<0 || index>= gvectorpos.size())
  630. {
  631. std::cout<<"out range."<<std::endl;
  632. return;
  633. }
  634. iv::pos_def xpos = gvectorpos[index];
  635. double lon,lat;
  636. lon = xpos.mflon;
  637. lat = xpos.mflat;
  638. xodrobj xo;
  639. xo.flon = lon;
  640. xo.flat = lat;
  641. xo.lane = 3;
  642. iv::modulecomm::ModuleSendMsg(mpadst,(char *)&xo,sizeof(xodrobj));
  643. }
  644. void MainWindow::on_comboBox_Station_currentIndexChanged(int index)
  645. {
  646. if(index<0 || index>= gvectorpos.size())
  647. {
  648. std::cout<<"out range."<<std::endl;
  649. return;
  650. }
  651. iv::pos_def xpos = gvectorpos[index];
  652. char strscript[256];
  653. snprintf(strscript,255,"objLocation(%11.7f,%11.7f);",xpos.mflon,xpos.mflat);
  654. mMapview->page()->runJavaScript(strscript);
  655. }
  656. void MainWindow::on_checkBox_Drive_stateChanged(int arg1)
  657. {
  658. }
  659. void MainWindow::on_checkBox_Drive_clicked()
  660. {
  661. }
  662. void MainWindow::on_checkBox_Null_clicked()
  663. {
  664. }
  665. void MainWindow::on_checkBox_Rear_clicked()
  666. {
  667. }
  668. void MainWindow::on_radioButton_Drive_clicked()
  669. {
  670. mnShift = 1;
  671. ui->radioButton_picfront->setChecked(true);
  672. on_radioButton_picfront_clicked();
  673. mpbigpicdlg->SetFront();
  674. }
  675. void MainWindow::on_radioButton_Null_clicked()
  676. {
  677. mnShift = 0;
  678. mpbigpicdlg->SetFront();
  679. }
  680. void MainWindow::on_radioButton_Rear_clicked()
  681. {
  682. mnShift = -1;
  683. ui->radioButton_picrear->setChecked(true);
  684. on_radioButton_picrear_clicked();
  685. mpbigpicdlg->SetRear();
  686. }
  687. void MainWindow::on_radioButton_picfront_clicked()
  688. {
  689. mnSelPic = 0;
  690. mppicshow->SetAttr("rawpicmsgname",gstrmem_pic[mnSelPic].data(),gstrmem_pic[mnSelPic].size());
  691. mpbigpicdlg->setCamera(mnSelPic);
  692. }
  693. void MainWindow::on_radioButton_picrear_clicked()
  694. {
  695. mnSelPic = 1;
  696. mppicshow->SetAttr("rawpicmsgname",gstrmem_pic[mnSelPic].data(),gstrmem_pic[mnSelPic].size());
  697. mpbigpicdlg->setCamera(mnSelPic);
  698. }
  699. void MainWindow::on_radioButton_picleft_clicked()
  700. {
  701. mnSelPic = 2;
  702. mppicshow->SetAttr("rawpicmsgname",gstrmem_pic[mnSelPic].data(),gstrmem_pic[mnSelPic].size());
  703. mpbigpicdlg->setCamera(mnSelPic);
  704. }
  705. void MainWindow::on_radioButton_picright_clicked()
  706. {
  707. mnSelPic = 3;
  708. mppicshow->SetAttr("rawpicmsgname",gstrmem_pic[mnSelPic].data(),gstrmem_pic[mnSelPic].size());
  709. mpbigpicdlg->setCamera(mnSelPic);
  710. }
  711. void MainWindow::on_pushButton_AllPic_clicked()
  712. {
  713. mppicdlg->show();
  714. mppicdlg->setRefresh(true);
  715. }
  716. void MainWindow::onCloseDlg()
  717. {
  718. mppicdlg->setRefresh(false);
  719. qDebug("cloase");
  720. }
  721. void MainWindow::on_checkBox_clicked()
  722. {
  723. int i;
  724. if(ui->checkBox->isChecked())
  725. {
  726. for(i=0;i<4;i++)
  727. {
  728. mpPicSave[i]->startsave();
  729. }
  730. mbSavePic = true;
  731. }
  732. else
  733. {
  734. for(i=0;i<4;i++)
  735. {
  736. mpPicSave[i]->stopsave();
  737. }
  738. mbSavePic = false;
  739. }
  740. }
  741. void MainWindow::saveavi(int index)
  742. {
  743. // if(mbSavePic == false)return;
  744. gMutexPic[index].lock();
  745. mpPicSave[index]->SetPic(grawpic[index]);
  746. gMutexPic[index].unlock();
  747. }
  748. void MainWindow::on_pushButton_big_clicked()
  749. {
  750. // pluginapp * pa = new pluginapp(this->winId(),"main","plugin_threepicshow","/home/yuchuli/qt/modularization/src/plugin/build-plugin_threepicshow-Debug");
  751. // return;
  752. mpbigpicdlg->show();
  753. mpbigpicdlg->setRefresh(true);
  754. }
  755. void MainWindow::onCloseBigDlg()
  756. {
  757. mpbigpicdlg->setRefresh(false);
  758. }
  759. void MainWindow::on_actionSet_Query_Pass_triggered()
  760. {
  761. DialogSetPassWord xdlg(DialogSetPassWord_Type::QUERY,mstrqueryMD5,this);
  762. if(xdlg.exec() == xdlg.Accepted)
  763. {
  764. mgrpcpc->setqueryMD5(ServiceRCIni.GetQueryMD5());
  765. mstrqueryMD5 = ServiceRCIni.GetQueryMD5();
  766. }
  767. }
  768. void MainWindow::on_actionSetting_triggered()
  769. {
  770. DialogSetting xdlg(this);
  771. if(xdlg.exec() == QDialog::Accepted)
  772. {
  773. mgrpcpc->setVIN(ServiceRCIni.GetVIN());
  774. mstrVehVIN = ServiceRCIni.GetVIN();
  775. }
  776. }
  777. void MainWindow::on_actionSet_Ctrl_Pass_triggered()
  778. {
  779. DialogSetPassWord xdlg(DialogSetPassWord_Type::CTRL,mstrctrlMD5,this);
  780. if(xdlg.exec() == xdlg.Accepted)
  781. {
  782. mgrpcpc->setctrlMD5(ServiceRCIni.GetCtrlMD5());
  783. mstrctrlMD5 = ServiceRCIni.GetCtrlMD5();
  784. }
  785. }
  786. void MainWindow::threadframe(int ncamppos)
  787. {
  788. iv::h264rawframedata xframe;
  789. while(mbThreadrun)
  790. {
  791. // std::this_thread::sleep_for(std::chrono::milliseconds(100));
  792. // continue;
  793. int nrtn;
  794. nrtn = mgrpcpc->Consumeh264frame(ncamppos,xframe,10);
  795. if(nrtn == 1)
  796. {
  797. std::cout<<"recv a frame."<<std::endl;
  798. iv::rawframedata xrawframe;
  799. xrawframe.mpstr_ptr = xframe.mpstr_ptr;
  800. xrawframe.ndatasize = xframe.mdatasize;
  801. mph264decode[ncamppos]->addframedata(xrawframe);
  802. }
  803. }
  804. }
  805. void MainWindow::threadpic(int ncampos)
  806. {
  807. while(mbThreadrun)
  808. {
  809. int nindex = mph264decode[ncampos]->GetUpdatedIndex(10);
  810. if(nindex<0)continue;
  811. std::cout<<" recv a yuv."<<std::endl;
  812. iv::framedecodebuf * pbuf = mph264decode[ncampos]->LockReadBuff(nindex);
  813. int cy = pbuf->frameheight;
  814. int cx = pbuf->framewidth;
  815. cv::Mat rgbImg(cy, cx,CV_8UC3);
  816. cv::cvtColor(pbuf->myuvImg, rgbImg, CV_YUV2RGB_I420);
  817. mph264decode[ncampos]->UnlockReadBuff(nindex);
  818. mMutexCam[ncampos].lock();
  819. mbCamUpdate[ncampos] = true;
  820. QImage image2 = QImage((uchar*)(rgbImg.data), rgbImg.cols, rgbImg.rows, QImage::Format_RGB888);
  821. *mpImageCam[ncampos] = image2.copy();
  822. mMutexCam[ncampos].unlock();
  823. emit CamUpdate(ncampos);
  824. // cv::cvtColor(rgbImg, rgbImg, CV_BGR2RGB);
  825. // QImage image2 = QImage((uchar*)(rgbImg.data), rgbImg.cols, rgbImg.rows, QImage::Format_RGB888);
  826. }
  827. }
  828. void MainWindow::onCamUpdate(int ncampos)
  829. {
  830. update();
  831. }