ソースを参照

change view_ndtmatching. not complete.

yuchuli 1 年間 前
コミット
7598f63e17

+ 44 - 0
src/tool/view_ndtmatching/mainwindow.cpp

@@ -7,6 +7,7 @@
 #include "showxodrinvtk.h"
 #include "showxodrinvtk.h"
 
 
 #include <QMessageBox>
 #include <QMessageBox>
+#include <QFile>
 
 
 static pose gCurPose;
 static pose gCurPose;
 
 
@@ -201,6 +202,7 @@ MainWindow::MainWindow(QWidget *parent) :
 
 
     setWindowTitle("NDT Matching View & Relocation Enable");
     setWindowTitle("NDT Matching View & Relocation Enable");
 
 
+
 }
 }
 
 
 MainWindow::~MainWindow()
 MainWindow::~MainWindow()
@@ -427,3 +429,45 @@ void MainWindow::UpdatePCDMap(const char *strdata, const unsigned int nSize, con
         std::cout<<"UpdatePCDMap Fail."<<std::endl;
         std::cout<<"UpdatePCDMap Fail."<<std::endl;
     }
     }
 }
 }
+
+bool MainWindow::ReadNDTOrigin(std::string strpcdpath,double & flon, double & flat,double & fheading)
+{
+    QString str1 = QString::fromStdString(strpcdpath);
+    QString str2;
+    if(str1.length()<5)return false;
+    str2 = str1.left(str1.length() -4);
+    str2.append(".txt");
+//    qDebug(str2.toLatin1().data());
+
+    QFile xFile;;
+
+    xFile.setFileName(str2);
+    if(!xFile.open(QIODevice::ReadOnly))
+    {
+        return false;
+    }
+
+    QByteArray ba;
+    ba = xFile.readLine();
+    xFile.close();
+    QString str;
+    str = ba;
+    QStringList strlist;
+    strlist = str.split("\t");
+    if(strlist.size() == 6)
+    {
+        QString xstr[6];
+        int i;
+        for(i=0;i<6;i++)xstr[i] = strlist.at(i);
+        flon = xstr[0].toDouble();
+        flat = xstr[1].toDouble();
+//        pnori->height = xstr[2].toDouble();
+        fheading = xstr[3].toDouble();
+//        pnori->pitch = xstr[4].toDouble();
+//        pnori->roll = xstr[5].toDouble();
+        return true;
+    }
+
+    return false;
+}
+

+ 4 - 0
src/tool/view_ndtmatching/mainwindow.h

@@ -61,6 +61,8 @@ private slots:
 private:
 private:
     void threadpcdview();
     void threadpcdview();
 
 
+    bool ReadNDTOrigin(std::string strpcdpath,double & flon, double & flat,double & fheading);
+
 private:
 private:
     void UpdateNDTPos(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
     void UpdateNDTPos(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
     void UpdatePCDMap(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
     void UpdatePCDMap(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
@@ -93,6 +95,8 @@ private:
     std::mutex mmutexpcdmap;
     std::mutex mmutexpcdmap;
     bool mbpcdmapupdate =false;
     bool mbpcdmapupdate =false;
 
 
+
+
 };
 };
 
 
 #endif // MAINWINDOW_H
 #endif // MAINWINDOW_H