Explorar el Código

change map_collectfromveh,not complete.

yuchuli hace 2 años
padre
commit
6585221464

+ 599 - 14
src/tool/map_collectfromveh/editwin.cpp

@@ -5,6 +5,8 @@
 #define VIEW_HEIGHT 6000
 
 #include <iostream>
+#include <QMessageBox>
+#include <QInputDialog>
 
 #include "gnss_coordinate_convert.h"
 
@@ -29,7 +31,13 @@ EditWin::EditWin(QWidget *parent) :
 
     std::cout<<"init."<<std::endl;
 
+    ui->actionSelectNone->setChecked(true);
+    ui->actionSelectPoint->setChecked(false);
+    ui->actionSelectRoad->setChecked(false);
+
+
     setWindowTitle("Edit Collect Data");
+    std::cout<<"complete init."<<std::endl;
 
 }
 
@@ -44,23 +52,29 @@ void EditWin::showEvent(QShowEvent *event)
     std::cout<<"show"<<std::endl;
     ResetPointView();
     updateshow();
+
+    mbShow = true;
+    mbChangeData = false;
 }
 
 
 void EditWin::resizeEvent(QResizeEvent *event)
 {
-    std::cout<<"resize"<<std::endl;
+//    std::cout<<"resize"<<std::endl;
     (void)event;
     QSize sizemain = ui->centralwidget->size();
 
 //    ui->plainTextEdit->setGeometry(690,30,sizemain.width()-730,300);
-    myview->setGeometry(690,50,sizemain.width()-730,sizemain.height()-100);
+    int toolbarheight = ui->toolBar->height() + ui->menubar->height();
+    myview->setGeometry(5,toolbarheight+5,sizemain.width()-10,sizemain.height()-10);
 }
 
 void EditWin::closeEvent(QCloseEvent *event)
 {
-    std::cout<<"close. "<<std::endl;
+//    std::cout<<"close. "<<std::endl;
+    mbShow = false;
     (void)event;
+    emit editwinclose();
 }
 
 void EditWin::Setcollect(iv::map::collectveh &xcollect)
@@ -68,6 +82,11 @@ void EditWin::Setcollect(iv::map::collectveh &xcollect)
     mcollectveh.CopyFrom(xcollect);
 }
 
+void EditWin::Getcollect(iv::map::collectveh &xcollect)
+{
+    xcollect.CopyFrom(mcollectveh);
+}
+
 void EditWin::updateshow()
 {
     int i;
@@ -100,13 +119,13 @@ void EditWin::updateshow()
             pmainitem->setScale(fscale);
             mpscene->addItem(pmainitem);
             pleftitem = new QGraphicsEllipseItem(0-mfLeftRightSize/2.0,0*(-1)-mfLeftRightSize/2.0,mfLeftRightSize,mfLeftRightSize);
-            pleftitem->setBrush(Qt::darkGray);
+            pleftitem->setBrush(Qt::blue);
             pleftitem->setPen(Qt::NoPen);
             pleftitem->setPos(VIEW_WIDTH/2 + x_left,VIEW_HEIGHT/2 -y_left);
             pleftitem->setScale(fscale);
             mpscene->addItem(pleftitem);
             prightitem = new QGraphicsEllipseItem(0-mfLeftRightSize/2.0,0*(-1)-mfLeftRightSize/2.0,mfLeftRightSize,mfLeftRightSize);
-            prightitem->setBrush(Qt::darkGray);
+            prightitem->setBrush(Qt::cyan);
             prightitem->setPen(Qt::NoPen);
             prightitem->setPos(VIEW_WIDTH/2 + x_right,VIEW_HEIGHT/2 -y_right);
             prightitem->setScale(fscale);
@@ -151,6 +170,9 @@ void EditWin::ResetPointView()
         mpSelPointItem = NULL;
     }
 
+    mpselpoint = NULL;
+    mpselroad = NULL;
+
     mvectorSelMainPointItem.clear();
     mvectorLeftPointItem.clear();
     mvectorMainPointItem.clear();
@@ -160,6 +182,7 @@ void EditWin::ResetPointView()
 void EditWin::paintEvent(QPaintEvent * event)
 {
     (void)event;
+//    std::cout<<"paint "<<std::endl;
     static double foldratio = 1.0;
 
     double ratio = myview->getbeishu();
@@ -201,11 +224,17 @@ void EditWin::ondbclickxy(double x, double y)
     sel_x = x - VIEW_WIDTH/2;
     sel_y = (y - VIEW_HEIGHT/2)*(-1.0);
 
+    if(mnSelMode == 0)return;
+
+    QString strtoolshow = "";
+
     int i;
     int j;
-    double point_x,point_y;
+//    double point_x,point_y;
     iv::map::collectvehroadpoint * pnear = NULL;
+    iv::map::collectvehroad * pnearroad = NULL;
     double fdismin = 100000;
+    int nindex = 0;
     for(i=0;i<mcollectveh.mroads_size();i++)
     {
         iv::map::collectvehroad * proad = mcollectveh.mutable_mroads(i);
@@ -226,30 +255,586 @@ void EditWin::ondbclickxy(double x, double y)
                 if(fdismin < 10.0)
                 {
                     pnear = ppoint;
-                    point_x = rel_x;
-                    point_y = rel_y;
+                    pnearroad = proad;
+//                    point_x = rel_x;
+//                    point_y = rel_y;
+                    nindex = j;
                 }
             }
         }
     }
 
-    if(pnear != NULL)
+
+    if(mpSelPointItem != NULL )
+    {
+        mpscene->removeItem(mpSelPointItem);
+        delete mpSelPointItem;
+        mpSelPointItem = NULL;
+        mpselpoint = NULL;
+        mpselroad = NULL;
+
+    }
+    if(mvectorSelMainPointItem.size() > 0)
+    {
+        unsigned int i;
+        for(i=0;i<mvectorSelMainPointItem.size();i++)
+        {
+            mpscene->removeItem(mvectorSelMainPointItem[i]);
+            delete mvectorSelMainPointItem[i];
+        }
+        mvectorSelMainPointItem.clear();
+        mpselroad = NULL;
+    }
+
+    if(mnSelMode == 1)
+    {
+        if(pnear != NULL)
+        {
+            mpselpoint = pnear;
+            mpselroad = NULL;
+            mpselpointatroad = pnearroad;
+            mnSelPointIndex=nindex;
+            strtoolshow = updatetoolbarstr(pnear);
+        }
+    }
+
+    if(mnSelMode == 2)
     {
-        if(mpSelPointItem != NULL )
+
+        if(pnearroad != NULL)
+        {
+            mpselroad = pnearroad;
+        }
+    }
+
+    ui->statusbar->showMessage(strtoolshow);
+
+    updateselecshow();
+}
+
+void EditWin::on_actionMove_triggered()
+{
+    if(mpselpoint == NULL)
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("请先选择一个点")),QMessageBox::YesAll);
+        return;
+    }
+
+    bool ok;
+    QString text = QInputDialog::getText(this, tr("左移"),
+                                         tr("左移值:"), QLineEdit::Normal,
+                                         tr("0.0"), &ok);
+
+    if(ok == false)return;
+    if(text.isEmpty())
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        return;
+    }
+
+    double fMove = text.toDouble();
+
+    if(fMove == 0.0)return;
+
+    if(fMove > 10.0)
+    {
+        QString str = "移动值超过10米,移动值为: "+ QString::number(fMove) + QString(tr("米,是否进行平移?"));
+        QMessageBox::StandardButton button;
+        button=QMessageBox::question(this,tr("平移"),str,QMessageBox::Yes|QMessageBox::No);
+        if(button==QMessageBox::No)
         {
-            mpscene->removeItem(mpSelPointItem);
-            delete mpSelPointItem;
-            mpSelPointItem = NULL;
+            return;
         }
+    }
+
+    double x, y;
+    GaussProjCal(mpselpoint->mflon(),mpselpoint->mflat(),&x,&y);
+    double flon,flat;
+    double fhdg = (90 - mpselpoint->mfheading())*M_PI/180.0;
+    x = x + fMove*cos(fhdg + M_PI/2.0);
+    y = y + fMove*sin(fhdg + M_PI/2.0);
+    GaussProjInvCal(x,y,&flon,&flat);
+    mpselpoint->set_mflon(flon);
+    mpselpoint->set_mflat(flat);
+
+    iv::map::collectvehroadpoint * psel = mpselpoint;
+
+    ResetPointView();
+    updateshow();
+    mpselpoint = psel;
+    updateselecshow();
+
+    mbChangeData = true;
+}
+
+void EditWin::updateselecshow()
+{
+    if(mpselpoint != NULL)
+    {
+        iv::map::collectvehroadpoint * ppoint = mpselpoint;
+        double gpsx,gpsy;
+        double x0,y0;
+        GaussProjCal(mcollectveh.mlon0(),mcollectveh.mlat0(),&x0,&y0);
+        GaussProjCal(ppoint->mflon(),ppoint->mflat(),&gpsx,&gpsy);
+        double rel_x,rel_y;
+        rel_x = gpsx - x0;
+        rel_y = gpsy - y0;
 
         double ratio = myview->getbeishu();
         double fscale = 1.0/ratio;
         mpSelPointItem = new QGraphicsEllipseItem(0-mfSelSize/2.0,0*(-1)-mfSelSize/2.0,mfSelSize,mfSelSize);
         mpSelPointItem->setBrush(Qt::red);
         mpSelPointItem->setPen(Qt::NoPen);
-        mpSelPointItem->setPos(VIEW_WIDTH/2 + point_x,VIEW_HEIGHT/2 -point_y);
+        mpSelPointItem->setPos(VIEW_WIDTH/2 + rel_x,VIEW_HEIGHT/2 -rel_y);
         mpSelPointItem->setScale(fscale);
         mpscene->addItem(mpSelPointItem);
+    }
+
+    if(mpselroad != NULL)
+    {
+        int j;
+        for(j=0;j<mpselroad->mpoints_size();j++)
+        {
+            iv::map::collectvehroadpoint * ppoint = mpselroad->mutable_mpoints(j);
+            double gpsx,gpsy;
+            double x0,y0;
+            GaussProjCal(mcollectveh.mlon0(),mcollectveh.mlat0(),&x0,&y0);
+            GaussProjCal(ppoint->mflon(),ppoint->mflat(),&gpsx,&gpsy);
+            double rel_x,rel_y;
+            rel_x = gpsx - x0;
+            rel_y = gpsy - y0;
+            double ratio = myview->getbeishu();
+            double fscale = 1.0/ratio;
+            QGraphicsEllipseItem * pPointItem = new QGraphicsEllipseItem(0-mfSelSize/2.0,0*(-1)-mfSelSize/2.0,mfSelSize,mfSelSize);
+            pPointItem->setBrush(Qt::red);
+            pPointItem->setPen(Qt::NoPen);
+            pPointItem->setPos(VIEW_WIDTH/2 + rel_x,VIEW_HEIGHT/2 -rel_y);
+            pPointItem->setScale(fscale);
+            mpscene->addItem(pPointItem);
+            mvectorSelMainPointItem.push_back(pPointItem);
+
+        }
+    }
+}
+
+void EditWin::on_actionRotate_triggered()
+{
+    if(mpselpoint == NULL)
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("请先选择一个点")),QMessageBox::YesAll);
+        return;
+    }
 
+    bool ok;
+    QString text = QInputDialog::getText(this, tr("旋转"),
+                                         tr("旋转值=:"), QLineEdit::Normal,
+                                         tr("0.0"), &ok);
+
+    if(ok == false)return;
+    if(text.isEmpty())
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        return;
     }
+
+    double fRotate = text.toDouble();
+
+    if(fRotate == 0.0)return;
+
+    double fHeading = mpselpoint->mfheading();
+    fHeading = fHeading - fRotate;
+    while(fHeading >=360)fHeading = fHeading - 360.0;
+    while(fHeading<0)fHeading = fHeading + 360.0;
+    mpselpoint->set_mfheading(fHeading);
+
+    iv::map::collectvehroadpoint * psel = mpselpoint;
+
+    ResetPointView();
+    updateshow();
+    mpselpoint = psel;
+    updateselecshow();
+    mbChangeData = true;
+}
+
+void EditWin::on_actionMoveFront_triggered()
+{
+    if(mpselpoint == NULL)
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("请先选择一个点")),QMessageBox::YesAll);
+        return;
+    }
+
+    bool ok;
+    QString text = QInputDialog::getText(this, tr("前移"),
+                                         tr("前移值:"), QLineEdit::Normal,
+                                         tr("0.0"), &ok);
+
+    if(ok == false)return;
+    if(text.isEmpty())
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        return;
+    }
+
+    double fMove = text.toDouble();
+
+    if(fMove == 0.0)return;
+
+    if(fMove > 10.0)
+    {
+        QString str = "移动值超过10米,移动值为: "+ QString::number(fMove) + QString(tr("米,是否进行前移?"));
+        QMessageBox::StandardButton button;
+        button=QMessageBox::question(this,tr("前移"),str,QMessageBox::Yes|QMessageBox::No);
+        if(button==QMessageBox::No)
+        {
+            return;
+        }
+    }
+
+    double x, y;
+    GaussProjCal(mpselpoint->mflon(),mpselpoint->mflat(),&x,&y);
+    double flon,flat;
+    double fhdg = (90 - mpselpoint->mfheading())*M_PI/180.0;
+    x = x + fMove*cos(fhdg );
+    y = y + fMove*sin(fhdg );
+    GaussProjInvCal(x,y,&flon,&flat);
+    mpselpoint->set_mflon(flon);
+    mpselpoint->set_mflat(flat);
+
+    iv::map::collectvehroadpoint * psel = mpselpoint;
+
+    ResetPointView();
+    updateshow();
+    mpselpoint = psel;
+    updateselecshow();
+    mbChangeData = true;
+}
+
+void EditWin::on_actionDelete_triggered()
+{
+    if(mpselpoint == NULL)
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("请先选择一个点")),QMessageBox::YesAll);
+        return;
+    }
+
+    QMessageBox::StandardButton button;
+    button=QMessageBox::question(this,tr("删除"),QString(tr("确认删除点?")),QMessageBox::Yes|QMessageBox::No);
+    if(button==QMessageBox::No)
+    {
+        return;
+    }
+
+    mpselpointatroad->mutable_mpoints()->erase(mpselpointatroad->mutable_mpoints()->begin() + mnSelPointIndex);
+
+    mpselpoint = NULL;
+    mpselpointatroad = NULL;
+    ResetPointView();
+    updateshow();
+    updateselecshow();
+    mbChangeData = true;
+
+
+
+}
+
+void EditWin::on_actionSelectNone_triggered()
+{
+    ui->actionSelectPoint->setChecked(false);
+    ui->actionSelectRoad->setChecked(false);
+    ui->actionSelectNone->setChecked(true);
+    mnSelMode = 0;
+}
+
+void EditWin::on_actionSelectPoint_triggered()
+{
+    ui->actionSelectPoint->setChecked(true);
+    ui->actionSelectNone->setChecked(false);
+    ui->actionSelectRoad->setChecked(false);
+    mnSelMode = 1;
+}
+
+void EditWin::on_actionSelectRoad_triggered()
+{
+    ui->actionSelectRoad->setChecked(true);
+    ui->actionSelectNone->setChecked(false);
+    ui->actionSelectPoint->setChecked(false);
+    mnSelMode = 2;
+}
+
+QString  EditWin::updatetoolbarstr(iv::map::collectvehroadpoint *pnear)
+{
+    QString strtoolshow;
+    QString strleftlanecolor = "White";
+    switch (pnear->mlanecolor_left()) {
+    case iv::map::collectvehroadpoint::LaneColor::collectvehroadpoint_LaneColor_WHITE:
+        strleftlanecolor = "White";
+        break;
+    case iv::map::collectvehroadpoint::LaneColor::collectvehroadpoint_LaneColor_YELLOW:
+        strleftlanecolor = "Yellow";
+        break;
+    default:
+        strleftlanecolor = "Yellow";
+        break;
+    }
+    QString strrightlanecolor = "White";
+    switch (pnear->mlanecolor_right()) {
+    case iv::map::collectvehroadpoint::LaneColor::collectvehroadpoint_LaneColor_WHITE:
+        strrightlanecolor = "White";
+        break;
+    case iv::map::collectvehroadpoint::LaneColor::collectvehroadpoint_LaneColor_YELLOW:
+        strrightlanecolor = "Yellow";
+        break;
+    default:
+        strrightlanecolor = "Yellow";
+        break;
+    }
+
+    QString strlanetype_left = "NONE";
+    switch (pnear->mlanetype_left()) {
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_NONE:
+        strlanetype_left = "NONE";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_SOLID:
+        strlanetype_left = "SOLID";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_DASH:
+        strlanetype_left = "DASH";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_DASH_DASH:
+        strlanetype_left = "DASH DASH";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_SOLID_SOLID:
+        strlanetype_left = "SOLID SOLID";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_SOLID_DASH:
+        strlanetype_left = "SOLID DASH";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_DASH_SOLID:
+        strlanetype_left = "DASH SOLID";
+        break;
+    default:
+        strlanetype_left = "NONE";
+        break;
+    }
+    QString strlanetype_right = "NONE";
+    switch (pnear->mlanetype_right()) {
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_NONE:
+        strlanetype_right = "NONE";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_SOLID:
+        strlanetype_right = "SOLID";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_DASH:
+        strlanetype_right = "DASH";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_DASH_DASH:
+        strlanetype_right = "DASH DASH";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_SOLID_SOLID:
+        strlanetype_right = "SOLID SOLID";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_SOLID_DASH:
+        strlanetype_right = "SOLID DASH";
+        break;
+    case iv::map::collectvehroadpoint::LaneType::collectvehroadpoint_LaneType_DASH_SOLID:
+        strlanetype_right = "DASH SOLID";
+        break;
+    default:
+        strlanetype_right = "NONE";
+        break;
+    }
+    strtoolshow = "Lon: "+ QString::number(pnear->mflon(),'f',7)
+            +"   Lat:" + QString::number(pnear->mflat(),'f',7)
+            +"   Heading:" + QString::number(pnear->mfheading(),'f',2)
+            +"   Lane Width:" + QString::number(pnear->mflanewidth(),'f',2)
+            +"   Distance To Left:"+QString::number(pnear->mfdis_left(),'f',2)
+            +"   Left Lane Type:" + strlanetype_left
+            +"   Left Lane Color:" + strleftlanecolor
+            +"   Right Lane Type:" + strlanetype_right
+            +"   Right Lane Color:" + strrightlanecolor;
+
+
+    return strtoolshow;
+}
+
+void EditWin::on_actionRoadMoveLeft_triggered()
+{
+    if(mpselroad == NULL)
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("请先选择一条路")),QMessageBox::YesAll);
+        return;
+    }
+
+    bool ok;
+    QString text = QInputDialog::getText(this, tr("左移道路"),
+                                         tr("左移值:"), QLineEdit::Normal,
+                                         tr("0.0"), &ok);
+
+    if(ok == false)return;
+    if(text.isEmpty())
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        return;
+    }
+
+    double fMove = text.toDouble();
+
+    if(fMove == 0.0)return;
+
+    int i;
+    for(i=0;i<mpselroad->mpoints_size();i++)
+    {
+        iv::map::collectvehroadpoint * ppoint = mpselroad->mutable_mpoints(i);
+        double x, y;
+        GaussProjCal(ppoint->mflon(),ppoint->mflat(),&x,&y);
+        double flon,flat;
+        double fhdg = (90 - ppoint->mfheading())*M_PI/180.0;
+        x = x + fMove*cos(fhdg + M_PI/2.0);
+        y = y + fMove*sin(fhdg + M_PI/2.0);
+        GaussProjInvCal(x,y,&flon,&flat);
+        ppoint->set_mflon(flon);
+        ppoint->set_mflat(flat);
+    }
+
+    iv::map::collectvehroad * proadsel = mpselroad;
+    ResetPointView();
+    updateshow();
+    mpselroad = proadsel;
+    updateselecshow();
+    mbChangeData = true;
+}
+
+void EditWin::on_actionRoadMoveFront_triggered()
+{
+    if(mpselroad == NULL)
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("请先选择一条路")),QMessageBox::YesAll);
+        return;
+    }
+
+    bool ok;
+    QString text = QInputDialog::getText(this, tr("前移道路"),
+                                         tr("前移值:"), QLineEdit::Normal,
+                                         tr("0.0"), &ok);
+
+    if(ok == false)return;
+    if(text.isEmpty())
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        return;
+    }
+
+    double fMove = text.toDouble();
+
+    if(fMove == 0.0)return;
+
+    int i;
+    for(i=0;i<mpselroad->mpoints_size();i++)
+    {
+        iv::map::collectvehroadpoint * ppoint = mpselroad->mutable_mpoints(i);
+        double x, y;
+        GaussProjCal(ppoint->mflon(),ppoint->mflat(),&x,&y);
+        double flon,flat;
+        double fhdg = (90 - ppoint->mfheading())*M_PI/180.0;
+        x = x + fMove*cos(fhdg);
+        y = y + fMove*sin(fhdg );
+        GaussProjInvCal(x,y,&flon,&flat);
+        ppoint->set_mflon(flon);
+        ppoint->set_mflat(flat);
+    }
+
+    iv::map::collectvehroad * proadsel = mpselroad;
+    ResetPointView();
+    updateshow();
+    mpselroad = proadsel;
+    updateselecshow();
+    mbChangeData = true;
+}
+
+void EditWin::on_actionRoadRotate_triggered()
+{
+    if(mpselroad == NULL)
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("请先选择一条路")),QMessageBox::YesAll);
+        return;
+    }
+
+    bool ok;
+    QString text = QInputDialog::getText(this, tr("旋转道路上每一个点"),
+                                         tr("旋转值:"), QLineEdit::Normal,
+                                         tr("0.0"), &ok);
+
+    if(ok == false)return;
+    if(text.isEmpty())
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("数值为空")),QMessageBox::YesAll);
+        return;
+    }
+
+    double fRotate = text.toDouble();
+
+    if(fRotate == 0.0)return;
+
+    int i;
+    for(i=0;i<mpselroad->mpoints_size();i++)
+    {
+        iv::map::collectvehroadpoint * ppoint = mpselroad->mutable_mpoints(i);
+        double fHeading = ppoint->mfheading();
+        fHeading = fHeading - fRotate;
+        while(fHeading >= 360.0)fHeading = fHeading - 360.0;
+        while(fHeading < 0.0)fHeading = fHeading + 360.0;
+        ppoint->set_mfheading(fHeading);
+    }
+
+    iv::map::collectvehroad * proadsel = mpselroad;
+    ResetPointView();
+    updateshow();
+    mpselroad = proadsel;
+    updateselecshow();
+    mbChangeData = true;
+}
+
+void EditWin::on_actionRoadDelete_triggered()
+{
+    if(mpselroad == NULL)
+    {
+        QMessageBox::warning(this,"Waring",QString(tr("请先选择一条路")),QMessageBox::YesAll);
+        return;
+    }
+    QMessageBox::StandardButton button;
+    button=QMessageBox::question(this,tr("删除"),QString(tr("确认删除道路?")),QMessageBox::Yes|QMessageBox::No);
+    if(button==QMessageBox::No)
+    {
+        return;
+    }
+
+    int i;
+    for(i=0;i<mcollectveh.mroads_size();i++)
+    {
+        if(mcollectveh.mutable_mroads(i) == mpselroad)
+        {
+            mcollectveh.mutable_mroads()->erase(mcollectveh.mutable_mroads()->begin() + i);
+            break;
+        }
+    }
+    mpselroad = NULL;
+    ResetPointView();
+    updateshow();
+    mbChangeData = true;
+}
+
+void EditWin::on_actionRoadAdd_triggered()
+{
+
+}
+
+bool EditWin::IsChangeData()
+{
+    return mbChangeData;
+}
+
+bool EditWin::IsShow()
+{
+    return mbShow;
 }

+ 45 - 0
src/tool/map_collectfromveh/editwin.h

@@ -46,15 +46,60 @@ private slots:
     virtual void paintEvent(QPaintEvent *);
     void ondbclickxy(double x,double y);
 
+
+    void on_actionMove_triggered();
+
+    void on_actionRotate_triggered();
+
+    void on_actionMoveFront_triggered();
+
+    void on_actionDelete_triggered();
+
+    void on_actionSelectNone_triggered();
+
+    void on_actionSelectPoint_triggered();
+
+    void on_actionSelectRoad_triggered();
+
+    void on_actionRoadMoveLeft_triggered();
+
+    void on_actionRoadMoveFront_triggered();
+
+    void on_actionRoadRotate_triggered();
+
+    void on_actionRoadDelete_triggered();
+
+    void on_actionRoadAdd_triggered();
+
+signals:
+    void editwinclose();
+
 private:
     iv::map::collectveh mcollectveh;
 
+    iv::map::collectvehroadpoint * mpselpoint = NULL;
+    iv::map::collectvehroad * mpselroad = NULL;
+
+    iv::map::collectvehroad * mpselpointatroad = NULL;
+    int mnSelPointIndex = 0;
+
 public:
     void Setcollect(iv::map::collectveh & xcollect);
+    void Getcollect(iv::map::collectveh & xcollect);
+    bool IsChangeData();
+    bool IsShow();
 
 private:
     void updateshow();
     void ResetPointView();
+    void updateselecshow();
+    QString  updatetoolbarstr(iv::map::collectvehroadpoint * pnear);
+
+private:
+    int mnSelMode = 0; //0 none  1 point   2 road
+
+    bool mbShow = false;
+    bool mbChangeData = false;
 };
 
 #endif // EDITWIN_H

+ 16 - 0
src/tool/map_collectfromveh/editwin.qrc

@@ -0,0 +1,16 @@
+<RCC>
+    <qresource prefix="/">
+        <file>icon/批量平移.png</file>
+        <file>icon/平移.png</file>
+        <file>icon/删除.png</file>
+        <file>icon/添加.png</file>
+        <file>icon/旋转.png</file>
+        <file>icon/左移.png</file>
+        <file>icon/批量删除.png</file>
+        <file>icon/编辑数据.png</file>
+        <file>icon/数据采集.png</file>
+        <file>icon/道路.png</file>
+        <file>icon/点.png</file>
+        <file>icon/点击.png</file>
+    </qresource>
+</RCC>

+ 223 - 55
src/tool/map_collectfromveh/editwin.ui

@@ -13,60 +13,11 @@
   <property name="windowTitle">
    <string>MainWindow</string>
   </property>
-  <widget class="QWidget" name="centralwidget">
-   <widget class="QGroupBox" name="groupBox_SelectMode">
-    <property name="geometry">
-     <rect>
-      <x>20</x>
-      <y>20</y>
-      <width>301</width>
-      <height>111</height>
-     </rect>
-    </property>
-    <property name="title">
-     <string>选择模式</string>
-    </property>
-    <widget class="QRadioButton" name="radioButton_selectnone">
-     <property name="geometry">
-      <rect>
-       <x>10</x>
-       <y>52</y>
-       <width>71</width>
-       <height>31</height>
-      </rect>
-     </property>
-     <property name="text">
-      <string>无</string>
-     </property>
-    </widget>
-    <widget class="QRadioButton" name="radioButton_selectpoint">
-     <property name="geometry">
-      <rect>
-       <x>110</x>
-       <y>52</y>
-       <width>81</width>
-       <height>31</height>
-      </rect>
-     </property>
-     <property name="text">
-      <string>点</string>
-     </property>
-    </widget>
-    <widget class="QRadioButton" name="radioButton_selectroad">
-     <property name="geometry">
-      <rect>
-       <x>200</x>
-       <y>52</y>
-       <width>112</width>
-       <height>31</height>
-      </rect>
-     </property>
-     <property name="text">
-      <string>路</string>
-     </property>
-    </widget>
-   </widget>
-  </widget>
+  <property name="windowIcon">
+   <iconset resource="editwin.qrc">
+    <normaloff>:/icon/编辑数据.png</normaloff>:/icon/编辑数据.png</iconset>
+  </property>
+  <widget class="QWidget" name="centralwidget"/>
   <widget class="QMenuBar" name="menubar">
    <property name="geometry">
     <rect>
@@ -76,9 +27,226 @@
      <height>28</height>
     </rect>
    </property>
+   <widget class="QMenu" name="menuPoint">
+    <property name="title">
+     <string>Point</string>
+    </property>
+    <addaction name="actionMove"/>
+    <addaction name="actionMoveFront"/>
+    <addaction name="actionRotate"/>
+    <addaction name="actionDelete"/>
+   </widget>
+   <widget class="QMenu" name="menuRoad">
+    <property name="title">
+     <string>Road</string>
+    </property>
+    <addaction name="actionRoadMoveLeft"/>
+    <addaction name="actionRoadMoveFront"/>
+    <addaction name="actionRoadRotate"/>
+    <addaction name="actionRoadDelete"/>
+    <addaction name="actionRoadAdd"/>
+   </widget>
+   <widget class="QMenu" name="menuView">
+    <property name="title">
+     <string>View</string>
+    </property>
+    <widget class="QMenu" name="menuSelect">
+     <property name="title">
+      <string>Select</string>
+     </property>
+     <addaction name="actionSelectNone"/>
+     <addaction name="actionSelectPoint"/>
+     <addaction name="actionSelectRoad"/>
+    </widget>
+    <addaction name="menuSelect"/>
+   </widget>
+   <addaction name="menuPoint"/>
+   <addaction name="menuRoad"/>
+   <addaction name="menuView"/>
   </widget>
   <widget class="QStatusBar" name="statusbar"/>
+  <widget class="QToolBar" name="toolBar">
+   <property name="windowTitle">
+    <string>toolBar</string>
+   </property>
+   <attribute name="toolBarArea">
+    <enum>TopToolBarArea</enum>
+   </attribute>
+   <attribute name="toolBarBreak">
+    <bool>false</bool>
+   </attribute>
+   <addaction name="separator"/>
+   <addaction name="actionMove"/>
+   <addaction name="actionMoveFront"/>
+   <addaction name="actionRotate"/>
+   <addaction name="actionDelete"/>
+   <addaction name="separator"/>
+   <addaction name="actionRoadMoveLeft"/>
+   <addaction name="actionRoadMoveFront"/>
+   <addaction name="actionRoadRotate"/>
+   <addaction name="actionRoadDelete"/>
+   <addaction name="actionRoadAdd"/>
+   <addaction name="separator"/>
+   <addaction name="actionSelectNone"/>
+   <addaction name="actionSelectPoint"/>
+   <addaction name="actionSelectRoad"/>
+  </widget>
+  <action name="actionMove">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/左移.png</normaloff>:/icon/左移.png</iconset>
+   </property>
+   <property name="text">
+    <string>平移</string>
+   </property>
+   <property name="toolTip">
+    <string>左移一个点</string>
+   </property>
+  </action>
+  <action name="actionRotate">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/旋转.png</normaloff>:/icon/旋转.png</iconset>
+   </property>
+   <property name="text">
+    <string>旋转</string>
+   </property>
+   <property name="toolTip">
+    <string>旋转一个点</string>
+   </property>
+  </action>
+  <action name="actionDelete">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/删除.png</normaloff>:/icon/删除.png</iconset>
+   </property>
+   <property name="text">
+    <string>删除</string>
+   </property>
+   <property name="toolTip">
+    <string>删除一个点</string>
+   </property>
+  </action>
+  <action name="actionMoveFront">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/平移.png</normaloff>:/icon/平移.png</iconset>
+   </property>
+   <property name="text">
+    <string>前移</string>
+   </property>
+   <property name="toolTip">
+    <string>前移一个点</string>
+   </property>
+  </action>
+  <action name="actionRoadMoveLeft">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/左移.png</normaloff>:/icon/左移.png</iconset>
+   </property>
+   <property name="text">
+    <string>平移</string>
+   </property>
+   <property name="toolTip">
+    <string>所选道路的所有点向左平移</string>
+   </property>
+  </action>
+  <action name="actionRoadMoveFront">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/批量平移.png</normaloff>:/icon/批量平移.png</iconset>
+   </property>
+   <property name="text">
+    <string>前移</string>
+   </property>
+   <property name="toolTip">
+    <string>所选道路的所有点向前平移</string>
+   </property>
+  </action>
+  <action name="actionRoadRotate">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/旋转.png</normaloff>:/icon/旋转.png</iconset>
+   </property>
+   <property name="text">
+    <string>旋转</string>
+   </property>
+   <property name="toolTip">
+    <string>所选道路的所有点原地旋转</string>
+   </property>
+  </action>
+  <action name="actionRoadDelete">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/批量删除.png</normaloff>:/icon/批量删除.png</iconset>
+   </property>
+   <property name="text">
+    <string>删除</string>
+   </property>
+   <property name="toolTip">
+    <string>删除道路</string>
+   </property>
+  </action>
+  <action name="actionRoadAdd">
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/添加.png</normaloff>:/icon/添加.png</iconset>
+   </property>
+   <property name="text">
+    <string>添加</string>
+   </property>
+   <property name="toolTip">
+    <string>添加道路</string>
+   </property>
+  </action>
+  <action name="actionSelectNone">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/点击.png</normaloff>:/icon/点击.png</iconset>
+   </property>
+   <property name="text">
+    <string>SelectNone</string>
+   </property>
+   <property name="toolTip">
+    <string>不选择点或道路</string>
+   </property>
+  </action>
+  <action name="actionSelectPoint">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/点.png</normaloff>:/icon/点.png</iconset>
+   </property>
+   <property name="text">
+    <string>SelectPoint</string>
+   </property>
+   <property name="toolTip">
+    <string>选择点</string>
+   </property>
+  </action>
+  <action name="actionSelectRoad">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="icon">
+    <iconset resource="editwin.qrc">
+     <normaloff>:/icon/道路.png</normaloff>:/icon/道路.png</iconset>
+   </property>
+   <property name="text">
+    <string>SelectRoad</string>
+   </property>
+   <property name="toolTip">
+    <string>选择道路</string>
+   </property>
+  </action>
  </widget>
- <resources/>
+ <resources>
+  <include location="editwin.qrc"/>
+ </resources>
  <connections/>
 </ui>

BIN
src/tool/map_collectfromveh/icon/删除.png


BIN
src/tool/map_collectfromveh/icon/左移.png


BIN
src/tool/map_collectfromveh/icon/平移.png


BIN
src/tool/map_collectfromveh/icon/批量删除.png


BIN
src/tool/map_collectfromveh/icon/批量平移.png


BIN
src/tool/map_collectfromveh/icon/数据采集.png


BIN
src/tool/map_collectfromveh/icon/旋转.png


BIN
src/tool/map_collectfromveh/icon/添加.png


BIN
src/tool/map_collectfromveh/icon/点.png


BIN
src/tool/map_collectfromveh/icon/点击.png


BIN
src/tool/map_collectfromveh/icon/编辑数据.png


BIN
src/tool/map_collectfromveh/icon/道路.png


+ 21 - 0
src/tool/map_collectfromveh/mainwindow.cpp

@@ -101,6 +101,7 @@ MainWindow::MainWindow(QWidget *parent)
     mpEditWin = new EditWin(this);
 
     connect(this,SIGNAL(updategps()),this,SLOT(ongpsupdate()));
+    connect(mpEditWin,SIGNAL(editwinclose()),this,SLOT(onEditWinClose()));
 
     setWindowTitle("Collect Data From Vehicle");
 
@@ -144,6 +145,11 @@ void MainWindow::resizeEvent(QResizeEvent *event)
 
 void MainWindow::on_pushButton_NewRoad_clicked()
 {
+    if(mpEditWin->IsShow())
+    {
+        QMessageBox::warning(this,"Warning",QString(tr("编辑窗口打开状态,请先关闭编辑窗口")),QMessageBox::YesAll);
+        return;
+    }
     bool ok;
     QString text = QInputDialog::getText(this, tr("道路名称"),
                                          tr("道路名称:"), QLineEdit::Normal,
@@ -632,6 +638,11 @@ void MainWindow::on_pushButton_Complete_clicked()
 
 void MainWindow::on_actionEdit_Collect_triggered()
 {
+    if(mbStartCollect == true)
+    {
+        QMessageBox::warning(this,"Warning",QString(tr("采集数据在激活状态,请先完成采集")),QMessageBox::YesAll);
+        return;
+    }
     mpEditWin->Setcollect(mcollectveh);
     mpEditWin->show();
 }
@@ -695,3 +706,13 @@ void MainWindow::on_pushButton_ManualCollect_clicked()
 {
     mbManualClick = true;
 }
+
+void MainWindow::onEditWinClose()
+{
+    if(mpEditWin->IsChangeData())
+    {
+        mpEditWin->Getcollect(mcollectveh);
+        ResetPointView();
+        UpdateLoadVIew();
+    }
+}

+ 2 - 0
src/tool/map_collectfromveh/mainwindow.h

@@ -55,6 +55,8 @@ private slots:
 
     void on_pushButton_ManualCollect_clicked();
 
+    void onEditWinClose();
+
 public:
      void resizeEvent(QResizeEvent *event);
 

+ 7 - 1
src/tool/map_collectfromveh/mainwindow.ui

@@ -13,6 +13,10 @@
   <property name="windowTitle">
    <string>MainWindow</string>
   </property>
+  <property name="windowIcon">
+   <iconset resource="editwin.qrc">
+    <normaloff>:/icon/数据采集.png</normaloff>:/icon/数据采集.png</iconset>
+  </property>
   <widget class="QWidget" name="centralwidget">
    <widget class="QPushButton" name="pushButton_NewRoad">
     <property name="geometry">
@@ -364,6 +368,8 @@
    </property>
   </action>
  </widget>
- <resources/>
+ <resources>
+  <include location="editwin.qrc"/>
+ </resources>
  <connections/>
 </ui>

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

@@ -48,3 +48,8 @@ else: unix:!android: target.path = /opt/$${TARGET}/bin
 
 INCLUDEPATH += ../../common/common/math
 
+RESOURCES += \
+    editwin.qrc
+
+DISTFILES +=
+