Jelajahi Sumber

add tool/map_rtkdatafromveh. for collect rtk data from vehicle gps.

yuchuli 3 tahun lalu
induk
melakukan
2150352c85

+ 73 - 0
src/tool/map_rtkdatafromveh/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 153 - 0
src/tool/map_rtkdatafromveh/gnss_coordinate_convert.cpp

@@ -0,0 +1,153 @@
+#include <gnss_coordinate_convert.h>
+
+void gps2xy(double J4, double K4, double *x, double *y)
+{
+    int L4 = (int)((K4 - 1.5) / 3) + 1;
+    double M4 = K4 - (L4 * 3);
+    double N4 = sin(J4 * 3.1415926536 / 180);
+    double O4 = cos(J4 * 3.1415926536 / 180);
+    double P4 = tan(J4 * 3.1415926536 / 180);
+    double Q4 = 111134.8611 * J4 - N4 * O4 * (32005.7799 + 133.9238 * N4 * N4 + 0.6973 * N4 * N4 * N4 * N4 + 0.0039 * N4 * N4 * N4 * N4 * N4 * N4);
+    double R4 = sqrt(0.006738525414683) * O4;
+    double S4 = sqrt(1 + R4 * R4);
+    double T4 = 6399698.901783 / S4;
+    double U4 = (T4 / S4) / S4;
+    double V4 = O4 * M4 * 3.1415926536 / 180;
+    double W4 = 0.5 + (5 - P4 * P4 + 9 * R4 * R4 + 4 * R4 * R4 * R4 * R4) * V4 * V4 / 24;
+    double X4 = V4 * V4 * V4 * V4 / 720 * (61 + (P4 * P4 - 58) * P4 * P4);
+    double Y4 = 1 + V4 * V4 * (1 - P4 * P4 + R4 * R4) / 6;
+    double Z4 = V4 * V4 * V4 * V4 * (5 - 18 * P4 * P4 * P4 * P4 * P4 * P4 + 14 * R4 * R4 - 58 * R4 * R4 * P4 * P4) / 120;
+
+    *y = Q4 + T4 * P4 * V4 * V4 * (W4 + X4);
+    *x = 500000 + T4 * V4 * (Y4 + Z4);
+}
+
+//高斯投影由经纬度(Unit:DD)反算大地坐标(含带号,Unit:Metres)
+void GaussProjCal(double longitude, double latitude, double *X, double *Y)
+{
+    int ProjNo = 0; int ZoneWide; ////带宽
+    double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
+    double a, f, e2, ee, NN, T, C, A, M, iPI;
+    iPI = 0.0174532925199433; ////3.1415926535898/180.0;
+    ZoneWide = 6; ////6度带宽
+    a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
+                                    ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
+    ProjNo = (int)(longitude / ZoneWide);
+    longitude0 = ProjNo * ZoneWide + ZoneWide / 2;
+    longitude0 = longitude0 * iPI;
+    latitude0 = 0;
+    longitude1 = longitude * iPI; //经度转换为弧度
+    latitude1 = latitude * iPI; //纬度转换为弧度
+    e2 = 2 * f - f * f;
+    ee = e2 * (1.0 - e2);
+    NN = a / sqrt(1.0 - e2 * sin(latitude1)*sin(latitude1));
+    T = tan(latitude1)*tan(latitude1);
+    C = ee * cos(latitude1)*cos(latitude1);
+    A = (longitude1 - longitude0)*cos(latitude1);
+    M = a * ((1 - e2 / 4 - 3 * e2*e2 / 64 - 5 * e2*e2*e2 / 256)*latitude1 - (3 * e2 / 8 + 3 * e2*e2 / 32 + 45 * e2*e2
+        *e2 / 1024)*sin(2 * latitude1)
+        + (15 * e2*e2 / 256 + 45 * e2*e2*e2 / 1024)*sin(4 * latitude1) - (35 * e2*e2*e2 / 3072)*sin(6 * latitude1));
+    xval = NN * (A + (1 - T + C)*A*A*A / 6 + (5 - 18 * T + T * T + 72 * C - 58 * ee)*A*A*A*A*A / 120);
+    yval = M + NN * tan(latitude1)*(A*A / 2 + (5 - T + 9 * C + 4 * C*C)*A*A*A*A / 24
+        + (61 - 58 * T + T * T + 600 * C - 330 * ee)*A*A*A*A*A*A / 720);
+    X0 = 1000000L * (ProjNo + 1) + 500000L;
+    Y0 = 0;
+    xval = xval + X0; yval = yval + Y0;
+    *X = xval;
+    *Y = yval;
+}
+
+
+
+//=======================zhaobo0904
+#define PI  3.14159265358979
+//void GaussProjCal(double lon, double lat, double *X, double *Y)
+//{
+//    // 1975 年国际椭球体长半轴 a, 第一离心率 e2, 第二离心率 ep2
+//    double a = 6378140.0;
+//    double e2 = 0.006694384999588;
+//    double ep2 = e2/(1-e2);
+
+//    // 原点所在经度
+//    double lon_origin = 6.0*int(lon/6) + 3.0;
+//    lon_origin *= PI / 180.0;
+
+//    double k0 = 0.9996;
+
+//    // 角度转弧度
+//    double lat1 = lat * PI / 180.0;
+//    double lon1 = lon * PI / 180.0;
+
+
+//    // 经线在该点处的曲率半径,
+//    double N = a / sqrt(1 - e2*sin(lat1)*sin(lat1));
+
+
+//    // 赤道到该点的经线长度近似值 M, 使用泰勒展开逐项积分然后取前四项.
+//    // 这个近似值是将 N 作为纬度 \phi 的函数展开为泰勒计数, 然后在区间 [0, lat1] 上积分得到的.
+//    // 首先计算前四项的系数 a1~a4.
+//    double a1 = 1 - e2/4 - (3*e2*e2)/64 - (5*e2*e2*e2)/256;
+//    double a2 = (3*e2)/8 + (3*e2*e2)/32 + (45*e2*e2*e2)/1024;
+//    double a3 = (15*e2*e2)/256 + (45*e2*e2*e2)/1024;
+//    double a4 = (35*e2*e2*e2)/3072;
+//    double M = a * (a1*lat1 - a2*sin(2*lat1) + a3*sin(4*lat1) - a4*sin(6*lat1));
+
+//    // 辅助量
+//    double T = tan(lat1)*tan(lat1);
+//    double C = ep2*cos(lat1)*cos(lat1);
+//    double A = (lon1 - lon_origin)*cos(lat1);
+
+//    *X = 500000.0 + k0 * N * (A + (1 - T + C)*(A*A*A)/6 + (5 - 18*T + T*T + 72*C - 58*ep2)*(A*A*A*A*A)/120);
+//    *Y = M + N * tan(lat1) * ((A*A)/2 +
+//                              (5 - T + 9*C + 4*C*C)*(A*A*A*A)/24 +
+//                              (61 - 58*T + T*T + 600*C - 330*ep2)*(A*A*A*A*A*A)/720);
+
+
+//    *Y *= k0;
+//    return;
+//}
+//==========================================================
+
+
+
+
+
+//高斯投影由大地坐标(Unit:Metres)反算经纬度(Unit:DD)
+void GaussProjInvCal(double X, double Y, double *longitude, double *latitude)
+{
+    int ProjNo; int ZoneWide; ////带宽
+    double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
+    double e1, e2, f, a, ee, NN, T, C, M, D, R, u, fai, iPI;
+    iPI = 0.0174532925199433; ////3.1415926535898/180.0;
+    a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
+    ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
+    ZoneWide = 6; ////6度带宽
+    ProjNo = (int)(X / 1000000L); //查找带号
+    longitude0 = (ProjNo - 1) * ZoneWide + ZoneWide / 2;
+    longitude0 = longitude0 * iPI; //中央经线
+    X0 = ProjNo * 1000000L + 500000L;
+    Y0 = 0;
+    xval = X - X0; yval = Y - Y0; //带内大地坐标
+    e2 = 2 * f - f * f;
+    e1 = (1.0 - sqrt(1 - e2)) / (1.0 + sqrt(1 - e2));
+    ee = e2 / (1 - e2);
+    M = yval;
+    u = M / (a*(1 - e2 / 4 - 3 * e2*e2 / 64 - 5 * e2*e2*e2 / 256));
+    fai = u + (3 * e1 / 2 - 27 * e1*e1*e1 / 32)*sin(2 * u) + (21 * e1*e1 / 16 - 55 * e1*e1*e1*e1 / 32)*sin(
+                4 * u)
+            + (151 * e1*e1*e1 / 96)*sin(6 * u) + (1097 * e1*e1*e1*e1 / 512)*sin(8 * u);
+    C = ee * cos(fai)*cos(fai);
+    T = tan(fai)*tan(fai);
+    NN = a / sqrt(1.0 - e2 * sin(fai)*sin(fai));
+    R = a * (1 - e2) / sqrt((1 - e2 * sin(fai)*sin(fai))*(1 - e2 * sin(fai)*sin(fai))*(1 - e2 * sin
+                                                                                       (fai)*sin(fai)));
+    D = xval / NN;
+    //计算经度(Longitude) 纬度(Latitude)
+    longitude1 = longitude0 + (D - (1 + 2 * T + C)*D*D*D / 6 + (5 - 2 * C + 28 * T - 3 * C*C + 8 * ee + 24 * T*T)*D
+                               *D*D*D*D / 120) / cos(fai);
+    latitude1 = fai - (NN*tan(fai) / R)*(D*D / 2 - (5 + 3 * T + 10 * C - 4 * C*C - 9 * ee)*D*D*D*D / 24
+                                         + (61 + 90 * T + 298 * C + 45 * T*T - 256 * ee - 3 * C*C)*D*D*D*D*D*D / 720);
+    //转换为度 DD
+    *longitude = longitude1 / iPI;
+    *latitude = latitude1 / iPI;
+}

+ 26 - 0
src/tool/map_rtkdatafromveh/gnss_coordinate_convert.h

@@ -0,0 +1,26 @@
+#pragma once
+#ifndef _IV_PERCEPTION_GNSS_CONVERT_
+#define _IV_PERCEPTION_GNSS_CONVERT_
+
+#include <math.h>
+//double nmeaConvert2Lat(string lat)
+//{
+//	Console.WriteLine(lat);
+//	double nmea_d = double.Parse(lat.Substring(0, 2));
+//	double nmea_m = double.Parse(lat.Substring(2, 6));
+//	return nmea_d + nmea_m / 60;
+//}
+//
+//double nmeaConvert2Lon(string lon)
+//{
+//	Console.WriteLine(lon);
+//	double nmea_d = double.Parse(lon.Substring(0, 3));
+//	double nmea_m = double.Parse(lon.Substring(3, 7));
+//	return nmea_d + nmea_m / 60;
+//}
+
+void gps2xy(double , double , double *, double *);
+void GaussProjCal(double longitude, double latitude, double *X, double *Y);
+void GaussProjInvCal(double X, double Y, double *longitude, double *latitude);
+
+#endif // !_IV_PERCEPTION_GNSS_CONVERT_

+ 14 - 0
src/tool/map_rtkdatafromveh/main.cpp

@@ -0,0 +1,14 @@
+#include "mainwindow.h"
+
+#include <QApplication>
+
+#include "ivbacktrace.h"
+
+int main(int argc, char *argv[])
+{
+    RegisterIVBackTrace();
+    QApplication a(argc, argv);
+    MainWindow w;
+    w.show();
+    return a.exec();
+}

+ 183 - 0
src/tool/map_rtkdatafromveh/mainwindow.cpp

@@ -0,0 +1,183 @@
+#include "mainwindow.h"
+#include "ui_mainwindow.h"
+
+#include <QFileDialog>
+#include <QMessageBox>
+
+#include "gnss_coordinate_convert.h"
+
+MainWindow::MainWindow(QWidget *parent)
+    : QMainWindow(parent)
+    , ui(new Ui::MainWindow)
+{
+    ui->setupUi(this);
+
+    ui->lineEdit_xoff->setText("2.3");
+    ui->lineEdit_yoff->setText("0.0");
+    ui->lineEdit_zoff->setText("0.0");
+
+    ModuleFun fungps = std::bind(&MainWindow::UpdateGPS,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
+    mpagpsmsg = iv::modulecomm::RegisterRecvPlus("hcp2_gpsimu",fungps);
+
+    QTimer * timer = new QTimer();
+    connect(timer,SIGNAL(timeout()),this,SLOT(onTimer()));
+    timer->start(10);
+
+    setWindowTitle("Collect RTK Data From Vehicle GPS");
+}
+
+MainWindow::~MainWindow()
+{
+    delete ui;
+}
+
+
+void MainWindow::on_actionNewCollection_triggered()
+{
+    QString str = QFileDialog::getSaveFileName(this,tr("Save RTK Data"),"",tr("csv File(*.csv)"));
+    if(str.isEmpty())return;
+
+    if(!str.contains(".csv"))
+    {
+        str.append(".csv");
+    }
+
+    if(mbProc)
+    {
+        mbProc = false;
+        mFile.close();
+
+    }
+    ui->plainTextEdit->clear();
+    mdistotal = 0.0;
+
+    mFile.setFileName(str);
+    if(mFile.open(QIODevice::ReadWrite))
+    {
+        mbProc = true;
+    }
+    else
+    {
+        QMessageBox::warning(this,"Warning","Open csv File Fail.",QMessageBox::YesAll);
+        return;
+    }
+    char strout[256];
+    snprintf(strout,256,"virtualbase,0.0    ,0.0    ,0.0");
+    mFile.write(strout,strnlen(strout,256));
+    mFile.write("\n",1);
+    ui->plainTextEdit->appendPlainText(strout);
+    mnIndex = 1;
+}
+
+
+void MainWindow::AddNewData(std::shared_ptr<iv::gps::gpsimu> xgpsimu_prt,const double fheadingdiff,
+                            const double fdis)
+{
+
+    double xoff = ui->lineEdit_xoff->text().toDouble();
+    double yoff = ui->lineEdit_yoff->text().toDouble();
+    double zoff = ui->lineEdit_zoff->text().toDouble();
+
+    double x_o,y_o;
+    GaussProjCal(xgpsimu_prt->lon(),xgpsimu_prt->lat(),&x_o,&y_o);
+    double lon,lat;
+    double hdg_o = (90 - xgpsimu_prt->heading())*M_PI/180.0;
+    double rel_x = xoff * cos(hdg_o) - yoff * sin(hdg_o);
+    double rel_y = xoff * sin(hdg_o) + yoff * cos(hdg_o);
+    GaussProjInvCal(x_o + rel_x,y_o + rel_y,&lon,&lat);
+    char strout[1000];
+    snprintf(strout,1000,"%d,%11.7f ,%11.7f ,%11.4f",mnIndex,
+             lat,lon,xgpsimu_prt->height() + zoff);
+    mFile.write(strout,strnlen(strout,1000));
+    mFile.write("\n",1);
+    ui->plainTextEdit->appendPlainText(strout);
+
+    mdistotal = mdistotal + fdis;
+    snprintf(strout,1000,"Index:%d Heading diff:%6.2f Distance:%6.2f Total DisTance:%6.2f",
+             mnIndex,fheadingdiff,fdis,mdistotal);
+    ui->statusbar->showMessage(strout);
+
+    mgpsimuold_ptr = xgpsimu_prt;
+    mnIndex++;
+}
+
+void MainWindow::onTimer()
+{
+    const double thresh_headingdiff = 1.0;
+    const double thresh_disdiff = 10.0;
+    std::shared_ptr<iv::gps::gpsimu> xgpsimu_ptr;
+    if(mbProc == false)return;
+    if(mbUpdate == false)
+    {
+        return;
+    }
+    else
+    {
+        mMutex.lock();
+        xgpsimu_ptr = mgpsimu_ptr;
+        mMutex.unlock();
+        mbUpdate = true;
+        ui->lineEdit_Lon->setText(QString::number(xgpsimu_ptr->lon(),'f',7));
+        ui->lineEdit_Lat->setText(QString::number(xgpsimu_ptr->lat(),'f',7));
+        ui->lineEdit_Heading->setText(QString::number(xgpsimu_ptr->heading(),'f',2));
+    }
+    if(mnIndex == 1)
+    {
+        AddNewData(xgpsimu_ptr);
+    }
+    else
+    {
+        double fheadingdiff = xgpsimu_ptr->heading() - mgpsimuold_ptr->heading();
+        if(fheadingdiff<0)fheadingdiff = fheadingdiff + 360.0;
+        if(fheadingdiff>= 360)fheadingdiff = fheadingdiff -360.0;
+
+        double x_old,y_old;
+        double x,y;
+        GaussProjCal(mgpsimuold_ptr->lon(),mgpsimuold_ptr->lat(),&x_old,&y_old);
+        GaussProjCal(xgpsimu_ptr->lon(),xgpsimu_ptr->lat(),&x,&y);
+        double fdis = sqrt(pow(x-x_old,2)+pow(y-y_old,2));
+
+
+        if((fheadingdiff>=thresh_headingdiff)&&(fheadingdiff<=(360.0 - thresh_headingdiff)))
+        {
+            AddNewData(xgpsimu_ptr,fheadingdiff,fdis);
+        }
+        else
+        {
+            if(fdis >= thresh_disdiff)
+            {
+                AddNewData(xgpsimu_ptr,fheadingdiff,fdis);
+            }
+        }
+
+    }
+}
+
+void MainWindow::UpdateGPS(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
+{
+    (void)index;
+    (void)dt;
+    (void)strmemname;
+
+    std::shared_ptr<iv::gps::gpsimu> xgpsimu_ptr = std::shared_ptr<iv::gps::gpsimu>(new iv::gps::gpsimu);
+
+    if(!xgpsimu_ptr->ParseFromArray(strdata,nSize))
+    {
+        qDebug("MainWindow::UpdateGPS Parse Error. nSize is ",nSize);
+        return;
+    }
+
+    mMutex.lock();
+    mgpsimu_ptr = xgpsimu_ptr;
+    mbUpdate = true;
+    mMutex.unlock();
+}
+
+void MainWindow::on_actionCompleteColllection_triggered()
+{
+    if(mbProc)
+    {
+        mbProc = false;
+        mFile.close();
+    }
+}

+ 56 - 0
src/tool/map_rtkdatafromveh/mainwindow.h

@@ -0,0 +1,56 @@
+#ifndef MAINWINDOW_H
+#define MAINWINDOW_H
+
+#include <QMainWindow>
+
+#include <QTimer>
+
+#include <memory>
+#include <QMutex>
+#include <QFile>
+
+#include "modulecomm.h"
+
+#include "gpsimu.pb.h"
+
+QT_BEGIN_NAMESPACE
+namespace Ui { class MainWindow; }
+QT_END_NAMESPACE
+
+class MainWindow : public QMainWindow
+{
+    Q_OBJECT
+
+public:
+    MainWindow(QWidget *parent = nullptr);
+    ~MainWindow();
+
+private slots:
+    void on_actionNewCollection_triggered();
+
+    void onTimer();
+
+    void on_actionCompleteColllection_triggered();
+
+private:
+    void UpdateGPS(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+
+    void AddNewData(std::shared_ptr<iv::gps::gpsimu> xgpsimu_prt,const double fheadingdiff = 0.0,
+                    const double fdis = 0.0);
+private:
+    Ui::MainWindow *ui;
+
+    bool mbProc = false;
+
+    std::shared_ptr<iv::gps::gpsimu> mgpsimu_ptr;
+    std::shared_ptr<iv::gps::gpsimu> mgpsimuold_ptr;
+    bool mbUpdate = false;
+    QMutex mMutex;
+
+    QFile mFile;
+    int mnIndex = 0;
+    double mdistotal = 0;
+
+    void * mpagpsmsg;
+};
+#endif // MAINWINDOW_H

+ 210 - 0
src/tool/map_rtkdatafromveh/mainwindow.ui

@@ -0,0 +1,210 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>MainWindow</class>
+ <widget class="QMainWindow" name="MainWindow">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>832</width>
+    <height>598</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>MainWindow</string>
+  </property>
+  <widget class="QWidget" name="centralwidget">
+   <widget class="QLineEdit" name="lineEdit_Lon">
+    <property name="geometry">
+     <rect>
+      <x>210</x>
+      <y>280</y>
+      <width>151</width>
+      <height>31</height>
+     </rect>
+    </property>
+    <property name="readOnly">
+     <bool>true</bool>
+    </property>
+   </widget>
+   <widget class="QLineEdit" name="lineEdit_Lat">
+    <property name="geometry">
+     <rect>
+      <x>210</x>
+      <y>347</y>
+      <width>151</width>
+      <height>31</height>
+     </rect>
+    </property>
+    <property name="readOnly">
+     <bool>true</bool>
+    </property>
+   </widget>
+   <widget class="QLineEdit" name="lineEdit_Heading">
+    <property name="geometry">
+     <rect>
+      <x>210</x>
+      <y>415</y>
+      <width>151</width>
+      <height>31</height>
+     </rect>
+    </property>
+    <property name="readOnly">
+     <bool>true</bool>
+    </property>
+   </widget>
+   <widget class="QPlainTextEdit" name="plainTextEdit">
+    <property name="geometry">
+     <rect>
+      <x>70</x>
+      <y>20</y>
+      <width>691</width>
+      <height>221</height>
+     </rect>
+    </property>
+    <property name="readOnly">
+     <bool>true</bool>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label">
+    <property name="geometry">
+     <rect>
+      <x>65</x>
+      <y>270</y>
+      <width>151</width>
+      <height>41</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>经度</string>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label_2">
+    <property name="geometry">
+     <rect>
+      <x>65</x>
+      <y>340</y>
+      <width>141</width>
+      <height>31</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>纬度</string>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label_3">
+    <property name="geometry">
+     <rect>
+      <x>65</x>
+      <y>410</y>
+      <width>151</width>
+      <height>30</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>航向</string>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label_4">
+    <property name="geometry">
+     <rect>
+      <x>490</x>
+      <y>270</y>
+      <width>131</width>
+      <height>40</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>向前偏移</string>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label_5">
+    <property name="geometry">
+     <rect>
+      <x>490</x>
+      <y>340</y>
+      <width>141</width>
+      <height>41</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>向左偏移</string>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label_6">
+    <property name="geometry">
+     <rect>
+      <x>490</x>
+      <y>410</y>
+      <width>121</width>
+      <height>31</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>向上偏移</string>
+    </property>
+   </widget>
+   <widget class="QLineEdit" name="lineEdit_xoff">
+    <property name="geometry">
+     <rect>
+      <x>650</x>
+      <y>280</y>
+      <width>111</width>
+      <height>30</height>
+     </rect>
+    </property>
+   </widget>
+   <widget class="QLineEdit" name="lineEdit_yoff">
+    <property name="geometry">
+     <rect>
+      <x>650</x>
+      <y>347</y>
+      <width>111</width>
+      <height>31</height>
+     </rect>
+    </property>
+   </widget>
+   <widget class="QLineEdit" name="lineEdit_zoff">
+    <property name="geometry">
+     <rect>
+      <x>650</x>
+      <y>410</y>
+      <width>111</width>
+      <height>31</height>
+     </rect>
+    </property>
+   </widget>
+  </widget>
+  <widget class="QMenuBar" name="menubar">
+   <property name="geometry">
+    <rect>
+     <x>0</x>
+     <y>0</y>
+     <width>832</width>
+     <height>28</height>
+    </rect>
+   </property>
+   <widget class="QMenu" name="menuFile">
+    <property name="title">
+     <string>File</string>
+    </property>
+    <addaction name="actionNewCollection"/>
+    <addaction name="actionCompleteColllection"/>
+   </widget>
+   <addaction name="menuFile"/>
+  </widget>
+  <widget class="QStatusBar" name="statusbar"/>
+  <action name="actionNewCollection">
+   <property name="text">
+    <string>NewCollection</string>
+   </property>
+  </action>
+  <action name="actionCompleteColllection">
+   <property name="text">
+    <string>CompleteColllection</string>
+   </property>
+  </action>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 48 - 0
src/tool/map_rtkdatafromveh/map_rtkdatafromveh.pro

@@ -0,0 +1,48 @@
+QT       += core gui
+
+greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
+
+CONFIG += c++11
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+    ../../include/msgtype/gps.pb.cc \
+    ../../include/msgtype/gpsimu.pb.cc \
+    ../../include/msgtype/imu.pb.cc \
+    gnss_coordinate_convert.cpp \
+    main.cpp \
+    mainwindow.cpp
+
+HEADERS += \
+    ../../include/msgtype/gps.pb.h \
+    ../../include/msgtype/gpsimu.pb.h \
+    ../../include/msgtype/imu.pb.h \
+    gnss_coordinate_convert.h \
+    mainwindow.h
+
+FORMS += \
+    mainwindow.ui
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}
+
+!include(../../../include/ivprotobuf.pri ) {
+    error( "Couldn't find the ivprotobuf.pri file!" )
+}