Procházet zdrojové kódy

change some ts. and enable relocation.

yuchuli před 1 rokem
rodič
revize
719faa4cd3

+ 12 - 0
src/detection/detection_ndt_matching/main.cpp

@@ -32,6 +32,8 @@ int gndttime;    //ndt calculate time
 
 void * gpa,* gpb ,* gpc, * gpd;   //Modulecomm pointer
 
+void * gparelocate;
+
 iv::Ivfault *gfault = nullptr;   //fault diag
 iv::Ivlog *givlog = nullptr;   //log
 
@@ -418,6 +420,12 @@ void ListenNDTRunstate(const char * strdata,const unsigned int nSize,const unsig
     gfault->SetFaultState(0, 0, "ok");
 }
 
+
+void ListenRelocate(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    gbNeedReloc = true;
+}
+
 /**
  * @brief pausecomm
  */
@@ -427,6 +435,7 @@ void pausecomm()
     iv::modulecomm::PauseComm(gpb);
     iv::modulecomm::PauseComm(gpc);
     iv::modulecomm::PauseComm(gpd);
+    iv::modulecomm::PauseComm(gparelocate);
 }
 
 /**
@@ -438,6 +447,7 @@ void continuecomm()
     iv::modulecomm::ContintuComm(gpb);
     iv::modulecomm::ContintuComm(gpc);
     iv::modulecomm::ContintuComm(gpd);
+    iv::modulecomm::ContintuComm(gparelocate);
 }
 
 /**
@@ -559,6 +569,7 @@ void exitfunc()
     iv::modulecomm::Unregister(gpb);
     iv::modulecomm::Unregister(gpc);
     iv::modulecomm::Unregister(gpd);
+    iv::modulecomm::Unregister(gparelocate);
     if(gpFileLastPos != 0)gpFileLastPos->close();
     std::cout<<"Complete exitfunc."<<std::endl;
 }
@@ -650,6 +661,7 @@ int main(int argc, char *argv[])
     gpb = iv::modulecomm::RegisterRecv(gstr_gpsmsgname.data(),ListenRaw);
     gpc = iv::modulecomm::RegisterSend(gstr_ndtposmsgname.data(),10000,1);
     gpd = iv::modulecomm::RegisterSend(gstr_ndtgpsposmsgname.data(),10000,1);
+    gparelocate = iv::modulecomm::RegisterRecv("relocate",ListenRelocate);
     ndt_match_Init_nomap();
 
     iv::ivexit::RegIVExitCall(exitfunc);

+ 13 - 0
src/include/proto/relocate.proto

@@ -0,0 +1,13 @@
+syntax = "proto2";
+
+package iv.ndt;
+
+message relocate
+{
+	optional bool bEnable = 1;
+
+};
+
+
+
+

+ 1 - 0
src/tool/map_collectfromveh/dialogconvert.cpp

@@ -6,6 +6,7 @@ DialogConvert::DialogConvert(QWidget *parent) :
     ui(new Ui::DialogConvert)
 {
     ui->setupUi(this);
+    setWindowTitle(tr("Convert"));
 }
 
 DialogConvert::~DialogConvert()

+ 16 - 16
src/tool/map_collectfromveh/editwin.cpp

@@ -36,7 +36,7 @@ EditWin::EditWin(QWidget *parent) :
     ui->actionSelectRoad->setChecked(false);
 
 
-    setWindowTitle("Edit Collect Data");
+    setWindowTitle(tr("Edit Collect Data"));
     std::cout<<"complete init."<<std::endl;
 
 }
@@ -378,7 +378,7 @@ void EditWin::on_actionMove_triggered()
     if(ok == false)return;
     if(text.isEmpty())
     {
-        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("数值为空")),QMessageBox::YesAll);
         return;
     }
 
@@ -388,7 +388,7 @@ void EditWin::on_actionMove_triggered()
 
     if(fMove > 10.0)
     {
-        QString str = "移动值超过10米,移动值为: "+ QString::number(fMove) + QString(tr("米,是否进行平移?"));
+        QString str = QString(tr("移动值超过10米,移动值为: "))+ QString::number(fMove) + QString(tr("米,是否进行平移?"));
         QMessageBox::StandardButton button;
         button=QMessageBox::question(this,tr("平移"),str,QMessageBox::Yes|QMessageBox::No);
         if(button==QMessageBox::No)
@@ -471,7 +471,7 @@ void EditWin::on_actionRotate_triggered()
 {
     if(mpselpoint == NULL)
     {
-        QMessageBox::warning(this,"Waring",QString(tr("请先选择一个点")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("请先选择一个点")),QMessageBox::YesAll);
         return;
     }
 
@@ -510,7 +510,7 @@ void EditWin::on_actionMoveFront_triggered()
 {
     if(mpselpoint == NULL)
     {
-        QMessageBox::warning(this,"Waring",QString(tr("请先选择一个点")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("请先选择一个点")),QMessageBox::YesAll);
         return;
     }
 
@@ -522,7 +522,7 @@ void EditWin::on_actionMoveFront_triggered()
     if(ok == false)return;
     if(text.isEmpty())
     {
-        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("数值为空")),QMessageBox::YesAll);
         return;
     }
 
@@ -532,7 +532,7 @@ void EditWin::on_actionMoveFront_triggered()
 
     if(fMove > 10.0)
     {
-        QString str = "移动值超过10米,移动值为: "+ QString::number(fMove) + QString(tr("米,是否进行前移?"));
+        QString str = QString(tr("移动值超过10米,移动值为: "))+ QString::number(fMove) + QString(tr("米,是否进行前移?"));
         QMessageBox::StandardButton button;
         button=QMessageBox::question(this,tr("前移"),str,QMessageBox::Yes|QMessageBox::No);
         if(button==QMessageBox::No)
@@ -564,7 +564,7 @@ void EditWin::on_actionDelete_triggered()
 {
     if(mpselpoint == NULL)
     {
-        QMessageBox::warning(this,"Waring",QString(tr("请先选择一个点")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Waring"),QString(tr("请先选择一个点")),QMessageBox::YesAll);
         return;
     }
 
@@ -712,7 +712,7 @@ void EditWin::on_actionRoadMoveLeft_triggered()
 {
     if(mpselroad == NULL)
     {
-        QMessageBox::warning(this,"Waring",QString(tr("请先选择一条路")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("请先选择一条路")),QMessageBox::YesAll);
         return;
     }
 
@@ -724,7 +724,7 @@ void EditWin::on_actionRoadMoveLeft_triggered()
     if(ok == false)return;
     if(text.isEmpty())
     {
-        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Waring"),QString(tr("数值为空")),QMessageBox::YesAll);
         return;
     }
 
@@ -759,7 +759,7 @@ void EditWin::on_actionRoadMoveFront_triggered()
 {
     if(mpselroad == NULL)
     {
-        QMessageBox::warning(this,"Waring",QString(tr("请先选择一条路")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("请先选择一条路")),QMessageBox::YesAll);
         return;
     }
 
@@ -771,7 +771,7 @@ void EditWin::on_actionRoadMoveFront_triggered()
     if(ok == false)return;
     if(text.isEmpty())
     {
-        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("数值为空")),QMessageBox::YesAll);
         return;
     }
 
@@ -806,7 +806,7 @@ void EditWin::on_actionRoadRotate_triggered()
 {
     if(mpselroad == NULL)
     {
-        QMessageBox::warning(this,"Waring",QString(tr("请先选择一条路")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("请先选择一条路")),QMessageBox::YesAll);
         return;
     }
 
@@ -818,7 +818,7 @@ void EditWin::on_actionRoadRotate_triggered()
     if(ok == false)return;
     if(text.isEmpty())
     {
-        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("数值为空")),QMessageBox::YesAll);
         return;
     }
 
@@ -849,7 +849,7 @@ void EditWin::on_actionRoadDelete_triggered()
 {
     if(mpselroad == NULL)
     {
-        QMessageBox::warning(this,"Waring",QString(tr("请先选择一条路")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("请先选择一条路")),QMessageBox::YesAll);
         return;
     }
     QMessageBox::StandardButton button;
@@ -974,7 +974,7 @@ void EditWin::CreateConnect(int nMode, std::string strroad1, std::string strroad
     }
     if(bExist)
     {
-        QMessageBox::warning(this,"Waring",QString(tr("道路连接已存在")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("道路连接已存在")),QMessageBox::YesAll);
         return;
     }
 

+ 9 - 0
src/tool/map_collectfromveh/main.cpp

@@ -9,6 +9,8 @@ iv::Ivlog * givlog;
 #include <getopt.h>
 #include <iostream>
 
+#include <QTranslator>
+
 char gstr_memname[256];
 
 
@@ -85,6 +87,13 @@ int main(int argc, char *argv[])
     givlog = new iv::Ivlog("map_collectfromveh");
     QApplication a(argc, argv);
 
+    QTranslator ts;
+    if(ts.load("./map_collectfromveh_language.qm"))
+    {
+        a.installTranslator(&ts);
+    }
+
+
     snprintf(gstr_memname,255,"hcp2_gpsimu");
 
     int nRtn = GetOptLong(argc,argv);

+ 13 - 13
src/tool/map_collectfromveh/mainwindow.cpp

@@ -117,7 +117,7 @@ MainWindow::MainWindow(QWidget *parent)
     double lon,lat;
     GaussProjInvCal(x,y,&lon,&lat);
 
-    setWindowTitle("Collect Data From Vehicle");
+    setWindowTitle(tr("Collect Data From Vehicle"));
 
     gw = this;
 
@@ -161,7 +161,7 @@ void MainWindow::on_pushButton_NewRoad_clicked()
 {
     if(mpEditWin->IsShow())
     {
-        QMessageBox::warning(this,"Warning",QString(tr("编辑窗口打开状态,请先关闭编辑窗口")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("编辑窗口打开状态,请先关闭编辑窗口")),QMessageBox::YesAll);
         return;
     }
     bool ok;
@@ -177,7 +177,7 @@ void MainWindow::on_pushButton_NewRoad_clicked()
     {
         if(mcollectveh.mutable_mroads(i)->strroadname() == text.toStdString())
         {
-            QMessageBox::warning(this,"Warning","Road Is Exist",QMessageBox::YesAll);
+            QMessageBox::warning(this,tr("Warning"),tr("Road Is Exist"),QMessageBox::YesAll);
             return;
         }
     }
@@ -454,7 +454,7 @@ void MainWindow::on_actionReset_triggered()
 {
     if(mbStartCollect)
     {
-        QMessageBox::warning(this,"Warning",QString(tr("请先停止采集")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("请先停止采集")),QMessageBox::YesAll);
         return;
     }
     QMessageBox::StandardButton button;
@@ -502,7 +502,7 @@ void MainWindow::on_actionSave_triggered()
     xFile.setFileName(str);
     if(!xFile.open(QIODevice::ReadWrite))
     {
-        QMessageBox::warning(this,"Warning","Open Save File Fail.",QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),tr("Open Save File Fail."),QMessageBox::YesAll);
         return;
     }
     int nbytesize = mcollectveh.ByteSize();
@@ -514,7 +514,7 @@ void MainWindow::on_actionSave_triggered()
     }
     else
     {
-        QMessageBox::warning(this,"Waring","Serialize Collect Data Fail.",QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Waring"),tr("Serialize Collect Data Fail."),QMessageBox::YesAll);
     }
     xFile.close();
 }
@@ -523,7 +523,7 @@ void MainWindow::on_actionLoad_triggered()
 {
     if(mbStartCollect)
     {
-        QMessageBox::warning(this,"Warning",QString(tr("请先停止采集")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("请先停止采集")),QMessageBox::YesAll);
         return;
     }
     if(mcollectveh.mroads_size() > 0)
@@ -535,13 +535,13 @@ void MainWindow::on_actionLoad_triggered()
             return;
         }
     }
-    QString str = QFileDialog::getOpenFileName(this,"Load Collect",".","*.cov");
+    QString str = QFileDialog::getOpenFileName(this,tr("Load Collect"),".","*.cov");
     if(str.isEmpty())return;
     QFile xFile;
     xFile.setFileName(str);
     if(!xFile.open(QIODevice::ReadOnly))
     {
-        QMessageBox::warning(this,"Warning","Open File Fail.",QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),tr("Open File Fail."),QMessageBox::YesAll);
         return;
     }
     QByteArray ba = xFile.readAll();
@@ -550,7 +550,7 @@ void MainWindow::on_actionLoad_triggered()
     ResetPointView();
     if(!mcollectveh.ParseFromArray(ba.data(),ba.size()))
     {
-        QMessageBox::warning(this,"Warning","Parse File Data Fail.",QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),tr("Parse File Data Fail."),QMessageBox::YesAll);
         return;
     }
 
@@ -655,7 +655,7 @@ void MainWindow::on_actionEdit_Collect_triggered()
 {
     if(mbStartCollect == true)
     {
-        QMessageBox::warning(this,"Warning",QString(tr("采集数据在激活状态,请先完成采集")),QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),QString(tr("采集数据在激活状态,请先完成采集")),QMessageBox::YesAll);
         return;
     }
     mpEditWin->Setcollect(mcollectveh);
@@ -737,7 +737,7 @@ void MainWindow::on_actionConvert_triggered()
 {
     if(mcollectveh.mroads_size() == 0)
     {
-        QMessageBox::warning(this,"Warning","No Roads",QMessageBox::YesAll);
+        QMessageBox::warning(this,tr("Warning"),tr("No Roads"),QMessageBox::YesAll);
         return;
     }
     OpenDrive xxodr;
@@ -745,7 +745,7 @@ void MainWindow::on_actionConvert_triggered()
     pco->StartConvert();
     delete pco;
 
-    QString str = QFileDialog::getSaveFileName(this,"Save OpenDrive",".","*.xodr");
+    QString str = QFileDialog::getSaveFileName(this,tr("Save OpenDrive"),".","*.xodr");
     if(str.isEmpty())return;
     if(str.right(5) != ".xodr")str = str + ".xodr";
     OpenDriveXmlWriter x(&xxodr);

+ 2 - 0
src/tool/map_collectfromveh/map_collectfromveh.pro

@@ -95,3 +95,5 @@ DISTFILES += \
     ../map_lanetoxodr/TinyXML/TinyXML.pri
 
 DEFINES += NOTINPILOT
+
+TRANSLATIONS = map_collectfromveh_language.ts

+ 589 - 0
src/tool/map_collectfromveh/map_collectfromveh_language.ts

@@ -0,0 +1,589 @@
+<?xml version="1.0" encoding="utf-8"?>
+<!DOCTYPE TS>
+<TS version="2.1" language="zh">
+<context>
+    <name>DialogConvert</name>
+    <message>
+        <location filename="dialogconvert.ui" line="14"/>
+        <source>Dialog</source>
+        <translation>Dialog</translation>
+    </message>
+    <message>
+        <location filename="dialogconvert.cpp" line="9"/>
+        <source>Convert</source>
+        <translation>Convert</translation>
+    </message>
+</context>
+<context>
+    <name>EditWin</name>
+    <message>
+        <location filename="editwin.ui" line="14"/>
+        <source>MainWindow</source>
+        <translation>MainWindow</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="32"/>
+        <source>Point</source>
+        <translation>Point</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="41"/>
+        <source>Road</source>
+        <translation>Road</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="51"/>
+        <source>View</source>
+        <translation>View</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="55"/>
+        <source>Select</source>
+        <translation>Select</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="65"/>
+        <source>Connect</source>
+        <translation>Connect</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="80"/>
+        <source>toolBar</source>
+        <translation>toolBar</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="114"/>
+        <location filename="editwin.ui" line="162"/>
+        <location filename="editwin.cpp" line="393"/>
+        <source>平移</source>
+        <translation>Move</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="117"/>
+        <source>左移一个点</source>
+        <translation>Move A Point To Left</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="126"/>
+        <location filename="editwin.ui" line="186"/>
+        <location filename="editwin.cpp" line="479"/>
+        <source>旋转</source>
+        <translation>Rotate</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="129"/>
+        <source>旋转一个点</source>
+        <translation>Rotate A Point</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="138"/>
+        <location filename="editwin.ui" line="198"/>
+        <location filename="editwin.cpp" line="572"/>
+        <location filename="editwin.cpp" line="856"/>
+        <source>删除</source>
+        <translation>Delete</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="141"/>
+        <source>删除一个点</source>
+        <translation>Delete A Point</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="150"/>
+        <location filename="editwin.ui" line="174"/>
+        <location filename="editwin.cpp" line="518"/>
+        <location filename="editwin.cpp" line="537"/>
+        <source>前移</source>
+        <translation>Move Front</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="153"/>
+        <source>前移一个点</source>
+        <translation>Move A Point To Front</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="165"/>
+        <source>所选道路的所有点向左平移</source>
+        <translation>Translate all points of the selected road to the left</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="177"/>
+        <source>所选道路的所有点向前平移</source>
+        <translation>Translate all points of the selected road forward</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="189"/>
+        <source>所选道路的所有点原地旋转</source>
+        <translation>All points of the selected road rotate in place</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="201"/>
+        <source>删除道路</source>
+        <translation>Delete Road</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="210"/>
+        <source>添加</source>
+        <translation>Add</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="213"/>
+        <source>添加道路</source>
+        <translation>Add Road</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="225"/>
+        <source>SelectNone</source>
+        <translation>Select None</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="228"/>
+        <source>不选择点或道路</source>
+        <translation>Do not select points or roads</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="240"/>
+        <source>SelectPoint</source>
+        <translation>SelectPoint</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="243"/>
+        <source>选择点</source>
+        <translation>SelectPoint</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="255"/>
+        <source>SelectRoad</source>
+        <translation>SelectRoad</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="258"/>
+        <source>选择道路</source>
+        <translation>SelectRoad</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="270"/>
+        <location filename="editwin.cpp" line="336"/>
+        <source>直连</source>
+        <translation>Straight</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="273"/>
+        <source>建立道路直接连接</source>
+        <translation>Create Straight</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="285"/>
+        <location filename="editwin.cpp" line="340"/>
+        <source>转弯</source>
+        <translation>Turn</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="288"/>
+        <source>建立转弯连接</source>
+        <translation>Create Turn</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="300"/>
+        <location filename="editwin.cpp" line="344"/>
+        <source>调头</source>
+        <translation>UTurn</translation>
+    </message>
+    <message>
+        <location filename="editwin.ui" line="303"/>
+        <source>建立掉头连接</source>
+        <translation>Create UTurn</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="39"/>
+        <source>Edit Collect Data</source>
+        <translation>Edit Collect Data</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="350"/>
+        <source>是否在道路(</source>
+        <translation>Is in Road(</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="351"/>
+        <source>)和道路(</source>
+        <translation>)And Road(</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="352"/>
+        <source>)建立</source>
+        <translation>)Create</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="352"/>
+        <source>连接?</source>
+        <translation>Connect?</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="354"/>
+        <source>建立连接</source>
+        <translation>Create Connect</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="369"/>
+        <location filename="editwin.cpp" line="474"/>
+        <location filename="editwin.cpp" line="513"/>
+        <location filename="editwin.cpp" line="567"/>
+        <source>请先选择一个点</source>
+        <translation>Please Select A Point</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="374"/>
+        <source>左移</source>
+        <translation>Move Left</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="375"/>
+        <location filename="editwin.cpp" line="721"/>
+        <source>左移值:</source>
+        <translation>Move Left Value:</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="376"/>
+        <location filename="editwin.cpp" line="481"/>
+        <location filename="editwin.cpp" line="520"/>
+        <location filename="editwin.cpp" line="722"/>
+        <location filename="editwin.cpp" line="769"/>
+        <location filename="editwin.cpp" line="816"/>
+        <source>0.0</source>
+        <translation>0.0</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="381"/>
+        <location filename="editwin.cpp" line="474"/>
+        <location filename="editwin.cpp" line="513"/>
+        <location filename="editwin.cpp" line="525"/>
+        <location filename="editwin.cpp" line="715"/>
+        <location filename="editwin.cpp" line="762"/>
+        <location filename="editwin.cpp" line="774"/>
+        <location filename="editwin.cpp" line="809"/>
+        <location filename="editwin.cpp" line="821"/>
+        <location filename="editwin.cpp" line="852"/>
+        <location filename="editwin.cpp" line="977"/>
+        <source>Warning</source>
+        <translation>Warning</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="381"/>
+        <location filename="editwin.cpp" line="486"/>
+        <location filename="editwin.cpp" line="525"/>
+        <location filename="editwin.cpp" line="727"/>
+        <location filename="editwin.cpp" line="774"/>
+        <location filename="editwin.cpp" line="821"/>
+        <source>数值为空</source>
+        <translation>Value is Null</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="391"/>
+        <location filename="editwin.cpp" line="535"/>
+        <source>移动值超过10米,移动值为: </source>
+        <translation>Move Value Extend 10 meters, Value: </translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="391"/>
+        <source>米,是否进行平移?</source>
+        <translation> Meters, Move? </translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="480"/>
+        <source>旋转值=:</source>
+        <translation>Rotate Value:</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="519"/>
+        <location filename="editwin.cpp" line="768"/>
+        <source>前移值:</source>
+        <translation>Move Front Value:</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="535"/>
+        <source>米,是否进行前移?</source>
+        <translation>meters, Move Front? </translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="567"/>
+        <location filename="editwin.cpp" line="727"/>
+        <source>Waring</source>
+        <translation>Warning</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="572"/>
+        <source>确认删除点?</source>
+        <translation>Confirm Delete Point?</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="715"/>
+        <location filename="editwin.cpp" line="762"/>
+        <location filename="editwin.cpp" line="809"/>
+        <location filename="editwin.cpp" line="852"/>
+        <source>请先选择一条路</source>
+        <translation>Please Select Road</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="720"/>
+        <source>左移道路</source>
+        <translation>Move A Road To Left</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="767"/>
+        <source>前移道路</source>
+        <translation>Move A Road To Front</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="814"/>
+        <source>旋转道路上每一个点</source>
+        <translation>Move All Points At Road</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="815"/>
+        <source>旋转值:</source>
+        <translation>Rotate Value:</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="856"/>
+        <source>确认删除道路?</source>
+        <translation>Confirm Delete Road?</translation>
+    </message>
+    <message>
+        <location filename="editwin.cpp" line="977"/>
+        <source>道路连接已存在</source>
+        <translation>Connect is Exists</translation>
+    </message>
+</context>
+<context>
+    <name>MainWindow</name>
+    <message>
+        <location filename="mainwindow.ui" line="14"/>
+        <source>MainWindow</source>
+        <translation>MainWindow</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="31"/>
+        <source>新道路</source>
+        <translation>New Road</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="44"/>
+        <source>完成</source>
+        <translation>Complete</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="57"/>
+        <source>采集模式</source>
+        <translation>Collection Mode</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="69"/>
+        <source>自动</source>
+        <translation>Auto</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="82"/>
+        <source>手动</source>
+        <translation>Manual</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="95"/>
+        <source>手动采集</source>
+        <translation>Manual Collection</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="109"/>
+        <source>左边线</source>
+        <translation>Left Lane</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="131"/>
+        <location filename="mainwindow.ui" line="249"/>
+        <source>距离</source>
+        <translation>Distance</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="144"/>
+        <location filename="mainwindow.ui" line="262"/>
+        <source>颜色</source>
+        <translation>Color</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="157"/>
+        <location filename="mainwindow.ui" line="275"/>
+        <source>类型</source>
+        <translation>Type</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="191"/>
+        <source>宽度</source>
+        <translation>Width</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="227"/>
+        <source>右边线</source>
+        <translation>RIght Lane</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="309"/>
+        <location filename="mainwindow.cpp" line="168"/>
+        <source>道路名称</source>
+        <translation>Road Name</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="334"/>
+        <source>File</source>
+        <translation>File</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="342"/>
+        <source>Edit</source>
+        <translation>Edit</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="348"/>
+        <source>Tool</source>
+        <translation>Tool</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="359"/>
+        <source>Load</source>
+        <translation>Load</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="364"/>
+        <source>Save</source>
+        <translation>Save</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="369"/>
+        <source>Reset</source>
+        <translation>Reset</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="374"/>
+        <source>Edit Collect</source>
+        <translation>Edit Collect</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.ui" line="379"/>
+        <source>Convert</source>
+        <translation>Convert</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="120"/>
+        <source>Collect Data From Vehicle</source>
+        <translation>Collect Data From Vehicle</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="164"/>
+        <location filename="mainwindow.cpp" line="180"/>
+        <location filename="mainwindow.cpp" line="457"/>
+        <location filename="mainwindow.cpp" line="505"/>
+        <location filename="mainwindow.cpp" line="526"/>
+        <location filename="mainwindow.cpp" line="544"/>
+        <location filename="mainwindow.cpp" line="553"/>
+        <location filename="mainwindow.cpp" line="658"/>
+        <location filename="mainwindow.cpp" line="740"/>
+        <source>Warning</source>
+        <translation>Warning</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="164"/>
+        <source>编辑窗口打开状态,请先关闭编辑窗口</source>
+        <translation>The editing window is open. Please close the editing window first</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="169"/>
+        <source>道路名称:</source>
+        <translation>Road Name:</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="170"/>
+        <source>道路1</source>
+        <translation>Road1</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="180"/>
+        <source>Road Is Exist</source>
+        <translation>Road Is Exist</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="457"/>
+        <location filename="mainwindow.cpp" line="526"/>
+        <source>请先停止采集</source>
+        <translation>Please stop collecting first</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="461"/>
+        <source>重置采集</source>
+        <translation>Reset Collect</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="461"/>
+        <source>是否重置采集</source>
+        <translation>if Reset Collect</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="470"/>
+        <source>采集重置成功</source>
+        <translation>Reset Collect Successful</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="505"/>
+        <source>Open Save File Fail.</source>
+        <translation>Open Save File Fail.</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="517"/>
+        <source>Waring</source>
+        <translation>Warning</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="517"/>
+        <source>Serialize Collect Data Fail.</source>
+        <translation>Serialize Collect Data Fail.</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="532"/>
+        <source>加载数据</source>
+        <translation>Load Data</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="532"/>
+        <source>当前已有采集,是否加载数据</source>
+        <translation>Currently collected, do you want to load data</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="538"/>
+        <source>Load Collect</source>
+        <translation>Load Collect</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="544"/>
+        <source>Open File Fail.</source>
+        <translation>Open File Fail.</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="553"/>
+        <source>Parse File Data Fail.</source>
+        <translation>Parse File Data Fail.</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="658"/>
+        <source>采集数据在激活状态,请先完成采集</source>
+        <translation>Data collection is active, please complete the collection first</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="740"/>
+        <source>No Roads</source>
+        <translation>No Roads</translation>
+    </message>
+    <message>
+        <location filename="mainwindow.cpp" line="748"/>
+        <source>Save OpenDrive</source>
+        <translation>Save OpenDrive</translation>
+    </message>
+</context>
+</TS>

+ 48 - 2
src/tool/view_ndtmatching/mainwindow.cpp

@@ -4,6 +4,7 @@
 #include <pcl/io/ply_io.h>
 #include <pcl/io/obj_io.h>
 
+#include <QMessageBox>
 
 static pose gCurPose;
 
@@ -135,7 +136,7 @@ MainWindow::MainWindow(QWidget *parent) :
     mpLabelStatus = new QLabel("No NDT Pos",ui->statusbar);
     mpLabelStatus->setMinimumWidth(350);
 
-    ui->pushButton_EnableRelocation->setEnabled(false);
+//    ui->pushButton_EnableRelocation->setEnabled(false);
 
     ui->pushButton_Test->setVisible(false);
 
@@ -160,6 +161,8 @@ MainWindow::MainWindow(QWidget *parent) :
     ModuleFun fun1 =std::bind(&MainWindow::UpdateNDTPos,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
     mpandtpos = iv::modulecomm::RegisterRecvPlus("ndtpos",fun1);
 
+    mparelocate = iv::modulecomm::RegisterSend("relocate",10000,1);
+
     connect(this,SIGNAL(ndtposupdate()),this,SLOT(onndtposupdate()));
 
     setWindowTitle("NDT Matching View & Relocation Enable");
@@ -171,6 +174,7 @@ MainWindow::~MainWindow()
     mbRun = false;
     mpthreadpcd->join();
     iv::modulecomm::Unregister(mpandtpos);
+    iv::modulecomm::Unregister(mparelocate);
     delete ui;
 }
 
@@ -185,7 +189,10 @@ void MainWindow::threadpcdview()
      pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud2(
                  new pcl::PointCloud<pcl::PointXYZI>());
 
-     pcl::io::loadPCDFile<pcl::PointXYZI>("/home/yuchuli/map/map.pcd",*point_cloud);
+     char strpcpath[256];
+     snprintf(strpcpath,256,"%s/map/map.pcd",getenv("HOME"));
+
+     pcl::io::loadPCDFile<pcl::PointXYZI>(strpcpath,*point_cloud);
 
  //    pcl::io::loadOBJFile("/home/yuchuli/car.obj",*point_cloud);
 //     pcl::io::loadPLYFile("/home/yuchuli/car.ply",*point_cloud);
@@ -231,7 +238,44 @@ void MainWindow::on_pushButton_Test_clicked()
 
 void MainWindow::on_pushButton_EnableRelocation_clicked()
 {
+    static int64_t nLastSend = 0;
+
+    int64_t nnow = std::chrono::system_clock::now().time_since_epoch().count()/1000000;
+
+    if(abs(nnow - nLastSend) < 180000)
+    {
+        QMessageBox::warning(this,tr("Warning"),tr("EnableRelocation Must Interval 3 minutes. "),QMessageBox::YesAll);
+        return;
+    }
 
+    if(mfTransProb >= 2.0)
+    {
+
+        QMessageBox::StandardButton button;
+        button=QMessageBox::question(this,tr("Relocate"),QString(tr("TransProblity is more than 2.0,do you want relocation?")),QMessageBox::Yes|QMessageBox::No);
+        if(button==QMessageBox::No)
+        {
+            return;
+        }
+        else if(button==QMessageBox::Yes)
+        {
+        }
+
+    }
+
+    iv::ndt::relocate xreloc;
+    xreloc.set_benable(true);
+    int nbytesize = xreloc.ByteSize();
+    std::shared_ptr<char> pstr_ptr = std::shared_ptr<char>(new char[nbytesize]);
+    if(xreloc.SerializeToArray(pstr_ptr.get(),nbytesize))
+    {
+        iv::modulecomm::ModuleSendMsg(mparelocate,pstr_ptr.get(),nbytesize);
+    }
+    else
+    {
+        QMessageBox::warning(this,tr("Warning"),tr("Relocate Message Serialize Fail."),QMessageBox::YesAll);
+    }
+    nLastSend = nnow;
 }
 
 void MainWindow::on_horizontalSlider_valueChanged(int value)
@@ -302,6 +346,8 @@ void MainWindow::onndtposupdate()
         ui->lineEdit_pitch->setText(QString::number(gCurPose.pitch,'f',3));
         ui->lineEdit_roll->setText(QString::number(gCurPose.roll,'f',3));
 
+        mfTransProb = xndtpos.trans_probability();
+
         mpLabelStatus->setText("NDT Update Time:" + QDateTime::currentDateTime().toString("yyyy-MM-dd hh:mm:ss:zzz"));
     }
 }

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

@@ -14,6 +14,7 @@
 
 #include "modulecomm.h"
 #include "ndtpos.pb.h"
+#include "relocate.pb.h"
 
 #include <QLabel>
 
@@ -72,6 +73,7 @@ private:
     bool mbRun = true;
 
     void * mpandtpos;
+    void * mparelocate;
 
     pose mCurPose;
 
@@ -82,6 +84,8 @@ private:
     QLabel * mpLabelStatus;
 
 
+    double mfTransProb = 0.0;
+
 };
 
 #endif // MAINWINDOW_H

+ 4 - 2
src/tool/view_ndtmatching/view_ndtmatching.pro

@@ -18,7 +18,8 @@ DEFINES += QT_DEPRECATED_WARNINGS
 
 SOURCES += main.cpp \
     mainwindow.cpp \
-    ../../include/msgtype/ndtpos.pb.cc
+    ../../include/msgtype/ndtpos.pb.cc \
+    ../../include/msgtype/relocate.pb.cc
 
 QMAKE_LFLAGS += -no-pie
 
@@ -65,7 +66,8 @@ FORMS += \
 
 HEADERS += \
     mainwindow.h \
-    ../../include/msgtype/ndtpos.pb.h
+    ../../include/msgtype/ndtpos.pb.h \
+    ../../include/msgtype/relocate.pb.h
 
 !include(../../../include/common.pri ) {
     error( "Couldn't find the common.pri file!" )