mainwindow.cpp 44 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453
  1. #include "mainwindow.h"
  2. #include "ui_mainwindow.h"
  3. #include <ostream>
  4. #include <strstream>
  5. #include <QScrollArea>
  6. #include "gpsimu.pb.h"
  7. #include "gnss_coordinate_convert.h"
  8. extern std::string gstrlidarmsg;
  9. extern std::string gstrimumsg;
  10. extern double gsplit_range ;
  11. extern double gsplit_filter;
  12. extern double gsplit_cur;
  13. extern iv::ndtorigin gndtorigin;
  14. extern bool gbManualSave;
  15. #include <Eigen/Geometry>
  16. #include <tf/tf.h>
  17. // Given two sets of 3D points, find the rotation + translation + scale
  18. // which best maps the first set to the second.
  19. // Source: http://en.wikipedia.org/wiki/Kabsch_algorithm
  20. // The input 3D points are stored as columns.
  21. Eigen::Affine3d Find3DAffineTransform(Eigen::Matrix3Xd in, Eigen::Matrix3Xd out) {
  22. // Default output
  23. Eigen::Affine3d A;
  24. A.linear() = Eigen::Matrix3d::Identity(3, 3);
  25. A.translation() = Eigen::Vector3d::Zero();
  26. if (in.cols() != out.cols())
  27. throw "Find3DAffineTransform(): input data mis-match";
  28. // First find the scale, by finding the ratio of sums of some distances,
  29. // then bring the datasets to the same scale.
  30. double dist_in = 0, dist_out = 0;
  31. for (int col = 0; col < in.cols()-1; col++) {
  32. dist_in += (in.col(col+1) - in.col(col)).norm();
  33. dist_out += (out.col(col+1) - out.col(col)).norm();
  34. }
  35. if (dist_in <= 0 || dist_out <= 0)
  36. return A;
  37. double scale = dist_out/dist_in;
  38. out /= scale;
  39. // Find the centroids then shift to the origin
  40. Eigen::Vector3d in_ctr = Eigen::Vector3d::Zero();
  41. Eigen::Vector3d out_ctr = Eigen::Vector3d::Zero();
  42. for (int col = 0; col < in.cols(); col++) {
  43. in_ctr += in.col(col);
  44. out_ctr += out.col(col);
  45. }
  46. in_ctr /= in.cols();
  47. out_ctr /= out.cols();
  48. for (int col = 0; col < in.cols(); col++) {
  49. in.col(col) -= in_ctr;
  50. out.col(col) -= out_ctr;
  51. }
  52. // SVD
  53. Eigen::MatrixXd Cov = in * out.transpose();
  54. Eigen::JacobiSVD<Eigen::MatrixXd> svd(Cov, Eigen::ComputeThinU | Eigen::ComputeThinV);
  55. // Find the rotation
  56. double d = (svd.matrixV() * svd.matrixU().transpose()).determinant();
  57. if (d > 0)
  58. d = 1.0;
  59. else
  60. d = -1.0;
  61. Eigen::Matrix3d I = Eigen::Matrix3d::Identity(3, 3);
  62. I(2, 2) = d;
  63. Eigen::Matrix3d R = svd.matrixV() * I * svd.matrixU().transpose();
  64. // The final transform
  65. A.linear() = scale * R;
  66. A.translation() = scale*(out_ctr - R*in_ctr);
  67. return A;
  68. }
  69. iv::ndtorigin PoseToGPS(iv::ndtorigin xori,iv::ndttracepoint xpose)
  70. {
  71. double x_o,y_o;
  72. GaussProjCal(xori.lon,xori.lat,&x_o,&y_o);
  73. double lon,lat;
  74. double hdg_o = (90 - xori.heading)*M_PI/180.0;
  75. double rel_x = xpose.x * cos(hdg_o) - xpose.y * sin(hdg_o);
  76. double rel_y = xpose.x * sin(hdg_o) + xpose.y * cos(hdg_o);
  77. GaussProjInvCal(x_o + rel_x,y_o + rel_y,&lon,&lat);
  78. double hdg_c = hdg_o + xpose.yaw;
  79. hdg_c = M_PI/2.0 - hdg_c;
  80. double heading = hdg_c * 180.0/M_PI;
  81. while(heading < 0)heading = heading + 360;
  82. while(heading >360)heading = heading - 360;
  83. iv::ndtorigin xgpspos;
  84. xgpspos.lon = lon;
  85. xgpspos.lat = lat;
  86. xgpspos.height = xpose.z + xori.height;
  87. xgpspos.heading = heading;
  88. xgpspos.pitch = xpose.pitch + xori.pitch;
  89. xgpspos.roll = xpose.roll + xori.roll;
  90. return xgpspos;
  91. }
  92. iv::ndttracepoint CalcPose(iv::ndtorigin xori, iv::gps::gpsimu xgpsimu)
  93. {
  94. double x_o,y_o,hdg_o;
  95. double x_c,y_c,hdg_c;
  96. GaussProjCal(xori.lon,xori.lat,&x_o,&y_o);
  97. GaussProjCal(xgpsimu.lon(),xgpsimu.lat(),&x_c,&y_c);
  98. double dis = sqrt(pow(x_c-x_o,2)+ pow(y_c-y_o,2));
  99. double rel_x0,rel_y0;
  100. rel_x0 = x_c -x_o;
  101. rel_y0 = y_c -y_o;
  102. double rel_x,rel_y;
  103. hdg_o = (90 - xori.heading)*M_PI/180.0;
  104. hdg_c = (90 - xgpsimu.heading())*M_PI/180.0;
  105. rel_x = rel_x0 * cos(-hdg_o) - rel_y0 * sin(-hdg_o);
  106. rel_y = rel_x0 * sin(-hdg_o) + rel_y0 * cos(-hdg_o);
  107. // double diffang = atan(rel_y/rel_x) * 180.0/M_PI;
  108. double rel_hdg;
  109. rel_hdg = hdg_c - hdg_o;
  110. iv::ndttracepoint posex;
  111. posex.x = rel_x;
  112. posex.y = rel_y;
  113. posex.z = xgpsimu.height() - xori.height;
  114. posex.pitch = xgpsimu.pitch() - xori.pitch;
  115. posex.roll = xgpsimu.roll() - xori.roll;
  116. posex.yaw = rel_hdg;
  117. return posex;
  118. }
  119. MainWindow::MainWindow(QWidget *parent) :
  120. QMainWindow(parent),
  121. ui(new Ui::MainWindow)
  122. {
  123. ui->setupUi(this);
  124. // iv::ndtorigin xs;
  125. // xs.heading = 359.80 -0.72;
  126. //// xs.heading = 350;
  127. // xs.height = 0;
  128. // xs.pitch = 0;
  129. // xs.roll = 0;
  130. // xs.lat = 39.12051011;
  131. // xs.lon = 117.02730387;
  132. // iv::gps::gpsimu xgpsimuobj;
  133. // xgpsimuobj.set_lat(39.12059277);
  134. // xgpsimuobj.set_lon(117.02730218);
  135. // iv::ndttracepoint xt = CalcPose(xs,xgpsimuobj);
  136. mfCalPitch = 0.0;
  137. mfCalRoll = 0.0;
  138. mfCalYaw = 0.0;
  139. //创建参数组合框
  140. CreateView();
  141. m_nP= 0;
  142. //启动定时器
  143. connect(&mTimer,SIGNAL(timeout()),this,SLOT(onTimer()));
  144. //启动mndtthread线程
  145. mndtthread.start();
  146. //设置窗口标题
  147. setWindowTitle("ADC NDT Mapping ------ Lidar Localization");
  148. mCalibMatrix<<1.0,0,0,
  149. 0,1.0,0,
  150. 0,0,1.0;
  151. Eigen::Matrix3d t = mCalibMatrix;
  152. tf::Matrix3x3 mat_l; // localizer
  153. mat_l.setValue(static_cast<double>(t(0, 0)), static_cast<double>(t(0, 1)), static_cast<double>(t(0, 2)),
  154. static_cast<double>(t(1, 0)), static_cast<double>(t(1, 1)), static_cast<double>(t(1, 2)),
  155. static_cast<double>(t(2, 0)), static_cast<double>(t(2, 1)), static_cast<double>(t(2, 2)));
  156. double roll,pitch,yaw;
  157. mat_l.getRPY(roll, pitch, yaw, 1);
  158. std::ostrstream ostr;
  159. ostr<<"Rotation:"<<std::endl;
  160. ostr<<t<<std::endl;
  161. std::cout<<"roll:"<<roll<<" pitch:"<<pitch<<" yaw:"<<yaw<<std::endl;
  162. ostr<<"roll:"<<roll<<" pitch:"<<pitch<<" yaw:"<<yaw<<std::endl;
  163. std::string strres = ostr.str();
  164. ui->plainTextEdit_Matrix->setPlainText(strres.substr(0,ostr.pcount()).data());
  165. // ui->Dial->setStyleSheet("background-color:Black");
  166. // ui->Dial->setStyleSheet("color:rgb(0,0,0)");
  167. }
  168. MainWindow::~MainWindow()
  169. {
  170. mndtthread.requestInterruption();
  171. while(!mndtthread.isFinished())
  172. {
  173. }
  174. delete ui;
  175. }
  176. void MainWindow::on_pushButton_Load_clicked()
  177. {
  178. gsplit_range = mpLE_SplitRange->text().toDouble();
  179. gsplit_filter = mpLE_FilterResolution->text().toDouble();
  180. gndtorigin.lon = mpLE_OriginLon->text().toDouble();
  181. gndtorigin.lat = mpLE_OriginLat->text().toDouble();
  182. gndtorigin.height = mpLE_OriginHeight->text().toDouble();
  183. gndtorigin.heading = mpLE_OriginHeading->text().toDouble();
  184. gndtorigin.pitch = 0;
  185. gndtorigin.roll = 0;
  186. mnPac = 0;
  187. mbCalcCalib = false;
  188. mbCalcCalib_Roll = false;
  189. int ncalindex = mpCB_Mode->currentIndex();
  190. if(ncalindex == 0)
  191. {
  192. mndtthread.setusecpu();
  193. }
  194. else
  195. {
  196. if(ncalindex == 1)
  197. {
  198. mndtthread.setuseomp();
  199. }
  200. else
  201. mndtthread.setusegpu();
  202. }
  203. //获取文件路径
  204. QString str = QFileDialog::getOpenFileName(this,tr("Open file"),"",tr("Record File(*.ivd)"));
  205. if(str.isEmpty())return;
  206. mvectorcalib.clear();
  207. mvectorgps.clear();
  208. mvectorrawgps.clear();
  209. mvectortrace.clear();
  210. mvectortracecalib.clear();
  211. mvectorglobalgps.clear();
  212. mbIVDSetOrigin = false;
  213. mndtthread.reset();
  214. // ui->pushButton_Start->setEnabled(false);
  215. mbReplay = false;
  216. mMutex.lock();
  217. if(mFile.isOpen())mFile.close();
  218. mFile.setFileName(str);
  219. //以只读打开文件
  220. if(mFile.open(QFile::ReadOnly))
  221. {
  222. if(mbSaveDiff)
  223. {
  224. QFileInfo fileinfo = QFileInfo(str);
  225. std::string strpath = getenv("HOME");
  226. strpath = strpath + "/map/";
  227. strpath = strpath + fileinfo.fileName().toLatin1().data();
  228. strpath = strpath +".txt";
  229. if(mFileDiff.isOpen())mFileDiff.close();
  230. mFileDiff.setFileName(strpath.data());
  231. if(mFileDiff.open(QIODevice::ReadWrite))
  232. {
  233. mbFileDiffOpen = true;
  234. char strout[1000];
  235. snprintf(strout,1000,"Pos\tDiff\tndt_x\tndt_y\tndt_z\tndt_yaw\trtk_x\trtk_y\trtk_z\trtk_yaw\t\n");
  236. mFileDiff.write(strout,strnlen(strout,1000));
  237. mFileDiff.flush();
  238. }
  239. else
  240. {
  241. mbFileDiffOpen = false;
  242. }
  243. }
  244. //设置当前文件打开状态
  245. mbOpen = true;
  246. //文件大小
  247. mnFileSize = mFile.size();
  248. //读取到文件的位置
  249. mnPos = 0;
  250. if(mnskip > 0)
  251. {
  252. int nReadSize = 0;
  253. int nDataSize;
  254. char * strData;
  255. char * strName;
  256. // 读取记录
  257. bool bx = ReadARecord(nReadSize,&strName,&nDataSize,&strData);
  258. mnPac++;
  259. int nr= 1;
  260. while((nr < mnskip)&&bx)
  261. {
  262. delete strName;
  263. delete strData;
  264. bx = ReadARecord(nReadSize,&strName,&nDataSize,&strData);
  265. mnPac++;
  266. nr++;
  267. }
  268. delete strName;
  269. delete strData;
  270. }
  271. }
  272. // if(mbOpen)
  273. // {
  274. // ui->pushButton_Start->setEnabled(true);
  275. // }
  276. // else
  277. // {
  278. // ui->pushButton_Start->setEnabled(false);
  279. // }
  280. mbIVDSetOrigin = false;
  281. mbIVDSetGlobalOrigin = false;
  282. mMutex.unlock();
  283. //更新地图参数
  284. UpdateMapParam();
  285. //启动定时器
  286. mTimer.start(10);
  287. }
  288. //定时器执行程序
  289. void MainWindow::onTimer()
  290. {
  291. int nP;
  292. std::string str;
  293. iv::ndttracepoint xndtpoint;
  294. qint64 xlidartime;
  295. //获取状态信息,获取全局变量g_np和gstr
  296. GetState(nP,str,xndtpoint,xlidartime);
  297. static double fOldDis = gsplit_cur;
  298. static double bFirst = true;
  299. //每执行一次point_ndtmapping操作,全局变量g_np会增加1,如果np有变化则更新文本框内的数据
  300. if(nP != m_nP)
  301. {
  302. ui->plainTextEdit->setPlainText(str.c_str());
  303. ui->lineEdit_Dis->setText(QString::number(gsplit_cur,'f',3));
  304. mvectortrace.push_back(xndtpoint);
  305. mptraceview->SetNDTTrace(mvectortrace);
  306. mvectortracecalib.push_back(xndtpoint);
  307. calibcalc(&mvectortracecalib[mvectortracecalib.size()-1]);
  308. mptraceview->SetNDTCalibTrace(mvectortracecalib);
  309. bool bHaveRTKPoint = false;
  310. iv::ndttracepoint xtrrtk;
  311. while(mvectorrawgps.size()>0)
  312. {
  313. // std::cout<<" time diff: "<<(mvectorrawgps[0].recvtime - xlidartime)<<std::endl;
  314. // std::cout<<" ldiar time: "<<xlidartime<<std::endl;
  315. if((mvectorrawgps[0].recvtime<xlidartime) &&(mvectorrawgps[0].recvtime>=(xlidartime-30)))
  316. {
  317. iv::ndttracepoint xtr;
  318. xtr = mvectorrawgps[0].xtrace;
  319. mvectorgps.push_back(xtr);
  320. bHaveRTKPoint = true;
  321. xtrrtk = xtr;
  322. break;
  323. }
  324. mvectorrawgps.erase(mvectorrawgps.begin());
  325. }
  326. if(mbFileDiffOpen)
  327. {
  328. if(((fabs(gsplit_cur - fOldDis )>=1.0) || bFirst)&&(bHaveRTKPoint))
  329. {
  330. bFirst = false;
  331. fOldDis = gsplit_cur;
  332. char strout[1000];
  333. double fdis = sqrt(pow(xndtpoint.x - xtrrtk.x,2)+pow(xndtpoint.y - xtrrtk.y,2));
  334. snprintf(strout,1000,"%6.2f\t%6.2f\t%6.2f\t%6.2f\t%6.2f\t%6.2f\t%6.2f\t%6.2f\t%6.2f\t%6.2f\t\n",
  335. gsplit_cur,fdis,xndtpoint.x,xndtpoint.y,xndtpoint.z,xndtpoint.yaw,
  336. xtrrtk.x,xtrrtk.y,xtrrtk.z,xtrrtk.yaw);
  337. mFileDiff.write(strout,strnlen(strout,1000));
  338. mFileDiff.flush();
  339. }
  340. }
  341. mptraceview->SetGPSTrace(mvectorgps);
  342. mptraceview->SetGlobalGPSTrace(mvectorglobalgps);
  343. if(mvectorgps.size()>0)
  344. {
  345. iv::ndttracepoint xtr = mvectorgps[mvectorgps.size()-1];
  346. char strtemp[1000];
  347. snprintf(strtemp,1000,"%6.3f %6.3f %6.3f %6.3f",
  348. xtr.x,xtr.y,xtr.z,xtr.yaw);
  349. ui->lineEdit_GPS->setText(strtemp);
  350. }
  351. if(mvectortrace.size()>0)
  352. {
  353. iv::ndttracepoint xtr = mvectortrace[mvectortrace.size()-1];
  354. char strtemp[1000];
  355. snprintf(strtemp,1000,"%6.3f %6.3f %6.3f %6.3f",
  356. xtr.x,xtr.y,xtr.z,xtr.yaw);
  357. ui->lineEdit_NDT->setText(strtemp);
  358. }
  359. if(mvectortracecalib.size()>0)
  360. {
  361. iv::ndttracepoint xtr = mvectortracecalib[mvectortracecalib.size()-1];
  362. char strtemp[1000];
  363. snprintf(strtemp,1000,"%6.3f %6.3f %6.3f %6.3f",
  364. xtr.x,xtr.y,xtr.z,xtr.yaw);
  365. ui->lineEdit_Calib->setText(strtemp);
  366. }
  367. if((gsplit_cur>50.0)&&(mbCalcCalib == false))
  368. {
  369. CalcCalib();
  370. mbCalcCalib = true;
  371. }
  372. if((gsplit_cur>100.0) &&(mbCalcCalib_Roll == false))
  373. {
  374. if(mvectortrace.size()>0)
  375. {
  376. if(fabs(mvectortrace[mvectortrace.size()-1].y) > 30.0)
  377. {
  378. CalcCalibRoll();
  379. mbCalcCalib_Roll = true;
  380. }
  381. }
  382. }
  383. update();
  384. }
  385. //记录执行了多少次
  386. m_nP = nP;
  387. if(mbPause)return;
  388. bool bLidarGood = true;
  389. if(mndtthread.AbleNext())//如果可执行下一次
  390. {
  391. int nReadSize = 0;
  392. int nDataSize;
  393. char * strData;
  394. char * strName;
  395. // 读取记录
  396. bool bx = ReadARecord(nReadSize,&strName,&nDataSize,&strData);
  397. mnPac++;
  398. //循环读取数据,直到读取到"lidar_pc"
  399. while((bx == true)&&(strcmp(strName,gstrlidarmsg.data()) != 0))
  400. {
  401. if((strcmp(strName,gstrimumsg.data()) == 0))
  402. {
  403. iv::gps::gpsimu xgpsimu;
  404. bool bParse;
  405. bParse = xgpsimu.ParseFromArray(strData,nDataSize);
  406. if(bParse)
  407. {
  408. // if(fabs(xgpsimu.vd())>0.5)
  409. // {
  410. // qDebug("vd is %f",xgpsimu.vd());
  411. // }
  412. //
  413. if(mbIVDSetOrigin == false)
  414. {
  415. if(xgpsimu.rtk_state() == 6)
  416. {
  417. double fheading = xgpsimu.heading();
  418. fheading = fheading - 0;
  419. if(fheading < 0)fheading = fheading + 360;
  420. double flat,flon;
  421. mpLE_OriginLat->setText(QString::number(xgpsimu.lat(),'f',7));
  422. mpLE_OriginLon->setText(QString::number(xgpsimu.lon(),'f',7));
  423. mpLE_OriginHeight->setText(QString::number(xgpsimu.height(),'f',2));
  424. mpLE_OriginHeading->setText(QString::number(fheading,'f',2));
  425. gndtorigin.lon = mpLE_OriginLon->text().toDouble();
  426. gndtorigin.lat = mpLE_OriginLat->text().toDouble();
  427. gndtorigin.height = mpLE_OriginHeight->text().toDouble();
  428. gndtorigin.heading = fheading;
  429. iv::ndttracepoint trarm;
  430. trarm.x = arm_x;
  431. trarm.y = arm_y;
  432. trarm.z = 0;
  433. trarm.yaw = 0;
  434. trarm.pitch = 0;
  435. trarm.roll = 0;
  436. gndtorigin = PoseToGPS(gndtorigin,trarm);
  437. mpLE_OriginLat->setText(QString::number(gndtorigin.lat,'f',7));
  438. mpLE_OriginLon->setText(QString::number(gndtorigin.lon,'f',7));
  439. mbIVDSetOrigin = true;
  440. if(mbIVDSetGlobalOrigin == false)
  441. {
  442. mbIVDSetGlobalOrigin = true;
  443. mglobalndtorigin = gndtorigin;
  444. }
  445. }
  446. }
  447. if(mbIVDSetOrigin)
  448. {
  449. iv::ndttracepoint xtr = CalcPose(gndtorigin,xgpsimu);
  450. double x,y;
  451. x = arm_x * cos(xtr.yaw) - arm_y * sin(xtr.yaw);
  452. y = arm_x * sin(xtr.yaw) + arm_y * cos(xtr.yaw);
  453. xtr.x = xtr.x + x - arm_x;
  454. xtr.y = xtr.y + y - arm_y;
  455. iv::gpstrace xg;
  456. if(xgpsimu.has_msgtime())
  457. xg.recvtime = xgpsimu.msgtime();
  458. else
  459. xg.recvtime = xgpsimu.time();
  460. // xg.recvtime = xgpsimu.msgtime();
  461. xg.xtrace = xtr;
  462. mvectorrawgps.push_back(xg);
  463. }
  464. if(mbIVDSetGlobalOrigin)
  465. {
  466. iv::ndttracepoint xtr = CalcPose(mglobalndtorigin,xgpsimu);
  467. double x,y;
  468. x = arm_x * cos(xtr.yaw) - arm_y * sin(xtr.yaw);
  469. y = arm_x * sin(xtr.yaw) + arm_y * cos(xtr.yaw);
  470. xtr.x = xtr.x + x - arm_x;
  471. xtr.y = xtr.y + y - arm_y;
  472. iv::gpstrace xg;
  473. mvectorglobalgps.push_back(xtr);
  474. }
  475. if(xgpsimu.has_acce_x())
  476. {
  477. // setuseimu(true);
  478. // imu_update(xgpsimu.time(),
  479. // xgpsimu.roll(),xgpsimu.pitch(),
  480. // xgpsimu.heading(),xgpsimu.acce_x(),
  481. // xgpsimu.acce_y(),xgpsimu.acce_z());
  482. }
  483. // if(xgpsimu.has_acce_z())
  484. // {
  485. // if(fabs(xgpsimu.acce_z() + 1.0)>0.5)
  486. // {
  487. // bLidarGood = true;
  488. // qDebug("acc z is %f vd is %f",xgpsimu.acce_z(),xgpsimu.vd());
  489. // }
  490. // }
  491. }
  492. }
  493. // if(strcmp(strName,"ins550d_gpsimu") == 0)
  494. // {
  495. // iv::gps::gpsimu xgpsimu;
  496. // bool bParse;
  497. // bParse = xgpsimu.ParseFromArray(strData,nDataSize);
  498. // if(bParse)
  499. // {
  500. //// if(fabs(xgpsimu.vd())>0.5)
  501. //// {
  502. //// qDebug("vd is %f",xgpsimu.vd());
  503. //// }
  504. // //
  505. // if(xgpsimu.has_acce_z())
  506. // {
  507. // if(fabs(xgpsimu.acce_z() + 1.0)>0.5)
  508. // {
  509. // bLidarGood = true;
  510. // qDebug("acc z is %f vd is %f",xgpsimu.acce_z(),xgpsimu.vd());
  511. // }
  512. // }
  513. // }
  514. // }
  515. delete strData;
  516. delete strName;
  517. // 读取一条记录并将读取的结果赋值给变量:strName,nDataSize,strData
  518. bx = ReadARecord(nReadSize,&strName,&nDataSize,&strData);
  519. mnPac++;
  520. }
  521. ui->lineEdit_Pac->setText(QString::number(mnPac));
  522. //更新进度条
  523. ui->horizontalSlider->setValue(mFile.pos()*100/mnFileSize);
  524. // 文件读取完毕,进度条设为100,停止计时器
  525. if(bx == false)
  526. {
  527. ui->horizontalSlider->setValue(100);
  528. mTimer.stop();
  529. }
  530. else//读取到lidar数据
  531. {
  532. qDebug("find a lidar_pc");
  533. //预处理数据
  534. if(bLidarGood == true)procapcd(strData,nDataSize);
  535. else
  536. {
  537. bLidarGood = true;
  538. qDebug("skip 1 lidarpc");
  539. }
  540. delete strData;
  541. delete strName;
  542. }
  543. }
  544. }
  545. void MainWindow::paintEvent(QPaintEvent *)
  546. {
  547. if(!mptraceview->IsHaveNew())
  548. {
  549. return;
  550. }
  551. QImage image = mptraceview->GetImage();
  552. mscene->clear();
  553. mscene->addPixmap(QPixmap::fromImage(image));
  554. mmyview->setScene(mscene);
  555. mmyview->show();
  556. }
  557. //获取rh时间
  558. inline QDateTime MainWindow::GetDateTimeFromRH(iv::RecordHead rh)
  559. {
  560. QDateTime dt;
  561. QDate datex;
  562. QTime timex;
  563. datex.setDate(rh.mYear,rh.mMon,rh.mDay);
  564. timex.setHMS(rh.mHour,rh.mMin,rh.mSec,rh.mMSec);
  565. dt.setDate(datex);
  566. dt.setTime(timex);
  567. return dt;
  568. }
  569. //处理数据
  570. void MainWindow::procapcd(char *strdata, int nSize)
  571. {
  572. if(nSize <=16)return;
  573. //头文件大小
  574. unsigned int * pHeadSize = (unsigned int *)strdata;
  575. if(*pHeadSize > nSize)
  576. {
  577. // std::cout<<"ListenPointCloud data is small headsize ="<<*pHeadSize<<" data size is"<<nSize<<std::endl;
  578. }
  579. //构建点云对象
  580. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
  581. new pcl::PointCloud<pcl::PointXYZI>());
  582. // pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud(
  583. // new pcl::PointCloud<pcl::PointXYZ>());
  584. // 获取名字
  585. int nNameSize;
  586. nNameSize = *pHeadSize - 4-4-8;
  587. char * strName = new char[nNameSize+1];strName[nNameSize] = 0;
  588. memcpy(strName,(char *)((char *)strdata +4),nNameSize);
  589. point_cloud->header.frame_id = strName;
  590. // 序列号
  591. memcpy(&point_cloud->header.seq,(char *)strdata+4+nNameSize,4);
  592. // 时间戳
  593. memcpy(&point_cloud->header.stamp,(char *)strdata+4+nNameSize+4,8);
  594. // 点数量
  595. int nPCount = (nSize - *pHeadSize)/sizeof(pcl::PointXYZI);
  596. int i;
  597. double yaw,pitch,roll;
  598. yaw = (mfCalYaw)*M_PI/180.0;
  599. pitch = (mfCalPitch)*M_PI/180.0;
  600. roll = (mfCalRoll)*M_PI/180.0;
  601. double x1,y1,z1;
  602. // 把点的数据赋值给点云对象中的变量
  603. pcl::PointXYZI * p;
  604. p = (pcl::PointXYZI *)((char *)strdata + *pHeadSize);
  605. for(i=0;i<nPCount;i++)
  606. {
  607. pcl::PointXYZI xp;
  608. xp.x = p->y;
  609. xp.y = p->x * (-1.0);
  610. xp.z = p->z;
  611. x1 = p->y;
  612. y1 = p->x * (-1.0);
  613. z1 = p->z;
  614. xp.x = x1*cos(yaw) -y1*sin(yaw);
  615. xp.y = x1*sin(yaw) + y1*cos(yaw);
  616. x1 = xp.x;
  617. z1 = xp.z;
  618. xp.z = z1*cos(pitch) -x1*sin(pitch);
  619. xp.x = z1*sin(pitch) + x1*cos(pitch);
  620. y1 = xp.y;
  621. z1 = xp.z;
  622. xp.y = y1*cos(roll) -z1*sin(roll);
  623. xp.z = y1*sin(roll) + z1*cos(roll);
  624. xp.intensity = p->intensity;
  625. point_cloud->push_back(xp);
  626. p++;
  627. }
  628. // 把点云数据传给处理点云数据的线程对象
  629. mndtthread.procapcd(point_cloud);
  630. }
  631. inline bool MainWindow::ReadARecord(int & nRecSize,char ** pstrName, int * pnDataSize, char ** pstrData)
  632. {
  633. char strmark[10];
  634. //消息总大小、消息头大小、消息名字大小、消息数据大小
  635. int nTotalSize,nHeadSize,nNameSize,nDataSize;
  636. int nRead = mFile.read(strmark,1);
  637. if(nRead == 0)return false;
  638. //获取消息总大小、消息头大小、消息名字大小、消息数据大小
  639. nRead = mFile.read((char *)&nTotalSize,sizeof(int));
  640. if(nRead < sizeof(int))return false;
  641. nRead = mFile.read((char *)&nHeadSize,sizeof(int));
  642. if(nRead < sizeof(int))return false;
  643. nRead = mFile.read((char *)&nNameSize,sizeof(int));
  644. if(nRead<sizeof(int))return false;
  645. nRead = mFile.read((char *)&nDataSize,sizeof(int));
  646. if(nRead<sizeof(int))return false;
  647. //校验数据关系
  648. if(nTotalSize !=(nHeadSize + nNameSize + nDataSize + 4*sizeof(int) ))
  649. {
  650. return false;
  651. }
  652. iv::RecordHead rh;
  653. char * strName = new char[1000];
  654. char * strData = new char[nDataSize];
  655. //获取时间
  656. nRead = mFile.read((char *)&rh,sizeof(iv::RecordHead));
  657. if(nRead < sizeof(iv::RecordHead))
  658. {
  659. delete strData;
  660. delete strName;
  661. return false;
  662. }
  663. mdtcurpos = GetDateTimeFromRH(rh);
  664. //获取名字
  665. nRead = mFile.read(strName,nNameSize);
  666. if(nRead < nNameSize)
  667. {
  668. delete strData;
  669. delete strName;
  670. return false;
  671. }
  672. // 使字符数组变为字符串
  673. strName[nNameSize] = 0;
  674. // qDebug(strName);
  675. // qDebug("file pos is %d ms is %d",mFile.pos(),rh.mMSec);
  676. //获取雷达数据
  677. nRead = mFile.read(strData,nDataSize);
  678. if(nRead < nDataSize)
  679. {
  680. delete strData;
  681. delete strName;
  682. return false;
  683. }
  684. //Share Data
  685. //指针赋值
  686. *pnDataSize = nDataSize;
  687. *pstrName = strName;
  688. *pstrData = strData;
  689. // delete strData;
  690. nRecSize = nTotalSize + 1;
  691. return true;
  692. }
  693. //点击save按钮
  694. void MainWindow::on_pushButton_Save_clicked()
  695. {
  696. // 获取存储的路径
  697. QString str = QFileDialog::getSaveFileName(this,tr("Open file"),"",tr("PCD File(*.pcd)"));
  698. if(str.isEmpty())return;
  699. if(!str.contains(".pcd"))str = str + ".pcd";
  700. //点云过滤网格尺寸
  701. double filter_res = mpLE_FilterResolution->text().toDouble();
  702. //存储地图
  703. savemap(str.toLatin1().data(),filter_res);
  704. QString strtrace = str;
  705. strtrace = str.left(strtrace.size()-4);
  706. strtrace = strtrace + ".txt";
  707. savetrace(strtrace.toLatin1().data());
  708. QString strorigin = str;
  709. strorigin = str.left(strorigin.size()-4);
  710. strorigin = strorigin + ".ori";
  711. saveorigin(strorigin.toLatin1().data());
  712. }
  713. //创建左侧标题为"Param"的组合框
  714. void MainWindow::CreateView()
  715. {
  716. // QDesktopWidget* desktopWidget = QApplication::desktop();
  717. // QRect screenRect = desktopWidget->screenGeometry();
  718. // g_nActScreenW = screenRect.width();
  719. // g_nActScreenH = screenRect.height();
  720. // qDebug("width = %d, height = %d",g_nActScreenW,g_nActScreenH);
  721. QGroupBox * gp1 = new QGroupBox(ui->centralWidget);
  722. gp1->setTitle(QStringLiteral("Param"));
  723. gp1->setGeometry(QRect(10,60,430,650));
  724. QGridLayout * gll1 = new QGridLayout(ui->centralWidget);
  725. gp1->setLayout(gll1);
  726. CreateParamView(gll1);
  727. QGroupBox * gp2 = new QGroupBox(ui->centralWidget);
  728. gp2->setTitle(QStringLiteral("Calib"));
  729. gp2->setGeometry(QRect(10,730,430,150));
  730. QGridLayout * gll2 = new QGridLayout(ui->centralWidget);
  731. gp2->setLayout(gll2);
  732. CreateCalibView(gll2);
  733. mptraceview = new ivtraceview();
  734. mptraceview->start();
  735. QLabel * pLabel = new QLabel(ui->centralWidget);
  736. pLabel->setGeometry(QRect(1400,60,80,30));
  737. pLabel->setText("Scale View");
  738. mpSlider = new QSlider(ui->centralWidget);
  739. mpSlider->setGeometry(QRect(1500,60,300,30));
  740. mpSlider->setOrientation(Qt::Horizontal);
  741. mpSlider->setValue(1);
  742. mpSlider->setRange(1,10);
  743. connect(mpSlider,SIGNAL(valueChanged(int)),this,SLOT(onChangeViewFac(int)));
  744. pLabel = new QLabel(ui->centralWidget);
  745. pLabel->setGeometry(QRect(1400,150,90,30));
  746. pLabel->setText("Cor Yaw:");
  747. QLineEdit * pLE = new QLineEdit(ui->centralWidget);
  748. pLE->setGeometry(QRect(1500,150,90,30));
  749. pLE->setText(QString::number(mfCalYaw));
  750. mpLE_CalYaw = pLE;
  751. pLabel = new QLabel(ui->centralWidget);
  752. pLabel->setGeometry(QRect(1600,150,90,30));
  753. pLabel->setText("Cor Pitch:");
  754. pLE = new QLineEdit(ui->centralWidget);
  755. pLE->setGeometry(QRect(1700,150,90,30));
  756. pLE->setText(QString::number(mfCalPitch));
  757. mpLE_CalPitch = pLE;
  758. pLabel = new QLabel(ui->centralWidget);
  759. pLabel->setGeometry(QRect(1400,200,90,30));
  760. pLabel->setText("Cor Roll:");
  761. pLE = new QLineEdit(ui->centralWidget);
  762. pLE->setGeometry(QRect(1500,200,90,30));
  763. pLE->setText(QString::number(mfCalRoll));
  764. mpLE_CalRoll = pLE;
  765. QPushButton * pPB = new QPushButton(ui->centralWidget);
  766. pPB->setGeometry(QRect(1700,200,90,30));
  767. pPB->setText("Set Cor");
  768. connect(pPB,SIGNAL(clicked(bool)),this,SLOT(onSetCor()));
  769. pLabel = new QLabel(ui->centralWidget);
  770. pLabel->setGeometry(QRect(1400,300,90,30));
  771. pLabel->setText("Arm x:");
  772. pLE = new QLineEdit(ui->centralWidget);
  773. pLE->setGeometry(QRect(1500,300,90,30));
  774. pLE->setText(QString::number(mfCalYaw));
  775. mpLE_Armx = pLE;
  776. pLabel = new QLabel(ui->centralWidget);
  777. pLabel->setGeometry(QRect(1600,300,90,30));
  778. pLabel->setText("Arm y:");
  779. pLE = new QLineEdit(ui->centralWidget);
  780. pLE->setGeometry(QRect(1700,300,90,30));
  781. pLE->setText(QString::number(mfCalPitch));
  782. mpLE_Army = pLE;
  783. pLabel = new QLabel(ui->centralWidget);
  784. pLabel->setGeometry(QRect(1400,350,260,30));
  785. pLabel->setText("Arm is LIDAR TO GPS:");
  786. pPB = new QPushButton(ui->centralWidget);
  787. pPB->setGeometry(QRect(1700,350,90,30));
  788. pPB->setText("Set Arm");
  789. connect(pPB,SIGNAL(clicked(bool)),this,SLOT(onSetArm()));
  790. mmyview = new MyView(ui->centralWidget);
  791. mmyview->setObjectName(QStringLiteral("graphicsView"));
  792. mmyview->setGeometry(QRect(460, 430, 600, 600));
  793. mmyview->setCacheMode(mmyview->CacheBackground);
  794. mscene = new QGraphicsScene;
  795. ui->pushButton_Reset->setEnabled(false);
  796. }
  797. void MainWindow::resizeEvent(QResizeEvent *event)
  798. {
  799. qDebug("resize");
  800. QSize sizemain = ui->centralWidget->size();
  801. qDebug("size x = %d y=%d",sizemain.width(),sizemain.height());
  802. if((sizemain.width()>500) &&(sizemain.height()>450))
  803. {
  804. mmyview->setGeometry(460,430,sizemain.width()-500,sizemain.height()-450);
  805. // ui->plainTextEdit->setGeometry(460,60,sizemain.width()-500,350);
  806. }
  807. }
  808. void MainWindow::CreateCalibView(QGridLayout * gl)
  809. {
  810. gl->setSpacing(10);
  811. int i = 0;
  812. QLabel * pl = new QLabel(this);
  813. pl->setText("Yaw");
  814. pl->setFixedWidth(200);
  815. QLineEdit * ple = new QLineEdit(this);
  816. ple->setFixedWidth(100);
  817. ple->setText(" ");
  818. gl->addWidget(pl,i,0);
  819. gl->addWidget(ple,i,1);
  820. mpLE_CalcCalib_Yaw = ple;
  821. i++;
  822. pl = new QLabel(this);
  823. pl->setText("Pitch");
  824. pl->setFixedWidth(200);
  825. ple = new QLineEdit(this);
  826. ple->setFixedWidth(100);
  827. ple->setText(" ");
  828. gl->addWidget(pl,i,0);
  829. gl->addWidget(ple,i,1);
  830. mpLE_CalcCalib_Pitch = ple;
  831. i++;
  832. pl = new QLabel(this);
  833. pl->setText("Roll");
  834. pl->setFixedWidth(200);
  835. ple = new QLineEdit(this);
  836. ple->setFixedWidth(100);
  837. ple->setText(" ");
  838. gl->addWidget(pl,i,0);
  839. gl->addWidget(ple,i,1);
  840. mpLE_CalcCalib_Roll = ple;
  841. i++;
  842. }
  843. //创建组合框内的Label和LineEdit,并设置初始化值
  844. void MainWindow::CreateParamView(QGridLayout *gl)
  845. {
  846. gl->setSpacing(10);
  847. int i = 0;
  848. QLabel * pl = new QLabel(this);
  849. pl->setText("Resolution");
  850. pl->setFixedWidth(200);
  851. QLineEdit * ple = new QLineEdit(this);
  852. ple->setFixedWidth(100);
  853. ple->setText("1");
  854. gl->addWidget(pl,i,0);
  855. gl->addWidget(ple,i,1);
  856. i++;
  857. mpLE_Resolution = ple;
  858. pl = new QLabel(this);
  859. pl->setText("Step Size");
  860. pl->setFixedWidth(200);
  861. ple = new QLineEdit(this);
  862. ple->setFixedWidth(100);
  863. ple->setText("0.1");
  864. gl->addWidget(pl,i,0);
  865. gl->addWidget(ple,i,1);
  866. i++;
  867. mpLE_StepSize = ple;
  868. pl = new QLabel(this);
  869. pl->setText("Transformation Epsilon");
  870. pl->setFixedWidth(200);
  871. ple = new QLineEdit(this);
  872. ple->setFixedWidth(100);
  873. ple->setText("0.01");
  874. gl->addWidget(pl,i,0);
  875. gl->addWidget(ple,i,1);
  876. i++;
  877. mpLE_TransFormationEpsilon = ple;
  878. pl = new QLabel(this);
  879. pl->setText("Maximum Iterations");
  880. pl->setFixedWidth(200);
  881. ple = new QLineEdit(this);
  882. ple->setFixedWidth(100);
  883. ple->setText("30");
  884. gl->addWidget(pl,i,0);
  885. gl->addWidget(ple,i,1);
  886. i++;
  887. mpLE_MaximumIterations = ple;
  888. pl = new QLabel(this);
  889. pl->setText("Leaf Size");
  890. pl->setFixedWidth(200);
  891. ple = new QLineEdit(this);
  892. ple->setFixedWidth(100);
  893. ple->setText("2");
  894. gl->addWidget(pl,i,0);
  895. gl->addWidget(ple,i,1);
  896. i++;
  897. mpLE_LeafSize = ple;
  898. pl = new QLabel(this);
  899. pl->setText("Minimum Scan Range");
  900. pl->setFixedWidth(200);
  901. ple = new QLineEdit(this);
  902. ple->setFixedWidth(100);
  903. ple->setText("5");
  904. gl->addWidget(pl,i,0);
  905. gl->addWidget(ple,i,1);
  906. i++;
  907. mpLE_MinimunScanRange = ple;
  908. pl = new QLabel(this);
  909. pl->setText("Maximum Scan Range");
  910. pl->setFixedWidth(200);
  911. ple = new QLineEdit(this);
  912. ple->setFixedWidth(100);
  913. ple->setText("200");
  914. gl->addWidget(pl,i,0);
  915. gl->addWidget(ple,i,1);
  916. i++;
  917. mpLE_MaximumScanRange = ple;
  918. pl = new QLabel(this);
  919. pl->setText("Minimum Add Scan Shift");
  920. pl->setFixedWidth(200);
  921. ple = new QLineEdit(this);
  922. ple->setFixedWidth(100);
  923. ple->setText("1");
  924. gl->addWidget(pl,i,0);
  925. gl->addWidget(ple,i,1);
  926. i++;
  927. mpLE_MinimumAddScanShfit = ple;
  928. pl = new QLabel(this);
  929. pl->setText("Mode");
  930. pl->setFixedWidth(200);
  931. QComboBox * pcb = new QComboBox(this);
  932. pcb->addItem("CPU");
  933. pcb->addItem("OpenMP");
  934. #ifdef CUDA_FOUND
  935. pcb->addItem("GPU");
  936. #endif
  937. pcb->setFixedWidth(100);
  938. gl->addWidget(pl,i,0);
  939. gl->addWidget(pcb,i,1);
  940. i++;
  941. mpCB_Mode = pcb;
  942. pl = new QLabel(this);
  943. pl->setText("Filter Resolution");
  944. pl->setFixedWidth(200);
  945. ple = new QLineEdit(this);
  946. ple->setFixedWidth(100);
  947. ple->setText("0.2");
  948. gl->addWidget(pl,i,0);
  949. gl->addWidget(ple,i,1);
  950. i++;
  951. mpLE_FilterResolution = ple;
  952. pl = new QLabel(this);
  953. pl->setText("Split Range");
  954. pl->setFixedWidth(200);
  955. ple = new QLineEdit(this);
  956. ple->setFixedWidth(100);
  957. ple->setText("2000");
  958. gl->addWidget(pl,i,0);
  959. gl->addWidget(ple,i,1);
  960. i++;
  961. mpLE_SplitRange = ple;
  962. pl = new QLabel(this);
  963. pl->setText("Origin Longitude");
  964. pl->setFixedWidth(200);
  965. ple = new QLineEdit(this);
  966. ple->setFixedWidth(100);
  967. ple->setText("117");
  968. gl->addWidget(pl,i,0);
  969. gl->addWidget(ple,i,1);
  970. i++;
  971. mpLE_OriginLon = ple;
  972. pl = new QLabel(this);
  973. pl->setText("Origin Latitude");
  974. pl->setFixedWidth(200);
  975. ple = new QLineEdit(this);
  976. ple->setFixedWidth(100);
  977. ple->setText("39");
  978. gl->addWidget(pl,i,0);
  979. gl->addWidget(ple,i,1);
  980. i++;
  981. mpLE_OriginLat =ple;
  982. pl = new QLabel(this);
  983. pl->setText("Origin Height");
  984. pl->setFixedWidth(200);
  985. ple = new QLineEdit(this);
  986. ple->setFixedWidth(100);
  987. ple->setText("0");
  988. gl->addWidget(pl,i,0);
  989. gl->addWidget(ple,i,1);
  990. i++;
  991. mpLE_OriginHeight = ple;
  992. pl = new QLabel(this);
  993. pl->setText("Origin Heading");
  994. pl->setFixedWidth(200);
  995. ple = new QLineEdit(this);
  996. ple->setFixedWidth(100);
  997. ple->setText("90");
  998. gl->addWidget(pl,i,0);
  999. gl->addWidget(ple,i,1);
  1000. i++;
  1001. mpLE_OriginHeading = ple;
  1002. QPushButton * pPB = new QPushButton(this);
  1003. pPB->setText("Change Param");
  1004. pPB->setFixedWidth(200);
  1005. gl->addWidget(pPB,i,0);
  1006. mpPB_ChangeParam = pPB;
  1007. pPB = new QPushButton(this);
  1008. pPB->setText("Split");
  1009. pPB->setFixedWidth(100);
  1010. gl->addWidget(pPB,i,1);
  1011. mpPB_Split = pPB;
  1012. i++;
  1013. connect(mpPB_ChangeParam,SIGNAL(clicked(bool)),this,SLOT(onChangeParam()));
  1014. connect(mpPB_Split,SIGNAL(clicked(bool)),this,SLOT(onSplit()));
  1015. QSpacerItem * xpsi2 = new QSpacerItem(200,1000,QSizePolicy::Maximum);
  1016. gl->addItem(xpsi2,i,0);
  1017. }
  1018. void MainWindow::UpdateMapParam()
  1019. {
  1020. double resolution,stepsize,epsilon,maxiter,leafsize,minscan,maxscan,minscanshift;
  1021. bool bUseGPU = false;
  1022. resolution = mpLE_Resolution->text().toDouble();
  1023. stepsize = mpLE_StepSize->text().toDouble();
  1024. epsilon = mpLE_TransFormationEpsilon->text().toDouble();
  1025. maxiter = mpLE_MaximumIterations->text().toDouble();
  1026. leafsize = mpLE_LeafSize->text().toDouble();
  1027. minscan = mpLE_MinimunScanRange->text().toDouble();
  1028. maxscan = mpLE_MaximumScanRange->text().toDouble();
  1029. minscanshift = mpLE_MinimumAddScanShfit->text().toDouble();
  1030. SetParam(resolution,stepsize,epsilon,maxiter,leafsize,minscan,maxscan,minscanshift,bUseGPU);
  1031. }
  1032. void MainWindow::onChangeParam()
  1033. {
  1034. UpdateMapParam();
  1035. }
  1036. void MainWindow::onSplit()
  1037. {
  1038. gbManualSave = true;
  1039. }
  1040. void MainWindow::on_pushButton_UsePoint_clicked()
  1041. {
  1042. if((mvectorgps.size() <1)||(mvectortrace.size()<1))
  1043. {
  1044. return;
  1045. }
  1046. double x1,y1,z1,x2,y2,z2;
  1047. iv::ndttracepoint xtrndt,xtrgps;
  1048. xtrndt = mvectortrace[mvectortrace.size()-1];
  1049. xtrgps = mvectorgps[mvectorgps.size()-1];
  1050. iv::calib xcalib;
  1051. xcalib.mndt = xtrndt;
  1052. xcalib.mgps = xtrgps;
  1053. mvectorcalib.push_back(xcalib);
  1054. int i;
  1055. char strout[10000];
  1056. snprintf(strout,10000,"");
  1057. for(i=0;i<mvectorcalib.size();i++)
  1058. {
  1059. char strtem[1000];
  1060. snprintf(strtem,1000,"%6.2f %6.2f %6.2f %6.2f %6.2f %6.2f\n",
  1061. mvectorcalib[i].mndt.x,mvectorcalib[i].mndt.y,mvectorcalib[i].mndt.z,
  1062. mvectorcalib[i].mgps.x,mvectorcalib[i].mgps.y,mvectorcalib[i].mgps.z);
  1063. strncat(strout,strtem,10000);
  1064. }
  1065. ui->plainTextEdit_NDTGPS->setPlainText(strout);
  1066. }
  1067. void MainWindow::on_pushButton_Calc_clicked()
  1068. {
  1069. int nsize = mvectorcalib.size();
  1070. Eigen::Matrix3Xd in(3, nsize), out(3, nsize);
  1071. int a = in.cols();
  1072. a = a+1;
  1073. for (int row = 0; row < in.rows(); row++) {
  1074. // for (int col = 0; col < in.cols(); col++) {
  1075. in(row, 0) = mvectorcalib[row].mndt.x;
  1076. in(row, 1) = mvectorcalib[row].mndt.y;
  1077. in(row, 2) = mvectorcalib[row].mndt.z;
  1078. out(row,0) = mvectorcalib[row].mgps.x;
  1079. out(row,1) = mvectorcalib[row].mgps.y;
  1080. out(row,2) = mvectorcalib[row].mgps.z;
  1081. // }
  1082. }
  1083. std::ostrstream ostr;
  1084. Eigen::Affine3d A = Find3DAffineTransform(in, out);
  1085. std::cout<<A.linear()<<std::endl;
  1086. std::cout<<A.translation()<<std::endl;
  1087. ostr<<"Rotation:"<<std::endl;
  1088. ostr<<A.linear()<<std::endl;
  1089. ostr<<"TransLation:"<<std::endl;
  1090. ostr<<A.translation()<<std::endl;
  1091. Eigen::Matrix3d t = A.linear();
  1092. tf::Matrix3x3 mat_l; // localizer
  1093. mat_l.setValue(static_cast<double>(t(0, 0)), static_cast<double>(t(0, 1)), static_cast<double>(t(0, 2)),
  1094. static_cast<double>(t(1, 0)), static_cast<double>(t(1, 1)), static_cast<double>(t(1, 2)),
  1095. static_cast<double>(t(2, 0)), static_cast<double>(t(2, 1)), static_cast<double>(t(2, 2)));
  1096. double roll,pitch,yaw;
  1097. mat_l.getRPY(roll, pitch, yaw, 1);
  1098. std::cout<<"roll:"<<roll<<" pitch:"<<pitch<<" yaw:"<<yaw<<std::endl;
  1099. ostr<<"roll:"<<roll<<" pitch:"<<pitch<<" yaw:"<<yaw<<std::endl;
  1100. std::string strres = ostr.str();
  1101. ui->plainTextEdit_Matrix->setPlainText(strres.substr(0,ostr.pcount()).data());
  1102. mCalibMatrix = t;
  1103. int i;
  1104. for(i=0;i<mvectortracecalib.size();i++)
  1105. {
  1106. iv::ndttracepoint xtr = calibcalc(&mvectortracecalib[i]);
  1107. mvectortracecalib[i].x = xtr.x;
  1108. mvectortracecalib[i].y = xtr.y;
  1109. mvectortracecalib[i].z = xtr.z;
  1110. }
  1111. mptraceview->SetNDTCalibTrace(mvectortracecalib);
  1112. }
  1113. void MainWindow::on_pushButton_Clear_clicked()
  1114. {
  1115. mvectorcalib.erase(mvectorcalib.begin(),mvectorcalib.end());
  1116. ui->plainTextEdit_NDTGPS->setPlainText("");
  1117. }
  1118. iv::ndttracepoint MainWindow::calibcalc(iv::ndttracepoint *p)
  1119. {
  1120. iv::ndttracepoint x;
  1121. Eigen::Vector3d xin;
  1122. xin(0) = p->x;
  1123. xin(1) = p->y;
  1124. xin(2) = p->z;
  1125. Eigen::Vector3d xout;
  1126. xout = mCalibMatrix * xin;
  1127. p->x = xout(0);
  1128. p->y = xout(1);
  1129. p->z = xout(2);
  1130. x = *p;
  1131. x.x = p->x;
  1132. x.y = p->y;
  1133. x.z = p->z;
  1134. return x;
  1135. }
  1136. void MainWindow::on_pushButton_Pause_clicked()
  1137. {
  1138. if(ui->pushButton_Pause->text() == "Pause")
  1139. {
  1140. ui->pushButton_Pause->setText("Conitinue");
  1141. ui->pushButton_Reset->setEnabled(true);
  1142. mbPause = true;
  1143. }
  1144. else
  1145. {
  1146. ui->pushButton_Pause->setText("Pause");
  1147. ui->pushButton_Reset->setEnabled(false);
  1148. mbPause = false;
  1149. }
  1150. }
  1151. void MainWindow::on_pushButton_SetSkip_clicked()
  1152. {
  1153. mnskip = ui->lineEdit_skip->text().toInt();
  1154. }
  1155. void MainWindow::on_pushButton_Reset_clicked()
  1156. {
  1157. mvectorcalib.clear();
  1158. mvectorgps.clear();
  1159. mvectorrawgps.clear();
  1160. mvectortrace.clear();
  1161. mvectortracecalib.clear();
  1162. mbIVDSetOrigin = false;
  1163. mndtthread.reset();
  1164. }
  1165. void MainWindow::onChangeViewFac(int nFac)
  1166. {
  1167. mptraceview->SetFac(nFac);
  1168. }
  1169. void MainWindow::onSetCor()
  1170. {
  1171. mfCalYaw = mpLE_CalYaw->text().toDouble();
  1172. mfCalPitch = mpLE_CalPitch->text().toDouble();
  1173. mfCalRoll = mpLE_CalRoll->text().toDouble();
  1174. }
  1175. void MainWindow::onSetArm()
  1176. {
  1177. arm_x = mpLE_Armx->text().toDouble();
  1178. arm_y = mpLE_Army->text().toDouble();
  1179. }
  1180. void MainWindow::CalcCalib()
  1181. {
  1182. if((mvectorgps.size()>0) &&(mvectortrace.size()>0))
  1183. {
  1184. double gps_x = mvectorgps[mvectorgps.size()-1].x;
  1185. double gps_y = mvectorgps[mvectorgps.size()-1].y;
  1186. double gps_z = mvectorgps[mvectorgps.size()-1].z;
  1187. double ndt_x = mvectortrace[mvectortrace.size()-1].x;
  1188. double ndt_y = mvectortrace[mvectortrace.size()-1].y;
  1189. double ndt_z = mvectortrace[mvectortrace.size()-1].z;
  1190. double gps_dis = sqrt(pow(gps_x,2)+pow(gps_y,2));
  1191. double ndt_dis = sqrt(pow(ndt_x,2)+pow(ndt_y,2));
  1192. if((gps_dis>0)&&(ndt_dis>0))
  1193. {
  1194. double gps_angle = asin(gps_y/gps_dis);
  1195. if(gps_x < 0)
  1196. {
  1197. gps_angle = M_PI - gps_angle;
  1198. }
  1199. double ndt_angle = asin(ndt_y/ndt_dis);
  1200. if(ndt_x < 0)
  1201. {
  1202. ndt_angle = M_PI - ndt_angle;
  1203. }
  1204. double calib_yaw = gps_angle - ndt_angle;
  1205. while(calib_yaw>2.0*M_PI) calib_yaw = calib_yaw - 2.0*M_PI;
  1206. while(calib_yaw < 0)calib_yaw = calib_yaw + 2.0*M_PI;
  1207. mpLE_CalcCalib_Yaw->setText(QString::number(calib_yaw*180.0/M_PI));
  1208. double calib_pitch = (-1.0) * asin((gps_z - ndt_z)/gps_dis);
  1209. while(calib_pitch>2.0*M_PI) calib_pitch = calib_pitch - 2.0*M_PI;
  1210. while(calib_pitch < 0)calib_pitch = calib_pitch + 2.0*M_PI;
  1211. mpLE_CalcCalib_Pitch->setText(QString::number(calib_pitch * 180.0/M_PI));
  1212. }
  1213. }
  1214. }
  1215. void MainWindow::CalcCalibRoll()
  1216. {
  1217. if((mvectorgps.size()>0) &&(mvectortrace.size()>0))
  1218. {
  1219. double gps_x = mvectorgps[mvectorgps.size()-1].x;
  1220. double gps_y = mvectorgps[mvectorgps.size()-1].y;
  1221. double gps_z = mvectorgps[mvectorgps.size()-1].z;
  1222. double ndt_x = mvectortrace[mvectortrace.size()-1].x;
  1223. double ndt_y = mvectortrace[mvectortrace.size()-1].y;
  1224. double ndt_z = mvectortrace[mvectortrace.size()-1].z;
  1225. double gps_dis = sqrt(pow(gps_x,2)+pow(gps_y,2));
  1226. double ndt_dis = sqrt(pow(ndt_x,2)+pow(ndt_y,2));
  1227. if((gps_dis>0)&&(ndt_dis>0) &&(fabs(gps_y)>10))
  1228. {
  1229. double calib_roll = (1.0) * asin((gps_z - ndt_z)/gps_y);
  1230. while(calib_roll>2.0*M_PI) calib_roll = calib_roll - 2.0*M_PI;
  1231. while(calib_roll < 0)calib_roll = calib_roll + 2.0*M_PI;
  1232. mpLE_CalcCalib_Roll->setText(QString::number(calib_roll * 180.0/M_PI));
  1233. }
  1234. }
  1235. }