Browse Source

add function that aavoid in road

liusunan 4 years ago
parent
commit
fe95b4fe25
66 changed files with 2437 additions and 1618 deletions
  1. 2 0
      src/decition/common/common/car_status.h
  2. 4 1
      src/decition/decition_brain/decition/adc_adapter/hapo_adapter.cpp
  3. 10 0
      src/decition/decition_brain/decition/adc_tools/compute_00.cpp
  4. 6 2
      src/decition/decition_brain/decition/brain.cpp
  5. 2 0
      src/decition/decition_brain/decition/brain.h
  6. 7 1
      src/decition/decition_brain/decition/decide_gps_00.cpp
  7. 9 9
      src/detection/detection_radar_delphi_esr_send/can_send_data_struct.h
  8. 60 22
      src/detection/detection_radar_delphi_esr_send/main.cpp
  9. 155 133
      src/driver/driver_cloud_grpc_client_stream/grpcclient.cpp
  10. 9 3
      src/driver/driver_cloud_grpc_client_stream/grpcclient.h
  11. 10 0
      src/driver/driver_cloud_grpc_client_stream/uploadstreammsg.proto
  12. 80 4
      src/driver/driver_cloud_grpc_pc_stream/grpcpc.cpp
  13. 17 1
      src/driver/driver_cloud_grpc_pc_stream/grpcpc.h
  14. 10 0
      src/driver/driver_cloud_grpc_pc_stream/uploadstreammsg.proto
  15. 13 2
      src/driver/driver_cloud_grpc_server_stream/cumsgbuffer.cpp
  16. 3 2
      src/driver/driver_cloud_grpc_server_stream/cumsgbuffer.h
  17. 126 9
      src/driver/driver_cloud_grpc_server_stream/main.cpp
  18. 4 2
      src/driver/driver_cloud_grpc_server_stream/pcmsgbuffer.cpp
  19. 3 2
      src/driver/driver_cloud_grpc_server_stream/pcmsgbuffer.h
  20. 10 0
      src/driver/driver_cloud_grpc_server_stream/uploadstreammsg.proto
  21. 15 0
      src/include/proto3/uploadstreammsg.proto
  22. 76 0
      src/tool/IVSysMan/main.cpp
  23. 4 1
      src/tool/IVSysMan/mainwindow.cpp
  24. 6 3
      src/tool/RemoteCtrl_Stream/RemoteCtrl_Stream.pro
  25. 27 0
      src/tool/RemoteCtrl_Stream/dialogsetframerate.cpp
  26. 27 0
      src/tool/RemoteCtrl_Stream/dialogsetframerate.h
  27. 78 0
      src/tool/RemoteCtrl_Stream/dialogsetframerate.ui
  28. 169 0
      src/tool/RemoteCtrl_Stream/mainwindow.cpp
  29. 21 0
      src/tool/RemoteCtrl_Stream/mainwindow.h
  30. 19 1
      src/tool/RemoteCtrl_Stream/mainwindow.ui
  31. 1 1
      src/tool/data_serials/mainwindow.cpp
  32. 158 0
      src/tool/map_lanetoxodr/ivxodrtool.cpp
  33. 24 0
      src/tool/map_lanetoxodr/ivxodrtool.h
  34. 12 0
      src/tool/map_lanetoxodr/mainwindow.cpp
  35. 5 0
      src/tool/map_lanetoxodr/mainwindow.h
  36. 27 0
      src/tool/map_lanetoxodr/mainwindow.ui
  37. 5 0
      src/tool/map_lanetoxodr/map_lanetoxodr.pro
  38. 345 0
      src/tool/map_lanetoxodr/roadeditdialog.cpp
  39. 50 0
      src/tool/map_lanetoxodr/roadeditdialog.h
  40. 226 0
      src/tool/map_lanetoxodr/roadeditdialog.ui
  41. 315 31
      src/ui/ui_ads_hmi/ADCIntelligentVehicle.cpp
  42. 24 8
      src/ui/ui_ads_hmi/ADCIntelligentVehicle.h
  43. 16 0
      src/ui/ui_ads_hmi/ADCIntelligentVehicle.qrc
  44. 220 28
      src/ui/ui_ads_hmi/ADCIntelligentVehicle.ui
  45. 12 0
      src/ui/ui_ads_hmi/common/car_status.h
  46. 0 1131
      src/ui/ui_ads_hmi/gps_collect.cpp
  47. 0 216
      src/ui/ui_ads_hmi/gps_collect.h
  48. BIN
      src/ui/ui_ads_hmi/light_image/diaotou-black.png
  49. BIN
      src/ui/ui_ads_hmi/light_image/diaotou-green.png
  50. BIN
      src/ui/ui_ads_hmi/light_image/diaotou-red.png
  51. BIN
      src/ui/ui_ads_hmi/light_image/diaotou-yellow.png
  52. BIN
      src/ui/ui_ads_hmi/light_image/youguai-black.png
  53. BIN
      src/ui/ui_ads_hmi/light_image/youguai-green.png
  54. BIN
      src/ui/ui_ads_hmi/light_image/youguai-red.png
  55. BIN
      src/ui/ui_ads_hmi/light_image/youguai-yellow.png
  56. BIN
      src/ui/ui_ads_hmi/light_image/zhixing-black.png
  57. BIN
      src/ui/ui_ads_hmi/light_image/zhixing-green.png
  58. BIN
      src/ui/ui_ads_hmi/light_image/zhixing-red.png
  59. BIN
      src/ui/ui_ads_hmi/light_image/zhixing-yellow.png
  60. BIN
      src/ui/ui_ads_hmi/light_image/zuoguai-black.png
  61. BIN
      src/ui/ui_ads_hmi/light_image/zuoguai-green.png
  62. BIN
      src/ui/ui_ads_hmi/light_image/zuoguai-red.png
  63. BIN
      src/ui/ui_ads_hmi/light_image/zuoguai-yellow.png
  64. 8 1
      src/ui/ui_ads_hmi/look.cpp
  65. 1 0
      src/ui/ui_ads_hmi/main.cpp
  66. 6 4
      src/ui/ui_ads_hmi/ui_ads_hmi.pro

+ 2 - 0
src/decition/common/common/car_status.h

@@ -144,6 +144,8 @@ namespace iv {
         boost::array<iv::ObstacleBasic, 64> obs_radar;//毫米波雷达的障碍物数据
          boost::array<iv::ObstacleBasic, 64> obs_rear_radar;//houxiang毫米波雷达的障碍物数据
         iv::ultrasonic_obs multrasonic_obs;
+        std::vector<iv::TracePoint> obsTraceLeft,obsTraceRight;
+
         double mfGPSAcc = 0;
 
 //        iv::brain::decitionview mdecitionview;

+ 4 - 1
src/decition/decition_brain/decition/adc_adapter/hapo_adapter.cpp

@@ -187,7 +187,7 @@ iv::decition::Decition iv::decition::HapoAdapter::getAdapterDeciton(GPS_INS now_
     controlSpeed = limitSpeed(realSpeed, controlBrake, dSpeed, controlSpeed);
 
    // (*decition)->brake = controlBrake*10;
-      (*decition)->brake = controlBrake*7;
+      (*decition)->brake = controlBrake*6;
 
     (*decition)->torque=controlSpeed;
       lastBrake= (*decition)->brake;
@@ -303,6 +303,9 @@ std::cout<<"========================================="<<std::endl;
    (*decition)->accelerator=  (*decition)->torque ;
 
 
+givlog->debug("obs_distance","dSpeed: %f, realSpeed: %f, brake: %f",
+              dSpeed, realSpeed,(*decition)->brake);
+
     return *decition;
 }
 

+ 10 - 0
src/decition/decition_brain/decition/adc_tools/compute_00.cpp

@@ -433,6 +433,8 @@ iv::Point2D iv::decition::Compute00::getLidarObsPoint(std::vector<Point2D> gpsTr
         xiuzheng=0-ServiceCarStatus.msysparam.lidarGpsXiuzheng;
     }
 
+    ServiceCarStatus.obsTraceLeft.clear();
+    ServiceCarStatus.obsTraceRight.clear();
 
     for (int j = 0; j < gpsTrace.size(); j++)
     {
@@ -467,6 +469,14 @@ iv::Point2D iv::decition::Compute00::getLidarObsPoint(std::vector<Point2D> gpsTr
         gpsTraceLeft.push_back(ptLeft);
         gpsTraceRight.push_back(ptRight);
 
+
+        TracePoint obsptleft(ptLeft.x,ptLeft.y);
+        ServiceCarStatus.obsTraceLeft.push_back(obsptleft);
+
+        TracePoint obsptright(ptRight.x,ptRight.y);
+        ServiceCarStatus.obsTraceLeft.push_back(obsptright);
+
+
     }
 
 

+ 6 - 2
src/decition/decition_brain/decition/brain.cpp

@@ -166,6 +166,8 @@ iv::decition::BrainDecition::BrainDecition()
     void * pa = iv::modulecomm::RegisterRecvPlus(gstrmemchassis.data(),funchassis);
 
     mpaPlanTrace = iv::modulecomm::RegisterSend("plantrace",100000,1);
+    mpaObsTraceLeft = iv::modulecomm::RegisterSend("obstraceleft",100000,1);
+    mpaObsTraceRight = iv::modulecomm::RegisterSend("obstraceright",100000,1);
 
     mTime.start();
     mnOldTime = mTime.elapsed();
@@ -639,12 +641,14 @@ void iv::decition::BrainDecition::run() {
             }
             iv::modulecomm::ModuleSendMsg(mpaPlanTrace,(char *)decitionGps00->planTrace.data(),decitionGps00->planTrace.size()*sizeof(iv::TracePoint));
 
-
-
+            iv::modulecomm::ModuleSendMsg(mpaObsTraceLeft,(char *)(ServiceCarStatus.obsTraceLeft.data()),ServiceCarStatus.obsTraceLeft.size()*sizeof(iv::TracePoint));
+            iv::modulecomm::ModuleSendMsg(mpaObsTraceRight,(char *)(ServiceCarStatus.obsTraceRight.data()),ServiceCarStatus.obsTraceRight.size()*sizeof(iv::TracePoint));
             //      decition_gps = decitionLine00->getDecideFromGPS(*gps_data_, navigation_data, obs_lidar_grid_);
             //ODS("\n决策:%f\t%f\t\t", decition_gps->speed, decition_gps->wheel_angle);
             //ODS("\n接收到的实时GPS数据:%f\t%f\t%f\n", gps_data_->gps_x, gps_data_->gps_y,gps_data_->ins_heading_angle);
 
+
+
             //carcall->is_arrived = decitionGps00->is_arrivaled;
             //double end = GetTickCount();
             decision_period = start - last;

+ 2 - 0
src/decition/decition_brain/decition/brain.h

@@ -127,6 +127,8 @@ namespace iv {
             void * mpaVechicleState;
             void * mpaToPlatform;
             void * mpaPlanTrace;
+            void * mpaObsTraceLeft;
+            void * mpaObsTraceRight;
 
 
             void ShareDecition(iv::decition::Decition decition);

+ 7 - 1
src/decition/decition_brain/decition/decide_gps_00.cpp

@@ -1979,6 +1979,12 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
 
     //   qDebug("decide1 time is %d",xTime.elapsed());
 
+    for(int i=0;i<ServiceCarStatus.obsTraceLeft.size();i++){
+        givlog->debug("obs_distance","obsTraceLeftX: %f, obsTraceLeftY: %f",
+                      ServiceCarStatus.obsTraceLeft.at(i).x, ServiceCarStatus.obsTraceLeft.at(i).y);
+    }
+
+
     return gps_decition;
 }
 
@@ -3686,7 +3692,7 @@ void iv::decition::DecideGps00::getEsrObsDistanceByFrenet(const std::vector<Poin
 void iv::decition::DecideGps00::getV2XTrafficPositionVector(const std::vector<GPSData> gpsMapLine){
     v2xTrafficVector.clear();
     for (int var = 0; var < gpsMapLine.size(); var++) {
-        if(gpsMapLine[var]->roadMode==6){
+        if(gpsMapLine[var]->roadMode==6 || gpsMapLine[var]->mode2==1000001){
             v2xTrafficVector.push_back(var);
         }
     }

+ 9 - 9
src/detection/detection_radar_delphi_esr_send/can_send_data_struct.h

@@ -53,13 +53,13 @@ struct canBit4F1
     //5
     unsigned char canLateralMountingOffset : 8;
     //6
-    unsigned char canMaximumTracks : 6; // <64
+    unsigned char canMaximumTracks : 6; //< max 64
     unsigned char canBlockageDisable : 1;
-    unsigned char canRadarCmdRadiate : 1; //<1
+    unsigned char canRadarCmdRadiate : 1; //< 1
     //7
     unsigned char canRawDataEnable : 1;
     unsigned char canWiperStatus : 1;
-    unsigned char canGroupingMode : 2;//<3
+    unsigned char canGroupingMode : 2;//< 3
     unsigned char canMmrUpsideDown : 1;
     unsigned char canVehicleSpeedValid : 1;
     unsigned char canTurnSignalStatus : 2;
@@ -73,25 +73,25 @@ union canSend4F1
 struct canBit5F2
 {
     //0
-    unsigned char canLatAccH : 5;
+    unsigned char canLatAccH : 6;
     unsigned char canLatAAccValid : 1;
     unsigned char canLonAccValid : 1;
     //1
-    unsigned char canLongAccH : 5;
+    unsigned char canLonAccH : 5;
     unsigned char canLatAccL : 3;
     //2
     unsigned char canRadarFovLrH : 4;
-    unsigned char canongAccL: 4;
+    unsigned char canLonAccL: 4;
     //3
     unsigned char canRadarFovMr : 7;
-    unsigned char canRadarFovLr : 1;
+    unsigned char canRadarFovLrL : 1;
     //4
     unsigned char canRadarHeight : 7;
     unsigned char canAutoAlignDisable : 1;
     //5
     unsigned char canWheelSlip : 2;
     unsigned char canAutoAlignConverged : 1;
-    unsigned char canAalignAvgCtrTotal : 3;
+    unsigned char canAalignAvgCtrTotal : 3; //< defalt 0x03
     unsigned char canServAlignEn : 1;
     unsigned char canServAlignType : 1;
     //6
@@ -110,7 +110,7 @@ struct canBit5F4
     //0
     unsigned char canOversteerUndersteer : 8;
     //1
-    unsigned char canBeamwidthVert : 7;
+    unsigned char canBeamwidthVert : 7; // default 0x71
     unsigned char canYawRateBiasShift : 1;
     //2
     unsigned char canFunnelOffsetLeft : 8;

+ 60 - 22
src/detection/detection_radar_delphi_esr_send/main.cpp

@@ -27,14 +27,18 @@
 
 std::string gstrmemgpsimu;
 std::string gstrmemcancar;
+
 static uint16_t CAN_Scan_Index;
 static double Vehicle_Yaw_Rate;
-
-static double Vehicle_Speed;        //<
-static uint8_t CAN_Vehicle_Speed_Valid; //<(1)valid
-
-static double Steering_Angle;
-static int16_t CAN_Radius_Curvature = 8191;
+static double Vehicle_Speed;        //< m/s
+static double Steering_Angle; //< optional signal, ready to use
+static int16_t Radius_Curvature = 8191; //< optional signal, 8191 meter is default
+static uint8_t Radar_FOV_Long_Range = 30; //< 0-30 degree
+static uint8_t Radar_FOV_Mid_Range = 120; //< 0-120 degree
+static uint8_t Radar_Height = 50;//< 0-125 cm
+static uint16_t Radar_to_Rear_Axle = 370;//< 0-710 cm
+static uint16_t Car_Wheel_Base = 270;//< 0-710 cm
+static uint8_t Car_Steering_Gear_Ratio = 18;//< 0-31.875
 /******************************************/
 
 canSend4F0 canData4f0;
@@ -56,18 +60,20 @@ QTime gTime;
 int gnRadarState = 0;
 
 #ifdef fujiankuan
-/****==================================================================================***/
+/***==================================================================================***/
 static int gnIndex = 0;
 
 //static unsigned char tmp1[8] = {0x00,0x00,0x00,0x00,0x00,0x00,0xBF,0x00};
 static unsigned char canbyte[8];
 
-void ExecSend1(uint16_t id, unsigned char canData[8],int size)
+void ExecSend(uint16_t id, unsigned char canData[8],int size)
 {
     iv::can::canmsg xmsg;
     iv::can::canraw xraw;
 
     memcpy(canbyte,canData,size);
+//    for(int i = 0 ; i< 8;i++)
+//        qDebug("%x",canbyte[i]);
 
     xraw.set_id(id);
     xraw.set_data(canbyte,8);
@@ -103,8 +109,8 @@ void Listengpsimu(const char * strdata,const unsigned int nSize,const unsigned i
         givlog->warn("detection_radar_delphi_esr_send--Listengpsimu parse errror. nSize is %d",nSize);
         return;
     }
-    Vehicle_Yaw_Rate = xgpsimu.gyro_z();
-    Vehicle_Speed = sqrt(pow(xgpsimu.vn(),2) + pow(xgpsimu.ve(),2));
+    Vehicle_Yaw_Rate = xgpsimu.gyro_z() * -1;
+    Vehicle_Speed = sqrt(xgpsimu.vn()*xgpsimu.vn() + xgpsimu.ve()*xgpsimu.ve() + xgpsimu.vd()*xgpsimu.vd());
 }
 
 void Listencancar(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
@@ -129,19 +135,52 @@ void signalHandler(int num)
 {
     unsigned int speed = (unsigned int)(Vehicle_Speed / 0.0625);
     int yawRate = (int)(Vehicle_Yaw_Rate / 0.0625);
+
     canData4f0.bit.canVehicleSpeedH = speed >> 8;
     canData4f0.bit.canVehicleSpeedL = speed & 0xFF;
+    if(Vehicle_Speed >= 0.0)
+        canData4f0.bit.can_VehicleSpeedDirection = 0x00;
+    else
+        canData4f0.bit.can_VehicleSpeedDirection = 0x01;
+
     canData4f0.bit.canYawRateH = yawRate >> 8;
     canData4f0.bit.canYawRateL = yawRate & 0xFF;
-    canData4f0.bit.canRadiusCurvatureH = CAN_Radius_Curvature >> 8;
-    canData4f0.bit.canRadiusCurvatureL = CAN_Radius_Curvature & 0x3F;
-    ExecSend1(0x4f0,canData4f0.byte,8);
+    canData4f0.bit.canYawRateValid = 0x01;
+qDebug("speed %x %f, yaw %x %f",speed,Vehicle_Speed,yawRate,Vehicle_Yaw_Rate);
+    canData4f0.bit.canRadiusCurvatureH = Radius_Curvature >> 8;
+    canData4f0.bit.canRadiusCurvatureL = Radius_Curvature & 0x3F;
+
+    ExecSend(0x4F0,canData4f0.byte,8);
 
     canData4f1.bit.canScanIndexAckH = CAN_Scan_Index >> 8;
     canData4f1.bit.canScanIndexAckL = CAN_Scan_Index & 0xFF;
-    ExecSend1(0x4f1,canData4f1.byte,8);
-    ExecSend1(0x5f2,canData5f2.byte,8);
-    ExecSend1(0x5f4,canData5f4.byte,8);
+
+    canData4f1.bit.canMaximumTracks = 0x3F;
+    canData4f1.bit.canRadarCmdRadiate = 0x01;
+
+    canData4f1.bit.canGroupingMode = 0x03;
+    canData4f1.bit.canVehicleSpeedValid = 0x01;
+
+    ExecSend(0x4F1,canData4f1.byte,8);
+
+    canData5f2.bit.canRadarFovLrH = Radar_FOV_Long_Range >> 1;
+    canData5f2.bit.canRadarFovLrL = Radar_FOV_Long_Range & 0x01;
+    canData5f2.bit.canRadarFovMr = Radar_FOV_Mid_Range & 0x7F;
+
+    canData5f2.bit.canRadarHeight = Radar_Height & 0x7F;
+
+    canData5f2.bit.canAalignAvgCtrTotal = 0x03;
+
+    ExecSend(0x5F2,canData5f2.byte,8);
+
+    canData5f4.bit.canBeamwidthVert = 0x47;
+    canData5f4.bit.canDistanceRearAxle = (uint8_t)((Radar_to_Rear_Axle - 200) / 2.0);
+//    qDebug()<<canData5f4.bit.canDistanceRearAxle;
+    canData5f4.bit.canWheelBase = (uint8_t)((Car_Wheel_Base - 200) / 2.0);
+    canData5f4.bit.canSteeringGearRatio = (uint8_t)(Car_Steering_Gear_Ratio / 0.125);
+
+
+    ExecSend(0x5F4,canData5f4.byte,8);
 }
 
 /*****************************************/
@@ -312,7 +351,7 @@ void DecodeRadar(iv::can::canmsg xmsg)
                     iv::radar::radarobject * pobj = gobj.mutable_obj(i + group_id * 7);
                     int8_t power = cdata[i+1] & 0x1F;
                     pobj->set_power(power - 10);
-                    qDebug()<<power;
+//                    qDebug()<<power;
                     pobj->set_moving((cdata[i+1] >> 5) & 0x01);
                     pobj->set_fast_movable((cdata[i+1] >> 7) & 0x01);
                     pobj->set_slow_movable((cdata[i+1] >> 6) & 0x01);
@@ -395,7 +434,6 @@ void DecodeRadar(iv::can::canmsg xmsg)
             gobj.set_mstime(QDateTime::currentMSecsSinceEpoch());
             ShareResult();
             gntemp = 0;
-
         }
 
         if(gntemp > 100)
@@ -423,7 +461,7 @@ void Listencan0(const char * strdata,const unsigned int nSize,const unsigned int
 
     DecodeRadar(xmsg);
 
-    qDebug("can size is %d",xmsg.rawmsg_size());
+//    qDebug("can size is %d",xmsg.rawmsg_size());
 //    xt = QDateTime::currentMSecsSinceEpoch();
 //    qDebug("latence = %ld ",xt-pic.time());
 
@@ -495,12 +533,12 @@ int main(int argc, char *argv[])
 
     iv::xmlparam::Xmlparam xp(strpath.toStdString());
 
-    std::string strmemcan = xp.GetParam("canrecv","canrecv0");
-    std::string strmemsend = xp.GetParam("cansend","cansend0");
+    std::string strmemcan = xp.GetParam("canrecv","canrecv1");
+    std::string strmemsend = xp.GetParam("cansend","cansend1");
     std::string strmemradar = xp.GetParam("radar","radar");
     std::string strmodulename = xp.GetParam("modulename","detection_radar_delphi_esr");
 #ifdef fujiankuan
-    gstrmemgpsimu = xp.GetParam("gpsimu_name","hcp_gpsimu");
+    gstrmemgpsimu = xp.GetParam("gpsimu_name","hcp2_gpsimu");
     gstrmemcancar = xp.GetParam("cancar","can_car");
 #endif
 

+ 155 - 133
src/driver/driver_cloud_grpc_client_stream/grpcclient.cpp

@@ -11,6 +11,7 @@ void ListenData(const char * strdata,const unsigned int nSize,const unsigned int
 
 grpcclient::grpcclient(std::string stryamlpath)
 {
+
     ggrpcclient = this;
     dec_yaml(stryamlpath.data());
 
@@ -27,14 +28,39 @@ grpcclient::grpcclient(std::string stryamlpath)
     }
 }
 
-void grpcclient::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::UploadRequestStream, iv::UploadReplyStream> > writer,bool * pbrun)
+qint64 grpcclient::calclatency(qint64 nnewlatency)
 {
+    mvectorlatency.push_back(nnewlatency);
+    while(mvectorlatency.size()>5)mvectorlatency.erase(mvectorlatency.begin());
+    qint64 nlatencytotal =0;
+    int nsize = mvectorlatency.size();
+    int i;
+    for(i=0;i<nsize;i++)
+    {
+        nlatencytotal = nlatencytotal + mvectorlatency.at(i);
+    }
+    if(nsize > 0)
+    {
+        nlatencytotal = nlatencytotal/nsize;
+    }
+    mnlatency = nlatencytotal;
+    return nlatencytotal;
+}
+
+void grpcclient::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::UploadRequestStream, iv::UploadReplyStream> > writer,std::shared_ptr<bool> pbrun,std::shared_ptr<qint64> nlastreftime)
+{
+    std::cout<<"threadsend start "<<std::endl;
     int nsize = mvectormsgunit.size();
     int i;
 
     int ninterval = atoi(gstruploadinterval.data());
     if(ninterval<=0)ninterval = 100;
 
+    mninterval = ninterval;
+    float ffraterate = 1.0f/((float)mninterval);
+    int nrawinterval = ninterval;
+    int nok = 0;
+
     QTime xTime;
     xTime.start();
     int nlastsend = xTime.elapsed();
@@ -44,7 +70,7 @@ void grpcclient::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::Uploa
     while(*pbrun)
     {
         std::this_thread::sleep_for(std::chrono::milliseconds(1));
-        if((xTime.elapsed()-nlastsend)<ninterval)
+        if((xTime.elapsed()-nlastsend)<mninterval)
         {
             continue;
         }
@@ -94,32 +120,101 @@ void grpcclient::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::Uploa
             request.set_xdata(strbuf,nbytesize);
             request.set_kepptime(nkeeptime);
             request.set_bimportant(bImportant);
+            request.set_nlatency(mnlatency);
+            ffraterate = 1000.0f/((float)mninterval);
+            request.set_fframerate(ffraterate);
+            request.set_nsendtime(time1);
             nid++;
 
             nlastsend = xTime.elapsed();
 
-            bool bsend = writer->Write(request);
-            std::cout<<"send msg. rtn is "<<bsend<<std::endl;
+            QTime xt;
+            xt.start();
+            ::grpc::WriteOptions wo;
+//            wo.set_write_through();
+//            wo.clear_buffer_hint();
+    //        writer->Write(request,(void * )2);
+
+    //        bool bsend = true;
+            bool bsend = writer->Write(request,wo);
+
+            *nlastreftime = QDateTime::currentMSecsSinceEpoch();
+
+//            if(xt.elapsed()>10)
+//            {
+//                nok = 0;
+//                if(ninterval < 1000)ninterval = ninterval * 11/10;
+//                mninterval = ninterval;
+//                ffraterate = 1.0f/((float)mninterval);
+//                qDebug("send ela is %d ninterval is %d",xt.elapsed(),ninterval);
+//            }
+//            else
+//            {
+//                nok++;
+//                if((ninterval > nrawinterval)&&(nok>10))
+//                {
+//                    nok = 0;
+
+//                    ninterval = ninterval*10/11;
+//                    mninterval = ninterval;
+//                    ffraterate = 1.0f/((float)mninterval);
+//                    std::cout<<"ninterval is "<<ninterval<<std::endl;
+//                }
+//            }
+            if(bsend == false)std::cout<<"send msg. rtn is "<<bsend<<std::endl;
 
 
         }
 
 
     }
+    std::cout<<"thread send end."<<std::endl;
 }
 
-void grpcclient::run()
+
+
+void grpcclient::threadrecv(std::shared_ptr<::grpc::ClientReaderWriter<iv::UploadRequestStream, iv::UploadReplyStream> > writer, std::shared_ptr<bool> pbrun,std::shared_ptr<qint64> nlastreftime)
 {
-    int nsize = mvectormsgunit.size();
-    int i;
+    std::cout<<"threadrecv start"<<std::endl;
+    iv::UploadReplyStream reply;
+    while (writer->Read(&reply)) {
+
+        *nlastreftime = QDateTime::currentMSecsSinceEpoch();
+        qint64 nlaten = QDateTime::currentMSecsSinceEpoch() - reply.nreqsendtime();
+        if(reply.nreqsendtime() == 0)nlaten = 0;
+        else
+        {
+            nlaten = nlaten - reply.npausetime();
+        }
+        calclatency(nlaten);
 
-    int ninterval = atoi(gstruploadinterval.data());
-    if(ninterval<=0)ninterval = 100;
+        if(reply.framerate() >0.001)
+        {
+            mninterval = 1000.0/reply.framerate();
+        }
 
-    QTime xTime;
-    xTime.start();
-    int nlastsend = xTime.elapsed();
+        qDebug("latency is %ld",nlaten);
+//        nfail = 0;
+//        std::cout << "接收到回复:" << reply.remsg()<<"--\n" << std::endl;
+        if(reply.nres() == 1)
+        {
+            iv::cloud::cloudmsg xmsg;
+            if(xmsg.ParseFromArray(reply.xdata().data(),reply.xdata().size()))
+            {
+                sharectrlmsg(&xmsg);
+            }
+        }
+
+//            std::cout<<"read data from server."<<std::endl;
+    }
+    std::cout<<"threadrecv end."<<std::endl;
+    *pbrun = false;
+}
 
+
+void grpcclient::threadRPC(std::shared_ptr<qint64> pnrpctime,std::shared_ptr<bool> pbRun)
+{
+    std::cout<<"threadrpc start."<<std::endl;
     std::string target_str = gstrserverip+":";
     target_str = target_str + gstrserverport ;//std::to_string()
     auto cargs = grpc::ChannelArguments();
@@ -132,151 +227,78 @@ void grpcclient::run()
     std::unique_ptr<iv::UploadStream::Stub> stub_ = iv::UploadStream::NewStub(channel);
 
 
-    iv::UploadRequestStream request;
-
     int nfail = 0;
 
     while(!QThread::isInterruptionRequested())
     {
         ClientContext context ;
+//        std::shared_ptr<ClientContext> pcontext(new ClientContext);
+        std::shared_ptr<::grpc::ClientReaderWriter<iv::UploadRequestStream, iv::UploadReplyStream> > writerRead(stub_->upload(&context));
 
 
+//        std::shared_ptr<bool> pbRun(new bool);
+        *pbRun = true;
+        std::shared_ptr<qint64> pntime = pnrpctime ;
+        *pntime = QDateTime::currentMSecsSinceEpoch();
+        std::thread * pthread = new std::thread(&grpcclient::threadsend,this,writerRead,pbRun,pntime);
+        (void )pthread;
+        std::thread * precvthread = new std::thread(&grpcclient::threadrecv,this,writerRead,pbRun,pntime);
+        (void)precvthread;
 
+        pthread->join();
+        precvthread->join();
 
-        std::shared_ptr<::grpc::ClientReaderWriter<iv::UploadRequestStream, iv::UploadReplyStream> > writerRead(stub_->upload(&context));
+ //       std::cout<<"threadRPC end"<<std::endl;
+ //       *pbRun = false;
 
-        bool bRun = true;
-        std::thread * pthread = new std::thread(&grpcclient::threadsend,this,writerRead,&bRun);
-        (void )pthread;
-        iv::UploadReplyStream reply;
-        while (writerRead->Read(&reply)) {
-            nfail = 0;
-    //        std::cout << "接收到回复:" << reply.remsg()<<"--\n" << std::endl;
-            if(reply.nres() == 1)
-            {
-                iv::cloud::cloudmsg xmsg;
-                if(xmsg.ParseFromArray(reply.xdata().data(),reply.xdata().size()))
-                {
-                    sharectrlmsg(&xmsg);
-                }
-            }
-            std::cout<<"read data from server."<<std::endl;
-        }
-        bRun = false;
-        pthread->join();
-        nfail++;
-        if(nfail > 100)std::this_thread::sleep_for(std::chrono::milliseconds(3000));
-        else std::this_thread::sleep_for(std::chrono::milliseconds(100));
-        std::cout<<"reconnnect to server. nfail is "<<nfail<<std::endl;
-    }
+//        while(((QDateTime::currentMSecsSinceEpoch() - *pntime)<3000)&&(*pbRun))
+//        {
+//            std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+//        }
 
-    int nid = 0;
+//        *pbRun = false;
 
-    // Container for the data we expect from the server.
-//    iv::UploadReply reply;
 
-    gpr_timespec timespec;
-      timespec.tv_sec = 30;//设置阻塞时间为2秒
-      timespec.tv_nsec = 0;
-      timespec.clock_type = GPR_TIMESPAN;
 
- //   ClientContext context;
+        std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+
+        channel = grpc::CreateCustomChannel(
+                 target_str, grpc::InsecureChannelCredentials(),cargs);
+        stub_ = iv::UploadStream::NewStub(channel);
+        nfail++;
+//        if(nfail > 100)std::this_thread::sleep_for(std::chrono::milliseconds(3000));
+//        else std::this_thread::sleep_for(std::chrono::milliseconds(100));
+        std::cout<<"reconnnect to server. nfail is "<<nfail<<std::endl;
+    }
+}
 
+void grpcclient::run()
+{
+            std::shared_ptr<bool> pbRun(new bool);
+            *pbRun = true;
+                    std::shared_ptr<qint64> pntime(new qint64);
+                    *pntime = QDateTime::currentMSecsSinceEpoch();
 
+    std::thread * pthread = new std::thread(&grpcclient::threadRPC,this,pntime,pbRun);
+    return;
 
 //    while(!QThread::isInterruptionRequested())
 //    {
-//        std::this_thread::sleep_for(std::chrono::milliseconds(1));
-//        if((xTime.elapsed()-nlastsend)<ninterval)
+//        std::shared_ptr<bool> pbRun(new bool);
+//        *pbRun = true;
+//        std::shared_ptr<qint64> pntime(new qint64);
+//        *pntime = QDateTime::currentMSecsSinceEpoch();
+//        std::thread * pthread = new std::thread(&grpcclient::threadRPC,this,pntime,pbRun);
+//        (void )pthread;
+//        while(((QDateTime::currentMSecsSinceEpoch() - *pntime)<10000)&&(*pbRun))
 //        {
-//            continue;
+//            std::this_thread::sleep_for(std::chrono::milliseconds(1000));
 //        }
-
-//            bool bImportant = false;
-//            int nkeeptime = 0;
-//            iv::cloud::cloudmsg xmsg;
-//            xmsg.set_xtime(QDateTime::currentMSecsSinceEpoch());
-//            gMutexMsg.lock();
-//            for(i=0;i<nsize;i++)
-//            {
-//                if(mvectormsgunit[i].mbRefresh)
-//                {
-//                    mvectormsgunit[i].mbRefresh = false;
-//                    if(mvectormsgunit[i].mbImportant)
-//                    {
-//                        bImportant = true;
-//                    }
-//                    if(mvectormsgunit[i].mnkeeptime > nkeeptime)
-//                    {
-//                        nkeeptime = mvectormsgunit[i].mnkeeptime;
-//                    }
-//                    iv::cloud::cloudunit xcloudunit;
-//                    xcloudunit.set_msgname(mvectormsgunit[i].mstrmsgname);
-//                    xcloudunit.set_data(mvectormsgunit[i].mpstrmsgdata.get(),mvectormsgunit[i].mndatasize);
-//                    iv::cloud::cloudunit * pcu = xmsg.add_xclouddata();
-//                    pcu->CopyFrom(xcloudunit);
-//                }
-
-//            }
-//            gMutexMsg.unlock();
-
-//            int nbytesize = xmsg.ByteSize();
-//            char * strbuf = new char[nbytesize];
-//            std::shared_ptr<char> pstrbuf;
-//            pstrbuf.reset(strbuf);
-//            if(xmsg.SerializeToArray(strbuf,nbytesize))
-//            {
-
-//                ClientContext context ;
-//                context.set_deadline(timespec);
-//                qint64 time1 = QDateTime::currentMSecsSinceEpoch();
-
-//                request.set_id(nid);
-//                request.set_ntime(time1);
-//                request.set_strquerymd5(gstrqueryMD5);
-//                request.set_strctrlmd5(gstrctrlMD5);
-//                request.set_strvin(gstrVIN);
-//                request.set_xdata(strbuf,nbytesize);
-//                request.set_kepptime(nkeeptime);
-//                request.set_bimportant(bImportant);
-//                nid++;
-
-//                nlastsend = xTime.elapsed();
-//                // The actual RPC.
-//                Status status = stub_->upload(&context, request, &reply);
-//                if (status.ok()) {
-//                    std::cout<<"  data size is "<<nbytesize<<std::endl;
-//                    std::cout<<nid<<" upload successfully"<<std::endl;
-//                    if(reply.nres() == 1)
-//                    {
-//                        iv::cloud::cloudmsg xmsg;
-//                        if(xmsg.ParseFromArray(reply.xdata().data(),reply.xdata().size()))
-//                        {
-//                            sharectrlmsg(&xmsg);
-//                        }
-//                    }
-//                } else {
-//                  std::cout << status.error_code() << ": " << status.error_message()
-//                            << std::endl;
-//                  std::cout<<"RPC failed"<<std::endl;
-//                  if(status.error_code() == 4)
-//                  {
-//                      std::cout<<" RPC Exceed Time, Create New stub_"<<std::endl;
-//                      channel = grpc::CreateCustomChannel(
-//                               target_str, grpc::InsecureChannelCredentials(),cargs);
-
-//                      stub_ = iv::Upload::NewStub(channel);
-//                  }
-//                  std::this_thread::sleep_for(std::chrono::milliseconds(900));
-
-//                }
-
-//            }
-
+//        std::cout<<" reconect."<<std::endl;
+//        *pbRun = false;
 
 //    }
 
-
 }
 
 

+ 9 - 3
src/driver/driver_cloud_grpc_client_stream/grpcclient.h

@@ -64,8 +64,6 @@ private:
     std::thread * guploadthread;
 
 
-
-
     std::vector<iv::msgunit> mvectormsgunit;
 
     std::vector<iv::msgunit> mvectorctrlmsgunit;
@@ -78,6 +76,10 @@ private:
 
 
     int gindex = 0;
+
+    int mninterval = 100;
+    int mnlatency = 0;
+    std::vector<qint64> mvectorlatency;
 public:
     void UpdateData(const char * strdata,const unsigned int nSize,const char * strmemname);
 private:
@@ -85,7 +87,11 @@ private:
     void dec_yaml(const char * stryamlpath);
     void sharectrlmsg(iv::cloud::cloudmsg * pxmsg);
 
-    void threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::UploadRequestStream, iv::UploadReplyStream> > writer,bool * pbrun);
+    void threadRPC(std::shared_ptr<qint64> pnrpctime,std::shared_ptr<bool> pbRun);
+
+    void threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::UploadRequestStream, iv::UploadReplyStream> > writer,std::shared_ptr<bool> pbrun,std::shared_ptr<qint64> nlastreftime);
+    void threadrecv(std::shared_ptr<::grpc::ClientReaderWriter<iv::UploadRequestStream, iv::UploadReplyStream> > writer,std::shared_ptr<bool> pbrun,std::shared_ptr<qint64> nlastreftime);
+    qint64 calclatency(qint64 nnewlatency);
 };
 
 #endif // GRPCCLIENT_H

+ 10 - 0
src/driver/driver_cloud_grpc_client_stream/uploadstreammsg.proto

@@ -42,12 +42,19 @@ message UploadRequestStream {
     bytes xdata = 6;
     bool bimportant = 7;  //if 1, is important.
     int32 kepptime = 8;   //If important keep this data before query ms.
+    float fFrameRate = 9;
+    int64 nSendTime = 10;
+    int64 nLatency = 11;
 }
 
 // The response message containing the greetings
 message UploadReplyStream {
   int32 nres = 1;  //0 no message 1 have ctrl message
   bytes xdata = 2;
+  int32 nreqid = 3;  
+  int64 nreqSendTime = 4;  //id and SendTime used for calculate latency. 
+  float framerate = 5;
+  int64 npausetime = 6;  //upload message in server pause time, calculate latency need substract this value.
 //  string message = 1;
 }
 
@@ -61,6 +68,7 @@ message queryReqStream {
   bool bimportant = 6;  //if 1, is important.
   int32 kepptime = 7;   //If important keep this data before ctrl ms.  if -1 must send.
   int32 ntype = 8;  //0 only query  1 ctrl.
+  float nSuggestFrameRate = 9;
 }
 
 message queryReplyStream {
@@ -68,6 +76,8 @@ message queryReplyStream {
     int32 id = 2;
     int64 ntime = 3;
     bytes xdata = 4;
+    int64 nculatency = 5;
+    float ncuFrameRage = 6;
 }
 
 

+ 80 - 4
src/driver/driver_cloud_grpc_pc_stream/grpcpc.cpp

@@ -26,13 +26,20 @@ grpcpc::grpcpc(std::string stryamlpath)
 }
 
 
-void grpcpc::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::queryReqStream, iv::queryReplyStream> > writer, bool *pbrun)
+void grpcpc::setframerate(float framerate)
+{
+    mframerate = framerate;
+}
+
+void grpcpc::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::queryReqStream, iv::queryReplyStream> > writer, bool *pbrun,
+                        int * pnsendid,qint64 * pnreplysendtime,qint64 * pnreceivetime,QMutex * pmutexrecive)
 {
     int nctrlsize = mvectorctrlmsgunit.size();
     int i;
 
     int ninterval = atoi(gstruploadinterval.data());
     if(ninterval<=0)ninterval = 100;
+    mninterval = ninterval;
 
     QTime xTime;
     xTime.start();
@@ -45,7 +52,7 @@ void grpcpc::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::queryReqS
     while(*pbrun)
     {
         std::this_thread::sleep_for(std::chrono::milliseconds(1));
-        if((xTime.elapsed()-nlastsend)<ninterval)
+        if((xTime.elapsed()-nlastsend)<mninterval)
         {
             continue;
         }
@@ -87,9 +94,14 @@ void grpcpc::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::queryReqS
 
             request.set_strquerymd5(gstrqueryMD5);
             request.set_strvin(gstrVIN);
+
 //            request.set_ntime(QDateTime::currentMSecsSinceEpoch());
             request.set_ntype(0);
 
+            request.set_nreplyid(0);
+            request.set_nreplysendtime(0);
+            request.set_npausetime(0);
+
             if(xmsg.xclouddata_size()>0)
             {
                 int nbytesize = xmsg.ByteSize();
@@ -97,10 +109,15 @@ void grpcpc::threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::queryReqS
                 pvectordata.resize(nbytesize);
                 if(xmsg.SerializeToArray(pvectordata.data(),nbytesize))
                 {
+                    pmutexrecive->lock();
+                    request.set_nreplyid(*pnsendid);
+                    request.set_nreplysendtime(*pnreplysendtime);
+                    request.set_npausetime(QDateTime::currentMSecsSinceEpoch() - *pnreceivetime);
+                    pmutexrecive->unlock();
 
 //                    request.set_id(nctrlid);nctrlid++;
                     request.set_strctrlmd5(gstrctrlMD5);
-
+                    request.set_nsuggestframerate(mframerate);
                     request.set_xdata(pvectordata.data(),pvectordata.size());
                     request.set_bimportant(bImportant);
                     request.set_kepptime(nkeeptime);
@@ -125,6 +142,7 @@ void grpcpc::run()
 
     int ninterval = atoi(gstruploadinterval.data());
     if(ninterval<=0)ninterval = 100;
+    mninterval = ninterval;
 
     QTime xTime;
     xTime.start();
@@ -144,6 +162,11 @@ void grpcpc::run()
 
     int nfail = 0;
 
+    int nreplyid;
+    qint64 nreplysendtime;
+    qint64 nreceivetime;
+    QMutex mutexlatency;
+
     while(!QThread::isInterruptionRequested())
     {
         ClientContext context ;
@@ -151,7 +174,8 @@ void grpcpc::run()
         std::shared_ptr<::grpc::ClientReaderWriter<iv::queryReqStream, iv::queryReplyStream> > writerRead(stub_->queryctrl(&context));
 
         bool bRun = true;
-        std::thread * pthread = new std::thread(&grpcpc::threadsend,this,writerRead,&bRun);
+        std::thread * pthread = new std::thread(&grpcpc::threadsend,this,writerRead,&bRun,
+                                                &nreplyid,&nreplysendtime,&nreceivetime,&mutexlatency);
         (void )pthread;
         iv::queryReplyStream reply;
         while (writerRead->Read(&reply)) {
@@ -159,6 +183,15 @@ void grpcpc::run()
     //        std::cout << "接收到回复:" << reply.remsg()<<"--\n" << std::endl;
             if(reply.nres() == 1)
             {
+                mnstate = 1;
+                mnlastpack = QDateTime::currentMSecsSinceEpoch();
+                mutexlatency.lock();
+                nreplyid = reply.id();
+                nreplysendtime = reply.nsendtime();
+                nreceivetime = QDateTime::currentMSecsSinceEpoch();
+                mutexlatency.unlock();
+                mnserverlatency = reply.nserverlatency();
+                mnculatency = reply.nculatency();
                 std::cout<<"data size is "<<reply.xdata().size()<<"time is"<<QDateTime::currentMSecsSinceEpoch()<<std::endl;
                 iv::cloud::cloudmsg xmsg;
                 if(xmsg.ParseFromArray(reply.xdata().data(),reply.xdata().size()))
@@ -166,11 +199,17 @@ void grpcpc::run()
                     sharequerymsg(&xmsg);
                 }
             }
+            else
+            {
+                if(mnlastpack == 0)
+                    mnstate = reply.nres();
+            }
             std::cout<<"read data from server. nres :"<< reply.nres()<<std::endl;
         }
         bRun = false;
         pthread->join();
         nfail++;
+        mnstate = -100;
         if(nfail > 100)std::this_thread::sleep_for(std::chrono::milliseconds(3000));
         else std::this_thread::sleep_for(std::chrono::milliseconds(100));
         std::cout<<"reconnnect to server. nfail is "<<nfail<<std::endl;
@@ -338,3 +377,40 @@ std::string grpcpc::GetVIN()
 {
     return gstrVIN;
 }
+
+float grpcpc::getframerate()
+{
+    return mframerate;
+}
+
+void grpcpc::setctrlfps(float framerate)
+{
+    if(framerate > 0.01)
+    {
+        mninterval =(int)( 1000.0/framerate);
+    }
+}
+
+float grpcpc::getctrlfps()
+{
+    return 1000.0/mninterval;
+}
+
+qint64 grpcpc::getculatency()
+{
+    return mnculatency;
+}
+
+qint64 grpcpc::getserverlatency()
+{
+    return mnserverlatency;
+}
+
+int grpcpc::getstate()
+{
+    if(mnstate == 1)
+    {
+        if((QDateTime::currentMSecsSinceEpoch() - mnlastpack) > 3000)mnstate = 0;
+    }
+    return mnstate;
+}

+ 17 - 1
src/driver/driver_cloud_grpc_pc_stream/grpcpc.h

@@ -73,10 +73,17 @@ private:
     std::string gstrctrlMD5 = "5d41402abc4b2a76b9719d911017c592";
 
 
+    float mframerate = 0.0;
+    int mninterval = 100;
 
+    qint64 mnculatency = 0;
+    qint64 mnserverlatency = 0;
 
     int gindex = 0;
 
+    int mnstate = -100;  // -1 no this vin -2 pass error   0 offline 1 online
+    qint64 mnlastpack = 0;
+
 
 private:
     void dec_yaml(const char * stryamlpath);
@@ -85,7 +92,16 @@ private:
 public:
     void UpdateData(const char * strdata,const unsigned int nSize,const char * strmemname);
     std::string GetVIN();
-    void threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::queryReqStream, iv::queryReplyStream> > writer,bool * pbrun);
+    void threadsend(std::shared_ptr<::grpc::ClientReaderWriter<iv::queryReqStream, iv::queryReplyStream> > writer,bool * pbrun,
+                    int * pnsendid,qint64 * pnreplysendtime,qint64 * pnreceivetime,QMutex * pmutexrecive);
+
+    void setframerate(float framerate);
+    float getframerate();
+    void setctrlfps(float framerate);
+    float getctrlfps();
+    qint64 getculatency();
+    qint64 getserverlatency();
+    int getstate();
 
 
 };

+ 10 - 0
src/driver/driver_cloud_grpc_pc_stream/uploadstreammsg.proto

@@ -42,12 +42,19 @@ message UploadRequestStream {
     bytes xdata = 6;
     bool bimportant = 7;  //if 1, is important.
     int32 kepptime = 8;   //If important keep this data before query ms.
+    float fFrameRate = 9;
+    int64 nSendTime = 10;
+    int64 nLatency = 11;
 }
 
 // The response message containing the greetings
 message UploadReplyStream {
   int32 nres = 1;  //0 no message 1 have ctrl message
   bytes xdata = 2;
+  int32 nreqid = 3;  
+  int64 nreqSendTime = 4;  //id and SendTime used for calculate latency. 
+  float framerate = 5;
+  int64 npausetime = 6;  //upload message in server pause time, calculate latency need substract this value.
 //  string message = 1;
 }
 
@@ -61,6 +68,7 @@ message queryReqStream {
   bool bimportant = 6;  //if 1, is important.
   int32 kepptime = 7;   //If important keep this data before ctrl ms.  if -1 must send.
   int32 ntype = 8;  //0 only query  1 ctrl.
+  float nSuggestFrameRate = 9;
 }
 
 message queryReplyStream {
@@ -68,6 +76,8 @@ message queryReplyStream {
     int32 id = 2;
     int64 ntime = 3;
     bytes xdata = 4;
+    int64 nculatency = 5;
+    float ncuFrameRage = 6;
 }
 
 

+ 13 - 2
src/driver/driver_cloud_grpc_server_stream/cumsgbuffer.cpp

@@ -5,7 +5,8 @@ cumsgbuffer::cumsgbuffer()
 
 }
 
-void cumsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::string strqueryMD5, std::string strctrlMD5, std::vector<char> *pxdata,bool bImportant,int nkeeptime)
+void cumsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::string strqueryMD5, std::string strctrlMD5,
+                         std::vector<char> *pxdata,bool bImportant,int nkeeptime,qint64 nculatency)
 {
     qDebug("ntime is %ld",ntime);
     mMutex.lock();
@@ -28,6 +29,7 @@ void cumsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::string s
         cmsg.strVIN = strVIN;
         cmsg.strqueryMD5 = strqueryMD5;
         cmsg.strctrlMD5 = strctrlMD5;
+        cmsg.mnlatency = nculatency;
         if(pxdata->size() > 0)
         {
             cmsg.xdata.resize(pxdata->size());
@@ -53,6 +55,7 @@ void cumsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::string s
         pmsg->strqueryMD5 = strqueryMD5;
         pmsg->strctrlMD5 = strctrlMD5;
         pmsg->xdata.clear();
+        pmsg->mnlatency = nculatency;
         if(pxdata->size()>0)
         {
             pmsg->xdata.resize(pxdata->size());
@@ -64,7 +67,8 @@ void cumsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::string s
 }
 
 
-int cumsgbuffer::getmsg(std::string strVIN,std::string strqueryMD5, qint64 nlasttime, int &id, qint64 &ntime,   std::vector<char> *pxdata)
+int cumsgbuffer::getmsg(std::string strVIN,std::string strqueryMD5, qint64 nlasttime, int &id, qint64 &ntime,
+                        std::vector<char> *pxdata,qint64 * pnculatency)
 {
     mMutex.lock();
     iv::cumsg * pmsg = 0;
@@ -99,9 +103,16 @@ int cumsgbuffer::getmsg(std::string strVIN,std::string strqueryMD5, qint64 nlast
         mMutex.unlock();
         return 0;
     }
+    qint64 now = QDateTime::currentMSecsSinceEpoch();
+    if(abs(now - pmsg->mlastuptime)>60000)   //Data  is old not use.
+    {
+        mMutex.unlock();
+        return 0;
+    }
     id = pmsg->id;
     ntime = pmsg->ntime;
     pxdata->clear();
+    *pnculatency = pmsg->mnlatency;
     int ndatasize = pmsg->xdata.size();
     pxdata->resize(ndatasize);
     memcpy(pxdata->data(),pmsg->xdata.data(),ndatasize);

+ 3 - 2
src/driver/driver_cloud_grpc_server_stream/cumsgbuffer.h

@@ -22,6 +22,7 @@ struct cumsg
     bool mbImportant = false;
     int mkeeptime;
     bool mbhavequery = false;
+    qint64 mnlatency;
 };
 }
 
@@ -37,14 +38,14 @@ private:
 
 public:
     void addmsg(int id,qint64 ntime,std::string strVIN,std::string strqueryMD5,
-                std::string strctrlMD5,std::vector<char> * pxdata,bool bImportant,int nkeeptime);
+                std::string strctrlMD5,std::vector<char> * pxdata,bool bImportant,int nkeeptime,qint64 nculatency);
 
 
     //if no new msg return 0
     // -1 no this vin
     // -2 queryMD5 error
     int getmsg(std::string strVIN,std::string strqueryMD5,qint64 nlasttime, int & id,qint64 & ntime,
-                std::vector<char> * pxdata);
+                std::vector<char> * pxdata,qint64 * pnculatency);
 
 
 

+ 126 - 9
src/driver/driver_cloud_grpc_server_stream/main.cpp

@@ -33,9 +33,63 @@ using grpc::Status;
 static cumsgbuffer gcumsgbuf;
 static pcmsgbuffer gpcmsgbuf;
 
+char gstrport[255];
+
+#include <getopt.h>
+
+void print_useage()
+{
+    std::cout<<" -p --port $port : port . eq.  -p 50051"<<std::endl;
+    std::cout<<" -h --help print help"<<std::endl;
+}
+
+int  GetOptLong(int argc, char *argv[]) {
+    int nRtn = 0;
+    int opt; // getopt_long() 的返回值
+    int digit_optind = 0; // 设置短参数类型及是否需要参数
+
+    // 如果option_index非空,它指向的变量将记录当前找到参数符合long_opts里的
+    // 第几个元素的描述,即是long_opts的下标值
+    int option_index = 0;
+    // 设置短参数类型及是否需要参数
+    const char *optstring = "m:r:x:y:o:p:s:h";
+
+
+    static struct option long_options[] = {
+        {"port", required_argument, NULL, 'p'},
+        {"help",  no_argument,       NULL, 'h'},
+ //       {"optarg", optional_argument, NULL, 'o'},
+        {0, 0, 0, 0}  // 添加 {0, 0, 0, 0} 是为了防止输入空值
+    };
+
+    while ( (opt = getopt_long(argc,
+                               argv,
+                               optstring,
+                               long_options,
+                               &option_index)) != -1) {
+        switch(opt)
+        {
+
+        case 'p':
+            strncpy(gstrport,optarg,255);
+            break;
+        case 'h':
+            print_useage();
+            nRtn = 1; //because use -h
+            break;
+        default:
+            break;
+        }
+
+    }
+
+    return nRtn;
+}
+
+
 
 void uploadsend(::grpc::ServerReaderWriter<iv::UploadReplyStream, iv::UploadRequestStream>* stream,bool * pbrun,
-                std::string * pstrvin,std::string * pstrmd5,bool *pbUpdatemd4orvin,QMutex * pmutex)
+                std::string * pstrvin,std::string * pstrmd5,bool *pbUpdatemd4orvin,QMutex * pmutex,int * preqid,qint64 * pnsendtime,qint64 * recvtime,QMutex * pmutexidtime)
 {
     std::string strvin;
     std::string strmd5;
@@ -60,16 +114,24 @@ void uploadsend(::grpc::ServerReaderWriter<iv::UploadReplyStream, iv::UploadRequ
 
         int id;
         qint64 ntime;
+        float framerate;
 
         std::vector<char > xvectorctrldata;
 
-        int nres = gpcmsgbuf.getmsg(strvin,strmd5,id,ntime,&xvectorctrldata);
+        int nres = gpcmsgbuf.getmsg(strvin,strmd5,id,ntime,&xvectorctrldata,&framerate);
 
         iv::UploadReplyStream reply;
+
+        pmutexidtime->lock();
+        reply.set_nreqsendtime(*pnsendtime);
+        reply.set_nreqid(*preqid);
+        reply.set_npausetime(QDateTime::currentMSecsSinceEpoch() - *recvtime);
+        pmutexidtime->unlock();
         if(nres == 1)
         {
             reply.set_nres(nres);
             reply.set_xdata(xvectorctrldata.data(),xvectorctrldata.size());
+            reply.set_framerate(framerate);
             stream->Write(reply);
             nlastsend = xTime.elapsed();
         }
@@ -78,7 +140,9 @@ void uploadsend(::grpc::ServerReaderWriter<iv::UploadReplyStream, iv::UploadRequ
             if(abs(xTime.elapsed() - nlastsend)>1000)
             {
                 reply.set_nres(nres);
+                reply.set_framerate(0);
                 stream->Write(reply);
+
                 nlastsend = xTime.elapsed();
             }
         }
@@ -88,8 +152,21 @@ void uploadsend(::grpc::ServerReaderWriter<iv::UploadReplyStream, iv::UploadRequ
     }
 }
 
+
+qint64 calcserverlatency(std::vector<qint64> & xvectorserverlatency,qint64 nlatency)
+{
+    xvectorserverlatency.push_back(nlatency);
+    while(xvectorserverlatency.size()>5)xvectorserverlatency.erase(xvectorserverlatency.begin());
+    if(xvectorserverlatency.size()<1)return 0;
+    int nsize = xvectorserverlatency.size();
+    int i;
+    qint64 nrtn = 0;
+    for(i=0;i<nsize;i++)nrtn = nrtn +  xvectorserverlatency.at(i);
+    return nrtn/nsize;
+}
+
 void queryctrlsend(::grpc::ServerReaderWriter<iv::queryReplyStream, iv::queryReqStream>* stream,bool * pbrun,
-                std::string * pstrvin,std::string * pstrmd5,bool *pbUpdatemd4orvin,QMutex * pmutex)
+                std::string * pstrvin,std::string * pstrmd5,bool *pbUpdatemd4orvin,QMutex * pmutex,qint64 * pnserverlatency)
 {
     std::string strvin;
     std::string strmd5;
@@ -102,6 +179,10 @@ void queryctrlsend(::grpc::ServerReaderWriter<iv::queryReplyStream, iv::queryReq
     xTime.start();
     int nlastsend = xTime.elapsed();
     qint64 nlastdatatime = 0;
+    qint64 nculatency;
+
+
+
     while(*pbrun)
     {
         if(*pbUpdatemd4orvin)
@@ -117,7 +198,7 @@ void queryctrlsend(::grpc::ServerReaderWriter<iv::queryReplyStream, iv::queryReq
         qint64 ntime;
         std::vector<char > xvectorquerydata;
 
-        int nres = gcumsgbuf.getmsg(strvin,strmd5,nlastdatatime,id,ntime,&xvectorquerydata);
+        int nres = gcumsgbuf.getmsg(strvin,strmd5,nlastdatatime,id,ntime,&xvectorquerydata,&nculatency);
 
         nlastdatatime = ntime;
 
@@ -125,9 +206,13 @@ void queryctrlsend(::grpc::ServerReaderWriter<iv::queryReplyStream, iv::queryReq
         reply.set_nres(nres);
         if(nres > 0)
         {
+
             reply.set_xdata(xvectorquerydata.data(),xvectorquerydata.size());
             reply.set_id(id);
             reply.set_ntime(ntime);
+            reply.set_nculatency(nculatency);
+            reply.set_nserverlatency(*pnserverlatency);
+            reply.set_nsendtime(QDateTime::currentMSecsSinceEpoch());
             stream->Write(reply);
             nlastsend = xTime.elapsed();
         }
@@ -158,8 +243,15 @@ class UploadServiceImpl final : public iv::UploadStream::Service {
       std::string strvin = "aaa";
       bool bUpdatemd4orvin = false;
       QMutex uploadmutex;
-      std::thread * pthread = new std::thread(uploadsend,stream,&brun,&strvin,&strctrlmd5,&bUpdatemd4orvin,&uploadmutex);
+      int reqid = -1;
+      qint64 pnsendtime = 0;
+      qint64 nrecvtime = 0;
+      QMutex mutexidtime;
+      std::thread * pthread = new std::thread(uploadsend,stream,&brun,&strvin,&strctrlmd5,&bUpdatemd4orvin,&uploadmutex,
+                                              &reqid,&pnsendtime,&nrecvtime,&mutexidtime);
       std::cout<<"new connect."<<std::endl;
+
+
       while (stream->Read(&request))
       {
           std::cout<<" rec req."<<std::endl;
@@ -180,8 +272,14 @@ class UploadServiceImpl final : public iv::UploadStream::Service {
               memcpy(xvectordata.data(),request.xdata().data(),request.xdata().size());
           }
 
+          mutexidtime.lock();
+          reqid = request.id();
+          pnsendtime = request.nsendtime();
+          nrecvtime = QDateTime::currentMSecsSinceEpoch();
+          mutexidtime.unlock();
+
           gcumsgbuf.addmsg(request.id(),request.ntime(),request.strvin(),request.strquerymd5(),request.strctrlmd5(),
-                           &xvectordata,request.bimportant(),request.kepptime());
+                           &xvectordata,request.bimportant(),request.kepptime(),request.nlatency());
 //          std::cout << "收到请求,类型为" << request.askmsg() <<"\n"<<std::endl;
       }
       std::cout<<" no conn"<<std::endl;
@@ -201,7 +299,11 @@ class UploadServiceImpl final : public iv::UploadStream::Service {
       std::string strvin = "aaa";
       bool bUpdatemd4orvin = false;
       QMutex uploadmutex;
-      std::thread * pthread = new std::thread(queryctrlsend,stream,&brun,&strvin,&strquerymd5,&bUpdatemd4orvin,&uploadmutex);
+      qint64 nreplysendtime;
+      qint64 npausetime;
+      std::vector<qint64> xvectorserverlatency;
+      qint64 nserverlatency = 0;
+      std::thread * pthread = new std::thread(queryctrlsend,stream,&brun,&strvin,&strquerymd5,&bUpdatemd4orvin,&uploadmutex,&nserverlatency);
       std::cout<<"new connect."<<std::endl;
       while (stream->Read(&request))
       {
@@ -222,10 +324,16 @@ class UploadServiceImpl final : public iv::UploadStream::Service {
               xvectordata.resize(request.xdata().size());
               memcpy(xvectordata.data(),request.xdata().data(),request.xdata().size());
           }
+          nreplysendtime = request.nreplysendtime();
+          npausetime = request.npausetime();
+          if(nreplysendtime > 0)
+          {
+              nserverlatency =  calcserverlatency(xvectorserverlatency,QDateTime::currentMSecsSinceEpoch() - nreplysendtime - npausetime);
+          }
           static int tempid = 0;
           tempid++;
           int nid = gpcmsgbuf.addmsg(tempid,request.ntime(),request.strvin(),request.strctrlmd5(),&xvectordata,
-                                     request.bimportant(),request.kepptime());
+                                     request.bimportant(),request.kepptime(),request.nsuggestframerate());
 
           (void)&nid;
 
@@ -285,7 +393,8 @@ class UploadServiceImpl final : public iv::UploadStream::Service {
 };
 
 void RunServer() {
-  std::string server_address("0.0.0.0:50051");
+  std::string server_address("0.0.0.0:");
+  server_address = server_address.append(gstrport);
   UploadServiceImpl service;
 
   grpc::EnableDefaultHealthCheckService(true);
@@ -319,6 +428,14 @@ int main(int argc, char *argv[])
 {
     QCoreApplication a(argc, argv);
 
+    snprintf(gstrport,255,"50051");
+
+    int nRtn = GetOptLong(argc,argv);
+    if(nRtn == 1)  //show help,so exit.
+    {
+        return 0;
+    }
+
     gpcmsgbuf.start();
 
     RunServer();

+ 4 - 2
src/driver/driver_cloud_grpc_server_stream/pcmsgbuffer.cpp

@@ -25,7 +25,7 @@ void pcmsgbuffer::run()
     }
 }
 
-unsigned int pcmsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::string strctrlMD5, std::vector<char> *pxdata,bool bImportant,int nkeeptime)
+unsigned int pcmsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::string strctrlMD5, std::vector<char> *pxdata,bool bImportant,int nkeeptime,float framerate)
 {
     unsigned int nrtn;
     mMutex.lock();
@@ -56,6 +56,7 @@ unsigned int pcmsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::
         cmsg.nsendid = muid;
         cmsg.mbImportant = bImportant;
         cmsg.mkeeptime = nkeeptime;
+        cmsg.framerate = framerate;
         nrtn = muid;
         muid++;
         mvectormsg.push_back(cmsg);
@@ -94,7 +95,7 @@ unsigned int pcmsgbuffer::addmsg(int id, qint64 ntime, std::string strVIN, std::
     return nrtn;
 }
 
-int pcmsgbuffer::getmsg(std::string strVIN, std::string strctrlMD5, int &id, qint64 &ntime, std::vector<char> *pxdata)
+int pcmsgbuffer::getmsg(std::string strVIN, std::string strctrlMD5, int &id, qint64 &ntime, std::vector<char> *pxdata,float * framerate)
 {
     mMutex.lock();
     iv::pcmsg * pmsg = 0;
@@ -127,6 +128,7 @@ int pcmsgbuffer::getmsg(std::string strVIN, std::string strctrlMD5, int &id, qin
 
     id = pmsg->id;
     ntime = pmsg->ntime;
+    *framerate = pmsg->framerate;
     pxdata->clear();
     int ndatasize = pmsg->xdata.size();
     pxdata->resize(ndatasize);

+ 3 - 2
src/driver/driver_cloud_grpc_server_stream/pcmsgbuffer.h

@@ -21,6 +21,7 @@ struct pcmsg
     bool mbImportant = false;
     int mkeeptime;
     bool mbhavequery = false;
+    float framerate = 0;
 };
 }
 
@@ -48,12 +49,12 @@ private:
 public:
 
     unsigned int addmsg(int id,qint64 ntime,std::string strVIN,
-                std::string strctrlMD5,std::vector<char> * pxdata,bool bImportant,int nkeeptime);
+                std::string strctrlMD5,std::vector<char> * pxdata,bool bImportant,int nkeeptime,float framerate);
 
     //if no new msg return 0
     // -2 queryMD5 error
     int getmsg(std::string strVIN,std::string strctrlMD5,int & id,qint64 & ntime,
-                std::vector<char> * pxdata);
+                std::vector<char> * pxdata,float * framerate);
 
     int querysendstate(int nsendid);
 private:

+ 10 - 0
src/driver/driver_cloud_grpc_server_stream/uploadstreammsg.proto

@@ -42,12 +42,19 @@ message UploadRequestStream {
     bytes xdata = 6;
     bool bimportant = 7;  //if 1, is important.
     int32 kepptime = 8;   //If important keep this data before query ms.
+    float fFrameRate = 9;
+    int64 nSendTime = 10;
+    int64 nLatency = 11;
 }
 
 // The response message containing the greetings
 message UploadReplyStream {
   int32 nres = 1;  //0 no message 1 have ctrl message
   bytes xdata = 2;
+  int32 nreqid = 3;  
+  int64 nreqSendTime = 4;  //id and SendTime used for calculate latency. 
+  float framerate = 5;
+  int64 npausetime = 6;  //upload message in server pause time, calculate latency need substract this value.
 //  string message = 1;
 }
 
@@ -61,6 +68,7 @@ message queryReqStream {
   bool bimportant = 6;  //if 1, is important.
   int32 kepptime = 7;   //If important keep this data before ctrl ms.  if -1 must send.
   int32 ntype = 8;  //0 only query  1 ctrl.
+  float nSuggestFrameRate = 9;
 }
 
 message queryReplyStream {
@@ -68,6 +76,8 @@ message queryReplyStream {
     int32 id = 2;
     int64 ntime = 3;
     bytes xdata = 4;
+    int64 nculatency = 5;
+    float ncuFrameRage = 6;
 }
 
 

+ 15 - 0
src/include/proto3/uploadstreammsg.proto

@@ -42,12 +42,19 @@ message UploadRequestStream {
     bytes xdata = 6;
     bool bimportant = 7;  //if 1, is important.
     int32 kepptime = 8;   //If important keep this data before query ms.
+    float fFrameRate = 9;
+    int64 nSendTime = 10;
+    int64 nLatency = 11;
 }
 
 // The response message containing the greetings
 message UploadReplyStream {
   int32 nres = 1;  //0 no message 1 have ctrl message
   bytes xdata = 2;
+  int32 nreqid = 3;  
+  int64 nreqSendTime = 4;  //id and SendTime used for calculate latency. 
+  float framerate = 5;
+  int64 npausetime = 6;  //upload message in server pause time, calculate latency need substract this value.
 //  string message = 1;
 }
 
@@ -61,6 +68,10 @@ message queryReqStream {
   bool bimportant = 6;  //if 1, is important.
   int32 kepptime = 7;   //If important keep this data before ctrl ms.  if -1 must send.
   int32 ntype = 8;  //0 only query  1 ctrl.
+  float nSuggestFrameRate = 9;
+  int32 nreplyid = 10;  
+  int64 nreplySendTime = 11;  //id and SendTime used for calculate latency. 
+  int64 npausetime = 12;  //upload message in server pause time, calculate latency need substract this value.
 }
 
 message queryReplyStream {
@@ -68,6 +79,10 @@ message queryReplyStream {
     int32 id = 2;
     int64 ntime = 3;
     bytes xdata = 4;
+    int64 nculatency = 5;
+    float ncuFrameRage = 6;
+    int64 nSendTime = 7;
+    int64 nserverLatency = 8;
 }
 
 

+ 76 - 0
src/tool/IVSysMan/main.cpp

@@ -1,5 +1,8 @@
 #include "mainwindow.h"
 #include <QApplication>
+#include <QSharedMemory>
+#include <QMessageBox>
+
 #include <string>
 #include "ivlog.h"
 
@@ -11,10 +14,83 @@ std::string locateInfoPath;
 iv::Ivlog * ivlog;
 iv::Ivfault * ivfault;
 
+#define USE_ONEIVSYSMAN
+
+
+extern bool gbOneThreadRunning ;
+extern bool gbOneThreadRun ;
+void threadOne(QSharedMemory * pshare,int ncount)
+{
+    while(gbOneThreadRun)
+    {
+        pshare->lock();
+        int * pdata = (int *)pshare->data();
+        if(*pdata != ncount)
+        {
+            *pdata = ncount;
+            qDebug("another thread want running.");
+        }
+        pshare->unlock();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+
+    gbOneThreadRunning = false;
+}
+
+
 int main(int argc, char *argv[])
 {
     QApplication a(argc, argv);
 
+#ifdef  USE_ONEIVSYSMAN
+
+    QSharedMemory shareMem("IVSysMan_Count");
+
+    int ncount = 0;
+    bool bHaveAnother = false;
+    if(shareMem.attach())
+    {
+        shareMem.lock();
+        int * pdata = (int *)shareMem.data();
+        ncount = (*pdata)+1;
+        qDebug("now IVSysMan_Count is %d",ncount);
+        *pdata = ncount;
+        shareMem.unlock();
+
+        std::this_thread::sleep_for(std::chrono::milliseconds(100));
+        shareMem.lock();
+        pdata = (int *)shareMem.data();
+        if(*pdata != ncount)
+        {
+            qDebug("Another IVSysMan Running");
+            bHaveAnother = true;
+        }
+        *pdata = ncount;
+        shareMem.unlock();
+
+    }
+    else
+    {
+        shareMem.create(100);
+        shareMem.lock();
+        int * pdata = (int *)shareMem.data();
+        *pdata = 1;
+        qDebug("now IVSysMan_Count is %d",*pdata);
+        shareMem.unlock();
+    }
+
+    if(bHaveAnother == true)
+    {
+        QMessageBox::warning(NULL,"Warning","Another IVSysMan Running.",QMessageBox::YesAll);
+        return 0;
+    }
+
+    void * ponethread = new std::thread(threadOne,&shareMem,ncount);
+    (void *)ponethread;
+
+
+#endif
+
     RegisterIVBackTrace();
 
     ivlog = new iv::Ivlog("IVSysMan");

+ 4 - 1
src/tool/IVSysMan/mainwindow.cpp

@@ -16,6 +16,8 @@ static iv::Switch::settingsCmd  gsettingcmd;
 static bool gbupdatesetting = false;
 QMutex gMutexSetting;
 
+bool gbOneThreadRunning = true;
+bool gbOneThreadRun = true;
 
 
 void ListenChange(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
@@ -149,9 +151,10 @@ MainWindow::~MainWindow()
     qint64 time;
     time = QDateTime::currentMSecsSinceEpoch();
     mPM->requestInterruption();
+    gbOneThreadRun = false;
     while((QDateTime::currentMSecsSinceEpoch() - time)<1500)
     {
-        if(mPM->isFinished())
+        if((mPM->isFinished())&&(gbOneThreadRunning == false))
         {
             qDebug("finish");
             break;

+ 6 - 3
src/tool/RemoteCtrl_Stream/RemoteCtrl_Stream.pro

@@ -46,7 +46,8 @@ SOURCES += \
     ../../driver/driver_cloud_grpc_pc_stream/uploadstreammsg.grpc.pb.cc \
     ../../include/msgtype/cloud.pb.cc \
     dialogpic.cpp \
-    ivpicsave.cpp
+    ivpicsave.cpp \
+    dialogsetframerate.cpp
 
 HEADERS += \
     ../../include/msgtype/gps.pb.h \
@@ -67,12 +68,14 @@ HEADERS += \
     ../../driver/driver_cloud_grpc_pc_stream/uploadstreammsg.grpc.pb.h \
     ../../include/msgtype/cloud.pb.h \
     dialogpic.h \
-    ivpicsave.h
+    ivpicsave.h \
+    dialogsetframerate.h
 
 FORMS += \
     dialogbigpic.ui \
     mainwindow.ui \
-    dialogpic.ui
+    dialogpic.ui \
+    dialogsetframerate.ui
 
 # Default rules for deployment.
 qnx: target.path = /tmp/$${TARGET}/bin

+ 27 - 0
src/tool/RemoteCtrl_Stream/dialogsetframerate.cpp

@@ -0,0 +1,27 @@
+#include "dialogsetframerate.h"
+#include "ui_dialogsetframerate.h"
+
+DialogSetFrameRate::DialogSetFrameRate(float * pframerate,float * pctrlfps,QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::DialogSetFrameRate)
+{
+    mpframerate = pframerate;
+    mpctrlfps = pctrlfps;
+
+    ui->setupUi(this);
+
+    ui->lineEdit_framerate->setText(QString::number(*mpframerate));
+    ui->lineEdit_ctrfps->setText(QString::number(*mpctrlfps));
+}
+
+DialogSetFrameRate::~DialogSetFrameRate()
+{
+    delete ui;
+}
+
+void DialogSetFrameRate::on_pushButton_set_clicked()
+{
+    *mpframerate = ui->lineEdit_framerate->text().toDouble();
+    *mpctrlfps = ui->lineEdit_ctrfps->text().toDouble();
+    this->accept();
+}

+ 27 - 0
src/tool/RemoteCtrl_Stream/dialogsetframerate.h

@@ -0,0 +1,27 @@
+#ifndef DIALOGSETFRAMERATE_H
+#define DIALOGSETFRAMERATE_H
+
+#include <QDialog>
+
+namespace Ui {
+class DialogSetFrameRate;
+}
+
+class DialogSetFrameRate : public QDialog
+{
+    Q_OBJECT
+
+public:
+    explicit DialogSetFrameRate(float * pframerate, float * pctrlfps,QWidget *parent = 0);
+    ~DialogSetFrameRate();
+
+private slots:
+    void on_pushButton_set_clicked();
+
+private:
+    Ui::DialogSetFrameRate *ui;
+    float * mpframerate;
+    float * mpctrlfps;
+};
+
+#endif // DIALOGSETFRAMERATE_H

+ 78 - 0
src/tool/RemoteCtrl_Stream/dialogsetframerate.ui

@@ -0,0 +1,78 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>DialogSetFrameRate</class>
+ <widget class="QDialog" name="DialogSetFrameRate">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>400</width>
+    <height>300</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <widget class="QPushButton" name="pushButton_set">
+   <property name="geometry">
+    <rect>
+     <x>140</x>
+     <y>190</y>
+     <width>89</width>
+     <height>25</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Set</string>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_framerate">
+   <property name="geometry">
+    <rect>
+     <x>188</x>
+     <y>124</y>
+     <width>111</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label">
+   <property name="geometry">
+    <rect>
+     <x>30</x>
+     <y>127</y>
+     <width>141</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>上传频率(HZ)</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_2">
+   <property name="geometry">
+    <rect>
+     <x>30</x>
+     <y>50</y>
+     <width>141</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>控制频率(HZ)</string>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_ctrfps">
+   <property name="geometry">
+    <rect>
+     <x>190</x>
+     <y>49</y>
+     <width>111</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 169 - 0
src/tool/RemoteCtrl_Stream/mainwindow.cpp

@@ -194,6 +194,47 @@ MainWindow::MainWindow(QWidget *parent)
     mpbigpicdlg->setModal(false);
     connect(mpbigpicdlg,SIGNAL(finished(int)),this,SLOT(onCloseBigDlg()));
 
+    mpProgLatency = new QProgressBar();
+    ui->statusbar->addPermanentWidget(mpProgLatency);
+    QLabel * pLabel = new QLabel();
+    pLabel->setFixedWidth(150);
+    pLabel->setText("Latency");
+    mpLabelLatency = pLabel;
+    ui->statusbar->addPermanentWidget(pLabel);
+    mpProgLatency->setRange(0,500);
+    mpProgLatency->setValue(0);
+    mpProgLatency->setTextVisible(false);
+    mpProgLatency->setFixedWidth(200);
+    mpProgLatency->setStyleSheet("QProgressBar{background:white} QProgressBar:chunk{background:green}");
+
+
+    mpProgServerLatency = new QProgressBar();
+    ui->statusbar->addPermanentWidget(mpProgServerLatency);
+    pLabel = new QLabel();
+    pLabel->setFixedWidth(150);
+    pLabel->setText("Server Latency");
+    mpLabelServerLatency = pLabel;
+    ui->statusbar->addPermanentWidget(pLabel);
+    mpProgServerLatency->setRange(0,500);
+    mpProgServerLatency->setValue(0);
+    mpProgServerLatency->setTextVisible(false);
+    mpProgServerLatency->setFixedWidth(200);
+    mpProgServerLatency->setStyleSheet("QProgressBar{background:white} QProgressBar:chunk{background:green}");
+ //   mpProgLatency->setGeometry(0,0,300,30);
+
+
+    pLabel = new QLabel();
+    pLabel->setText(" ");
+    pLabel->setFixedWidth(50);
+    ui->statusbar->addPermanentWidget(pLabel);
+
+    pLabel = new QLabel();
+    pLabel->setText("Connecting to server....");
+    pLabel->setFixedWidth(200);
+    ui->statusbar->addPermanentWidget(pLabel);
+    mpLabelState = pLabel;
+    mpLabelState->setStyleSheet("QLabel{color: red}");
+
     setWindowTitle(mstrProgName +mstrVIN+  mstrGPSTime + mstrPicTime);
 
 }
@@ -635,6 +676,111 @@ void MainWindow::onTimerUpdateView()
     static qint64 time_gps = 0;
 
 
+    qint64 nculatency = mgrpcpc->getculatency();
+    if(nculatency != mncurculatency)
+    {
+        mncurculatency = nculatency;
+        int nsheet = 0;
+        if(mncurculatency >= 50)
+        {
+            if(mncurculatency >= 200)nsheet = 2;
+            else nsheet = 1;
+        }
+        bool bNeedChangeSheet = false;
+        if(nsheet != mnProgLatencySheet)
+        {
+            mnProgLatencySheet = nsheet;
+            bNeedChangeSheet = true;
+        }
+        mpLabelLatency->setText("IV Latency: "+QString::number(mncurculatency)+"ms");
+        int nprog = mncurculatency;
+        if(nprog>500)nprog = 500;
+        mpProgLatency->setValue(nprog);
+        if(bNeedChangeSheet)
+        {
+            switch(mnProgLatencySheet)
+            {
+            case 0:
+                mpProgLatency->setStyleSheet("QProgressBar{background:white} QProgressBar:chunk{background:green}");
+                break;
+            case 1:
+                mpProgLatency->setStyleSheet("QProgressBar{background:white} QProgressBar:chunk{background:blue}");
+                break;
+            case 2:
+                mpProgLatency->setStyleSheet("QProgressBar{background:white} QProgressBar:chunk{background:red}");
+                break;
+            }
+        }
+
+    }
+
+    int nstate = mgrpcpc->getstate();
+    if(nstate != mnstate)
+    {
+        mnstate = nstate;
+        switch (mnstate) {
+        case -100:
+            mpLabelState->setText("Connecting to Server...");
+            mpLabelState->setStyleSheet("QLabel{color: red}");
+            break;
+        case -2:
+            mpLabelState->setText("Password Error...");
+            mpLabelState->setStyleSheet("QLabel{color: red}");
+            break;
+        case -1:
+            mpLabelState->setText("IV not login...");
+            mpLabelState->setStyleSheet("QLabel{color: red}");
+            break;
+        case 0:
+            mpLabelState->setText("IV OffLine.");
+            mpLabelState->setStyleSheet("QLabel{color: red}");
+            break;
+        case 1:
+            mpLabelState->setText("IV OK...");
+            mpLabelState->setStyleSheet("QLabel{color: green}");
+            break;
+        default:
+            break;
+        }
+    }
+
+    qint64 nServerlatency = mgrpcpc->getserverlatency();
+    if(nServerlatency != mncurServerlatency)
+    {
+        mncurServerlatency = nServerlatency;
+        int nsheet = 0;
+        if(mncurServerlatency >= 50)
+        {
+            if(mncurServerlatency >= 200)nsheet = 2;
+            else nsheet = 1;
+        }
+        bool bNeedChangeSheet = false;
+        if(nsheet != mnProgServerLatencySheet)
+        {
+            mnProgServerLatencySheet = nsheet;
+            bNeedChangeSheet = true;
+        }
+        mpLabelServerLatency->setText("Server Latency: "+QString::number(mncurServerlatency)+"ms");
+        int nprog = mncurServerlatency;
+        if(nprog>500)nprog = 500;
+        mpProgServerLatency->setValue(nprog);
+        if(bNeedChangeSheet)
+        {
+            switch(mnProgServerLatencySheet)
+            {
+            case 0:
+                mpProgServerLatency->setStyleSheet("QProgressBar{background:white} QProgressBar:chunk{background:green}");
+                break;
+            case 1:
+                mpProgServerLatency->setStyleSheet("QProgressBar{background:white} QProgressBar:chunk{background:blue}");
+                break;
+            case 2:
+                mpProgServerLatency->setStyleSheet("QProgressBar{background:white} QProgressBar:chunk{background:red}");
+                break;
+            }
+        }
+
+    }
 
     if(gTimeGPSIMUUpdate != time_gps)
     {
@@ -839,3 +985,26 @@ void MainWindow::onCloseBigDlg()
 {
     mpbigpicdlg->setRefresh(false);
 }
+
+void MainWindow::on_actionSet_FrameRate_triggered()
+{
+    float framerate = mgrpcpc->getframerate();
+    float oldfr = framerate;
+    float fctrlfps = mgrpcpc->getctrlfps();
+    float oldctrlfps = fctrlfps;
+    DialogSetFrameRate xdialog(&framerate,&fctrlfps);
+    xdialog.exec();
+    if(oldfr != framerate)
+    {
+        mgrpcpc->setframerate(framerate);
+    }
+    if(oldctrlfps != fctrlfps)
+    {
+        mgrpcpc->setctrlfps(fctrlfps);
+    }
+}
+
+void MainWindow::on_actionSet_Camera_triggered()
+{
+    
+}

+ 21 - 0
src/tool/RemoteCtrl_Stream/mainwindow.h

@@ -10,6 +10,7 @@
 #include <QtWebEngineWidgets/QtWebEngineWidgets>
 #include <QSet>
 #include <QMutex>
+#include <QProgressBar>
 
 #include <iostream>
 
@@ -26,6 +27,7 @@
 
 #include "dialogpic.h"
 #include "dialogbigpic.h"
+#include "dialogsetframerate.h"
 
 #include "modulecomm.h"
 
@@ -101,6 +103,10 @@ private slots:
 
     void on_pushButton_big_clicked();
 
+    void on_actionSet_FrameRate_triggered();
+
+    void on_actionSet_Camera_triggered();
+    
 public:
      void resizeEvent(QResizeEvent *event);
 
@@ -170,6 +176,21 @@ private:
      DialogPic * mppicdlg;
      DialogBigPic * mpbigpicdlg;
 
+     QProgressBar * mpProgLatency;
+     QLabel * mpLabelLatency;
+
+     qint64 mncurculatency = 0;
+     int mnProgLatencySheet = 0; //0 green 1 blue 2 red
+
+     QProgressBar * mpProgServerLatency;
+     QLabel * mpLabelServerLatency;
+
+     qint64 mncurServerlatency = 0;
+     int mnProgServerLatencySheet = 0; //0 green 1 blue 2 red
+
+     int mnstate = -100;
+     QLabel * mpLabelState;
+
 
      bool mbSavePic = false;
 

+ 19 - 1
src/tool/RemoteCtrl_Stream/mainwindow.ui

@@ -486,11 +486,29 @@
      <x>0</x>
      <y>0</y>
      <width>1183</width>
-     <height>28</height>
+     <height>22</height>
     </rect>
    </property>
+   <widget class="QMenu" name="menuFile">
+    <property name="title">
+     <string>Fi&amp;le</string>
+    </property>
+   </widget>
+   <widget class="QMenu" name="menuSet">
+    <property name="title">
+     <string>Set</string>
+    </property>
+    <addaction name="actionSet_FrameRate"/>
+   </widget>
+   <addaction name="menuFile"/>
+   <addaction name="menuSet"/>
   </widget>
   <widget class="QStatusBar" name="statusbar"/>
+  <action name="actionSet_FrameRate">
+   <property name="text">
+    <string>&amp;Set FrameRate</string>
+   </property>
+  </action>
  </widget>
  <resources>
   <include location="remotectrl.qrc"/>

+ 1 - 1
src/tool/data_serials/mainwindow.cpp

@@ -61,7 +61,7 @@ void MainWindow::on_updataDecision()
         mf_speed    = mp_dataParser->mf_speed;
         mf_acc      = mp_dataParser->mf_acc;
         mf_brake    = mp_dataParser->mf_brake;
-        mf_brake    = mp_dataParser->mf_wheel;
+        mf_wheel    = mp_dataParser->mf_wheel;
         mf_obsDis   = mp_dataParser->mf_obsDis;
         mi_lidarObs = mp_dataParser->mi_lidarObs;
         mi_radarObs = mp_dataParser->mi_radarObs;

+ 158 - 0
src/tool/map_lanetoxodr/ivxodrtool.cpp

@@ -0,0 +1,158 @@
+#include "ivxodrtool.h"
+
+#include <limits>
+#include <math.h>
+
+ivxodrtool::ivxodrtool()
+{
+
+}
+
+ivxodrtool & ivxodrtool::Inst()
+{
+    static ivxodrtool x;
+    return x;
+}
+
+
+void ivxodrtool::ChangeMaxMin(double x, double y, double &xmin, double &ymin, double &xmax, double &ymax)
+{
+    if(x<xmin)xmin = x;
+    if(y<ymin)ymin = y;
+    if(x>xmax)xmax = x;
+    if(y>ymax)ymax = y;
+}
+
+int ivxodrtool::GetRoadMaxMin(Road *pRoad, double &xmin, double &ymin, double &xmax, double &ymax)
+{
+    if(pRoad == 0)return -1;
+
+    int j;
+    xmin = std::numeric_limits<double>::max();
+    ymin = std::numeric_limits<double>::max();
+    xmax = (-1.0)*std::numeric_limits<double>::max();
+    ymax = (-1.0)*std::numeric_limits<double>::max();
+    for(j=0;j<pRoad->GetGeometryBlockCount();j++)
+    {
+        GeometryBlock * pgeob = pRoad->GetGeometryBlock(j);
+        double x,y;
+        double x_center,y_center;
+        double R;
+        RoadGeometry * pg;
+        GeometryArc * parc;
+        GeometryParamPoly3 * ppp3;
+        GeometrySpiral *pSpiral;
+        double rel_x,rel_y,rel_hdg;
+        pg = pgeob->GetGeometryAt(0);
+
+        x = pg->GetX();
+        y = pg->GetY();
+
+        ChangeMaxMin(x,y,xmin,ymin,xmax,ymax);
+
+        switch (pg->GetGeomType()) {
+        case 0:
+            ChangeMaxMin(x + pg->GetLength() * cos(pg->GetHdg()),y + pg->GetLength() * sin(pg->GetHdg()),xmin,ymin,xmax,ymax);
+
+            break;
+
+        case 1:
+            pSpiral = (GeometrySpiral * )pg;
+            {
+               int ncount = 100;
+               double sstep = pSpiral->GetLength()/((double)ncount);
+               int k;
+               double x0,y0,hdg0,s0;
+               x0 = pSpiral->GetX();
+               y0 = pSpiral->GetY();
+               s0 = pSpiral->GetS();
+               hdg0 = pSpiral->GetHdg() ;
+               for(k=0;k<ncount;k++)
+               {
+                   pSpiral->GetCoords(s0+sstep*k,rel_x,rel_y,rel_hdg);
+
+                   x = rel_x;
+                   y = rel_y;
+                   ChangeMaxMin(x,y,xmin,ymin,xmax,ymax);
+
+
+               }
+            }
+
+//                    qDebug("spi");
+            break;
+        case 2:
+            {
+            parc = (GeometryArc *)pg;
+            R = abs(1.0/parc->GetCurvature());
+            if(parc->GetCurvature() > 0)
+            {
+                x_center = pg->GetX() + R *cos(pg->GetHdg() + M_PI/2.0);
+                y_center = pg->GetY() + R * sin(pg->GetHdg() + M_PI/2.0);
+            }
+            else
+            {
+                x_center = pg->GetX() + R *cos(pg->GetHdg() -M_PI/2.0);
+                y_center = pg->GetY() + R * sin(pg->GetHdg() - M_PI/2.0);
+            }
+
+            int k;
+            int ncount = 100 ;
+            double curv = parc->GetCurvature();
+            double hdgstep;
+            double hdg0 = parc->GetHdg();
+            double hdgnow = parc->GetHdg();
+            if(ncount > 0) hdgstep= (parc->GetLength()/R)/ncount;
+            for(k=0;k<ncount;k++)
+            {
+                double x_draw,y_draw;
+
+                if(curv > 0)
+                {
+                    hdgnow =  hdg0 + k*hdgstep;
+                    x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
+                    y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
+                }
+                else
+                {
+                    hdgnow = hdg0 - k * hdgstep;
+                    x_draw = x_center + R *cos(hdgnow  + M_PI/2.0);
+                    y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
+                }
+                ChangeMaxMin(x_draw,y_draw,xmin,ymin,xmax,ymax);
+
+            }
+            }
+            break;
+        case 4:
+            {
+            ppp3 = (GeometryParamPoly3 * )pg;
+            int ncount = ppp3->GetLength();
+            double sstep;
+            if(ncount > 0)sstep = ppp3->GetLength()/ncount;
+            else sstep = 10000.0;
+            double s = 0;
+            while(s < ppp3->GetLength())
+            {
+                double xtem,ytem;
+                xtem = ppp3->GetuA() +  ppp3->GetuB() * s +  ppp3->GetuC() * s*s +  ppp3->GetuD() * s*s*s;
+                ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
+                x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
+                y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
+                ChangeMaxMin(x,y,xmin,ymin,xmax,ymax);
+                s = s+ sstep;
+            }
+            }
+            break;
+        default:
+            break;
+        }
+
+//         painter->drawPoint((int)(x*nfac),(int)(y*(-1.0*nfac)));
+
+    }
+    return 0;
+
+
+
+}

+ 24 - 0
src/tool/map_lanetoxodr/ivxodrtool.h

@@ -0,0 +1,24 @@
+#ifndef IVXODRTOOL_H
+#define IVXODRTOOL_H
+
+#include "OpenDrive/OpenDrive.h"
+
+class ivxodrtool
+{
+public:
+    ivxodrtool();
+public:
+    static ivxodrtool& Inst();
+
+public:
+    int GetRoadMaxMin(Road * pRoad,double & xmin,double & ymin,double & xmax,double & ymax);
+
+private:
+
+    void ChangeMaxMin(double x,double y,double & xmin,double & ymin,double & xmax,double & ymax);
+};
+
+
+#define ServiceXODRTool ivxodrtool::Inst()
+
+#endif // IVXODRTOOL_H

+ 12 - 0
src/tool/map_lanetoxodr/mainwindow.cpp

@@ -4795,3 +4795,15 @@ void MainWindow::on_actionSet_Traffic_Light_triggered()
     TrafficLightDialog td(&mxodr,this);
     int res = td.exec();
 }
+
+void MainWindow::on_actionEdit_Road_Lane_triggered()
+{
+
+}
+
+void MainWindow::on_actionEdit_Road_triggered()
+{
+
+    RoadEditDialog rd(&mxodr,this);
+    int res = rd.exec();
+}

+ 5 - 0
src/tool/map_lanetoxodr/mainwindow.h

@@ -42,6 +42,7 @@
 #include "autoconnect.h"
 #include "speeddialog.h"
 #include "trafficlightdialog.h"
+#include "roadeditdialog.h"
 
 #include <iostream>
 #include <map>
@@ -165,6 +166,10 @@ private slots:
 
     void on_actionSet_Traffic_Light_triggered();
 
+    void on_actionEdit_Road_Lane_triggered();
+
+    void on_actionEdit_Road_triggered();
+
 private:
 
 

+ 27 - 0
src/tool/map_lanetoxodr/mainwindow.ui

@@ -42,8 +42,17 @@
     <addaction name="actionSet_Speed"/>
     <addaction name="actionSet_Traffic_Light"/>
    </widget>
+   <widget class="QMenu" name="menuTool">
+    <property name="title">
+     <string>Tool</string>
+    </property>
+    <addaction name="actionEdit_Road"/>
+    <addaction name="actionMerge_Road"/>
+    <addaction name="actionEdit_Road_Lane"/>
+   </widget>
    <addaction name="menuFile"/>
    <addaction name="menuFunction"/>
+   <addaction name="menuTool"/>
   </widget>
   <widget class="QToolBar" name="mainToolBar">
    <attribute name="toolBarArea">
@@ -85,6 +94,24 @@
     <string>Edit Traffic Light</string>
    </property>
   </action>
+  <action name="actionEdit_Road">
+   <property name="text">
+    <string>Edit Road</string>
+   </property>
+   <property name="toolTip">
+    <string>编辑导率</string>
+   </property>
+  </action>
+  <action name="actionMerge_Road">
+   <property name="text">
+    <string>Merge Road</string>
+   </property>
+  </action>
+  <action name="actionEdit_Road_Lane">
+   <property name="text">
+    <string>Edit Road Lane</string>
+   </property>
+  </action>
  </widget>
  <layoutdefault spacing="6" margin="11"/>
  <resources>

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

@@ -29,8 +29,10 @@ QMAKE_LFLAGS += -no-pie
 
 SOURCES += \
     autoconnect.cpp \
+    ivxodrtool.cpp \
         main.cpp \
         mainwindow.cpp \
+    roadeditdialog.cpp \
     speeddialog.cpp \
     trafficlightdialog.cpp \
     trafficlightlanevaliditydialog.cpp \
@@ -64,8 +66,10 @@ SOURCES += \
 
 HEADERS += \
     autoconnect.h \
+    ivxodrtool.h \
         mainwindow.h \
     rawtype.h \
+    roadeditdialog.h \
     speeddialog.h \
     trafficlightdialog.h \
     trafficlightlanevaliditydialog.h \
@@ -96,6 +100,7 @@ HEADERS += \
 
 FORMS += \
         mainwindow.ui \
+        roadeditdialog.ui \
         speeddialog.ui \
         trafficlightdialog.ui \
         trafficlightlanevaliditydialog.ui \

+ 345 - 0
src/tool/map_lanetoxodr/roadeditdialog.cpp

@@ -0,0 +1,345 @@
+#include "roadeditdialog.h"
+#include "ui_roadeditdialog.h"
+
+#include "math.h"
+
+#define VIEW_WIDTH 850
+#define VIEW_HEIGHT 350
+
+RoadEditDialog::RoadEditDialog(OpenDrive * pxodr,QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::RoadEditDialog)
+{
+    mpxodr = pxodr;
+    ui->setupUi(this);
+
+    myview = new MyView(this);
+    myview->setObjectName(QStringLiteral("graphicsView"));
+    myview->setGeometry(QRect(30, 400, 900, 400));
+
+    connect(myview,SIGNAL(dbclickxy(double,double)),this,SLOT(onClickXY(double,double)));
+
+    image = new QImage(VIEW_WIDTH, VIEW_HEIGHT, QImage::Format_RGB32);//画布的初始化大小设为300*300,使用32位颜色
+    myview->setCacheMode(myview->CacheBackground);
+
+    painter = new QPainter(image);
+
+    painter->end();
+
+    scene = new QGraphicsScene;
+
+    ui->comboBox_geotype->addItem("Line");
+    ui->comboBox_geotype->addItem("Spiral");
+    ui->comboBox_geotype->addItem("Arc");
+    ui->comboBox_geotype->addItem("Poly");
+    ui->comboBox_geotype->addItem("Param Poly");
+
+    int i;
+    int nroadcount = mpxodr->GetRoadCount();
+    for(i=0;i<nroadcount;i++)
+    {
+        const char * strname = mpxodr->GetRoad(i)->GetRoadId().data();
+        ui->comboBox_Road->addItem(strname);
+
+    }
+}
+
+RoadEditDialog::~RoadEditDialog()
+{
+    delete ui;
+}
+
+void RoadEditDialog::ExecPainter()
+{
+    painter->begin(image);
+
+    int nkeep = 30;
+    Road * pRoad = mpCurRoad;
+//         qDebug("time is %d",x.elapsed());
+         image->fill(QColor(255, 255, 255));//对画布进行填充
+
+     //    std::vector<iv::GPSData> navigation_data = brain->navigation_data;
+         painter->setRenderHint(QPainter::Antialiasing, true);//设置反锯齿模式,好看一点
+
+  //       painter->translate(mnMoveX,mnMoveY);
+
+ //        painter->translate(VIEW_WIDTH/2,VIEW_HEIGHT/2);
+
+    double froad_xmin,froad_ymin,froad_xmax,froad_ymax;
+
+    int nfac = 1;
+    ServiceXODRTool.GetRoadMaxMin(pRoad,froad_xmin,froad_ymin,froad_xmax,froad_ymax);
+
+
+    double fac_x,fac_y;
+    fac_x = 100000;
+    fac_y = 100000;
+    if(froad_xmax > froad_xmin)
+    {
+        fac_x = (VIEW_WIDTH-nkeep*2)/(froad_xmax - froad_xmin);
+    }
+
+    if(froad_ymax > froad_ymin)
+    {
+        fac_y = (VIEW_HEIGHT - nkeep*2)/(froad_ymax - froad_ymin);
+    }
+
+    nfac = fac_x;
+    if(fac_y < nfac)nfac = fac_y;
+
+
+         painter->translate(nkeep,VIEW_HEIGHT-nkeep);
+
+         painter->setPen(Qt::black);
+
+//         painter->drawLine(VIEW_WIDTH/(-2),0,VIEW_WIDTH/2,0);
+//         painter->drawLine(0,VIEW_HEIGHT/(-2),0,VIEW_HEIGHT/2);
+
+         int i;
+
+
+        //         int nfac = 5;;
+
+
+         painter->setPen(Qt::blue);
+
+//         if(mbClick)
+//         {
+//         painter->setPen(Qt::red);
+//         painter->drawEllipse(QPoint(mClickX ,mClickY),mnMarkSize,mnMarkSize);
+
+//         painter->setPen(Qt::black);
+//         }
+
+//     if(mbSetObj)
+//     {
+//         painter->setPen(Qt::green);
+//         painter->drawRect(mfObjX*nfac-mnMarkSize,mfObjY*nfac*(-1)-mnMarkSize,mnMarkSize*2,mnMarkSize*2);
+
+//         painter->setPen(Qt::black);
+//     }
+
+     painter->setPen(Qt::green);
+     double x0,y0;
+//     GaussProjCal(glon0,glat0,&x0,&y0);
+
+     painter->setPen(Qt::blue);
+ //            int nfac = nfac;
+  //   int selid = mpCBRoad->currentText().toInt();
+
+   //     continue;
+         int j;
+
+         painter->setPen(Qt::blue);
+
+
+         for(j=0;j<pRoad->GetGeometryBlockCount();j++)
+         {
+             GeometryBlock * pgeob = pRoad->GetGeometryBlock(j);
+             double x,y;
+             double x_center,y_center;
+             double R;
+             RoadGeometry * pg;
+             GeometryArc * parc;
+             GeometryParamPoly3 * ppp3;
+             GeometrySpiral *pSpiral;
+             double rel_x,rel_y,rel_hdg;
+             pg = pgeob->GetGeometryAt(0);
+
+             x = pg->GetX();
+             y = pg->GetY();
+
+              painter->setPen(Qt::blue);
+             if(j == mnSelGeo)
+             {
+                 painter->setPen(Qt::green);
+             }
+
+//             if(j== 0)
+//             {
+//                 if(selid == atoi(pRoad->GetRoadId().data()))
+//                 {
+//                     painter->setPen(Qt::green);
+//                     painter->drawEllipse(x*nfac-5,y*nfac*(-1)-5,10,10);
+//                     painter->setPen(Qt::red);
+//                 }
+//             }
+
+             switch (pg->GetGeomType()) {
+             case 0:
+                 painter->drawLine(QPoint((x-froad_xmin)*nfac,(y-froad_ymin)*nfac*(-1)),
+                                   QPoint(((x-froad_xmin) + pg->GetLength() * cos(pg->GetHdg()))*nfac,((y-froad_ymin) + pg->GetLength() * sin(pg->GetHdg()))*nfac*(-1)));
+                 break;
+
+             case 1:
+                 pSpiral = (GeometrySpiral * )pg;
+                 {
+                    int ncount = pSpiral->GetLength() * nfac;
+                    double sstep = pSpiral->GetLength()/((double)ncount);
+                    int k;
+                    double x0,y0,hdg0,s0;
+                    x0 = pSpiral->GetX();
+                    y0 = pSpiral->GetY();
+                    s0 = pSpiral->GetS();
+                    hdg0 = pSpiral->GetHdg() ;
+                    painter->setPen(Qt::red);
+                    for(k=0;k<ncount;k++)
+                    {
+                        pSpiral->GetCoords(s0+sstep*k,rel_x,rel_y,rel_hdg);
+
+                        x = rel_x - froad_xmin;
+                        y = rel_y - froad_ymin;
+                        painter->drawPoint((int)(x*nfac),(int)(y*(-1.0*nfac)));
+
+                    }
+                    painter->setPen(Qt::blue);
+                 }
+
+ //                    qDebug("spi");
+                 break;
+             case 2:
+                 {
+                 parc = (GeometryArc *)pg;
+                 R = abs(1.0/parc->GetCurvature());
+                 if(parc->GetCurvature() > 0)
+                 {
+                     x_center = pg->GetX() + R *cos(pg->GetHdg() + M_PI/2.0);
+                     y_center = pg->GetY() + R * sin(pg->GetHdg() + M_PI/2.0);
+                 }
+                 else
+                 {
+                     x_center = pg->GetX() + R *cos(pg->GetHdg() -M_PI/2.0);
+                     y_center = pg->GetY() + R * sin(pg->GetHdg() - M_PI/2.0);
+                 }
+
+                 int k;
+                 int ncount = parc->GetLength() * nfac ;
+                 double curv = parc->GetCurvature();
+                 double hdgstep;
+                 double hdg0 = parc->GetHdg();
+                 double hdgnow = parc->GetHdg();
+                 if(ncount > 0) hdgstep= (parc->GetLength()/R)/ncount;
+                 for(k=0;k<ncount;k++)
+                 {
+                     double x_draw,y_draw;
+
+                     if(curv > 0)
+                     {
+                         hdgnow =  hdg0 + k*hdgstep;
+                         x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
+                         y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
+                     }
+                     else
+                     {
+                         hdgnow = hdg0 - k * hdgstep;
+                         x_draw = x_center + R *cos(hdgnow  + M_PI/2.0);
+                         y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
+                     }
+                     x_draw = x_draw - froad_xmin;
+                     y_draw = y_draw - froad_ymin;
+                     painter->drawPoint(x_draw * nfac ,y_draw * nfac *(-1));
+                 }
+                 }
+                 break;
+             case 4:
+                 {
+                 ppp3 = (GeometryParamPoly3 * )pg;
+                 int ncount = ppp3->GetLength()* nfac;
+                 double sstep;
+                 if(ncount > 0)sstep = ppp3->GetLength()/ncount;
+                 else sstep = 10000.0;
+                 double s = 0;
+                 while(s < ppp3->GetLength())
+                 {
+                     double xtem,ytem;
+                     xtem = ppp3->GetuA() +  ppp3->GetuB() * s +  ppp3->GetuC() * s*s +  ppp3->GetuD() * s*s*s;
+                     ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
+                     x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
+                     y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
+                     x = x - froad_xmin;
+                     y = y- froad_ymin;
+                     painter->drawPoint((int)(x*nfac),(int)(y*(-1.0*nfac)));
+                     s = s+ sstep;
+                 }
+                 }
+                 break;
+             default:
+                 break;
+             }
+
+    //         painter->drawPoint((int)(x*nfac),(int)(y*(-1.0*nfac)));
+
+         }
+
+
+
+
+
+        painter->setPen(Qt::green);
+
+
+
+         painter->end();
+}
+
+void RoadEditDialog::paintEvent(QPaintEvent * painter)
+{
+    if(mpCurRoad != 0)
+    {
+        ExecPainter();
+        scene->clear();
+        scene->addPixmap(QPixmap::fromImage(*image));
+        myview->setScene(scene);
+        myview->show();
+    }
+}
+
+void RoadEditDialog::on_comboBox_Road_activated(const QString &arg1)
+{
+
+}
+
+void RoadEditDialog::on_comboBox_Road_currentIndexChanged(int index)
+{
+    Road * pRoad = mpxodr->GetRoad(index);
+    if(pRoad == 0)
+    {
+ //       QMessageBox::warning(this,"WARN","MainWindow::onClickCBRoadChange road is NULL");
+        return;
+    }
+
+    mpCurRoad = pRoad;
+
+    mnSelGeo = -1;
+
+    ui->lineEdit_roadlen->setText(QString::number(pRoad->GetRoadLength()));
+
+    ui->comboBox_Geo->clear();
+    int nsize = pRoad->GetGeometryBlockCount();
+    int i;
+    for(i=0;i<nsize;i++)
+    {
+        ui->comboBox_Geo->addItem(QString("Geo ")+QString::number(i));
+    }
+
+    update();
+}
+
+void RoadEditDialog::on_comboBox_Geo_currentIndexChanged(int index)
+{
+    if(mpCurRoad == 0 )return;
+    if(index<0)return;
+    mnSelGeo = index;
+    if(index>= mpCurRoad->GetGeometryBlockCount())return;
+    GeometryBlock * pgb = mpCurRoad->GetGeometryBlock(index);
+    RoadGeometry * pg = pgb->GetGeometryAt(0);
+    ui->lineEdit_s->setText(QString::number(pg->GetS()));
+    ui->lineEdit_x->setText(QString::number(pg->GetX()));
+    ui->lineEdit_y->setText(QString::number(pg->GetY()));
+    ui->lineEdit_hdg->setText(QString::number(pg->GetHdg()));
+    ui->lineEdit_len->setText(QString::number(pg->GetLength()));
+    if((pg->GetGeomType()>=0)&&(pg->GetGeomType()<5))
+    {
+        ui->comboBox_geotype->setCurrentIndex(pg->GetGeomType());
+    }
+}

+ 50 - 0
src/tool/map_lanetoxodr/roadeditdialog.h

@@ -0,0 +1,50 @@
+#ifndef ROADEDITDIALOG_H
+#define ROADEDITDIALOG_H
+
+#include <QDialog>
+
+#include "myview.h"
+#include "OpenDrive/OpenDrive.h"
+
+#include "ivxodrtool.h"
+
+namespace Ui {
+class RoadEditDialog;
+}
+
+class RoadEditDialog : public QDialog
+{
+    Q_OBJECT
+
+public:
+    explicit RoadEditDialog(OpenDrive * pxodr,QWidget *parent = nullptr);
+    ~RoadEditDialog();
+
+private:
+    void ExecPainter();
+
+private slots:
+   virtual void paintEvent(QPaintEvent *);
+
+    void on_comboBox_Road_activated(const QString &arg1);
+
+    void on_comboBox_Road_currentIndexChanged(int index);
+
+    void on_comboBox_Geo_currentIndexChanged(int index);
+
+private:
+    Ui::RoadEditDialog *ui;
+    OpenDrive * mpxodr;
+
+    QImage *image;
+    QPainter *painter;
+    MyView *myview;
+    QTimer *timer;
+    QGraphicsScene *scene;
+
+    Road * mpCurRoad = 0;
+
+    int mnSelGeo = -1;
+};
+
+#endif // ROADEDITDIALOG_H

+ 226 - 0
src/tool/map_lanetoxodr/roadeditdialog.ui

@@ -0,0 +1,226 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>RoadEditDialog</class>
+ <widget class="QDialog" name="RoadEditDialog">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>1260</width>
+    <height>830</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <widget class="QLabel" name="label">
+   <property name="geometry">
+    <rect>
+     <x>60</x>
+     <y>39</y>
+     <width>121</width>
+     <height>21</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Road</string>
+   </property>
+  </widget>
+  <widget class="QComboBox" name="comboBox_Road">
+   <property name="geometry">
+    <rect>
+     <x>160</x>
+     <y>30</y>
+     <width>241</width>
+     <height>41</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QComboBox" name="comboBox_Geo">
+   <property name="geometry">
+    <rect>
+     <x>230</x>
+     <y>100</y>
+     <width>161</width>
+     <height>31</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_s">
+   <property name="geometry">
+    <rect>
+     <x>520</x>
+     <y>100</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_x">
+   <property name="geometry">
+    <rect>
+     <x>770</x>
+     <y>100</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_y">
+   <property name="geometry">
+    <rect>
+     <x>1040</x>
+     <y>100</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_len">
+   <property name="geometry">
+    <rect>
+     <x>770</x>
+     <y>150</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_2">
+   <property name="geometry">
+    <rect>
+     <x>96</x>
+     <y>110</y>
+     <width>91</width>
+     <height>20</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Geometry</string>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_hdg">
+   <property name="geometry">
+    <rect>
+     <x>520</x>
+     <y>150</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_3">
+   <property name="geometry">
+    <rect>
+     <x>430</x>
+     <y>106</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>s:</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_4">
+   <property name="geometry">
+    <rect>
+     <x>680</x>
+     <y>104</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>x:</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_5">
+   <property name="geometry">
+    <rect>
+     <x>940</x>
+     <y>102</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>y:</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_6">
+   <property name="geometry">
+    <rect>
+     <x>430</x>
+     <y>154</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>hdg:</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_7">
+   <property name="geometry">
+    <rect>
+     <x>680</x>
+     <y>154</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Length:</string>
+   </property>
+  </widget>
+  <widget class="QLineEdit" name="lineEdit_roadlen">
+   <property name="geometry">
+    <rect>
+     <x>770</x>
+     <y>30</y>
+     <width>113</width>
+     <height>25</height>
+    </rect>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_8">
+   <property name="geometry">
+    <rect>
+     <x>626</x>
+     <y>38</y>
+     <width>121</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Road Length</string>
+   </property>
+  </widget>
+  <widget class="QLabel" name="label_9">
+   <property name="geometry">
+    <rect>
+     <x>940</x>
+     <y>152</y>
+     <width>67</width>
+     <height>17</height>
+    </rect>
+   </property>
+   <property name="text">
+    <string>Type</string>
+   </property>
+  </widget>
+  <widget class="QComboBox" name="comboBox_geotype">
+   <property name="geometry">
+    <rect>
+     <x>1040</x>
+     <y>149</y>
+     <width>111</width>
+     <height>31</height>
+    </rect>
+   </property>
+  </widget>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 315 - 31
src/ui/ui_ads_hmi/ADCIntelligentVehicle.cpp

@@ -291,6 +291,14 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
     ModuleFun funplantrace = std::bind(&ADCIntelligentVehicle::UpdatePlanTrace,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
     mpaplantrace = iv::modulecomm::RegisterRecvPlus("plantrace",funplantrace);
 
+    ModuleFun funplantrace_left = std::bind(&ADCIntelligentVehicle::UpdatePlanTrace_left,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
+    mpaplantrace_left = iv::modulecomm::RegisterRecvPlus("obstraceleft",funplantrace_left);
+
+    ModuleFun funplantrace_right = std::bind(&ADCIntelligentVehicle::UpdatePlanTrace_right,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
+    mpaplantrace_right = iv::modulecomm::RegisterRecvPlus("obstraceright",funplantrace_right);
+
+
+
     ModuleFun funmap = std::bind(&ADCIntelligentVehicle::UpdateMap,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
     mpa = iv::modulecomm::RegisterRecvPlus("tracemap",funmap);
     //   mpa = iv::modulecomm::RegisterRecv("tracemap",ListenTraceMap);
@@ -334,6 +342,73 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
 //    timermanualctrl->start(10);
 
     //connect(ui->lineEdit_6, SIGNAL(textEdited(const QString &)), this, SLOT(savestabuyEditinfo(const QString &)));
+
+    mpamapreq = iv::modulecomm::RegisterSend("mapreq",1000,1);
+    shareMapReqMsg();
+
+    ModuleFun funvbox = std::bind(&ADCIntelligentVehicle::UpdateVbox,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
+    mpaplantrace = iv::modulecomm::RegisterRecvPlus("vbox",funvbox);
+
+#if 1
+    ui->lcdNumber->setDigitCount(3); //设置显示几个数字
+    ui->lcdNumber->setMode(QLCDNumber::Dec);
+    ui->lcdNumber->setSegmentStyle(QLCDNumber::Flat);//设置数字字体:Outline,轮廓突出,颜色为背景色;Filled,内部填充型,颜色为黑色;Flat,平面型
+    // 设置数字颜色时要注意:  函数setSegmentStyle(QLCDNumber::Flat)中选择Flat属性,否则在setColor()设置数字颜色时不生效
+    // 设置背景色直接用setStyleSheet()函数设定就可以了。
+    //调色板
+    QPalette lcdpat = ui->lcdNumber->palette();
+    /*设置颜色,整体背景颜色 颜色蓝色,此函数的第一个参数可以设置多种。如文本、按钮按钮文字、多种*/
+    lcdpat.setColor(QPalette::Normal,QPalette::WindowText,Qt::red);
+    //设置当前窗口的调色板
+    ui->lcdNumber->setPalette(lcdpat);
+    //设置背景色
+    //ui->lcdNumber->setStyleSheet("background-color: black");
+    //ui->lcdNumber->display(QDateTime::currentDateTime().toString("yyyy-MM-dd hh:mm:ss"));
+    ui->lcdNumber->display(0);
+
+    ui->lcdNumber_2->setDigitCount(3);
+    ui->lcdNumber_2->setMode(QLCDNumber::Dec);
+    ui->lcdNumber_2->setSegmentStyle(QLCDNumber::Flat);
+    ui->lcdNumber_2->setPalette(lcdpat);
+    //ui->lcdNumber_2->setStyleSheet("background-color: black");
+    ui->lcdNumber_2->display(0);
+
+    ui->lcdNumber_3->setDigitCount(3);
+    ui->lcdNumber_3->setMode(QLCDNumber::Dec);
+    ui->lcdNumber_3->setSegmentStyle(QLCDNumber::Flat);
+    ui->lcdNumber_3->setPalette(lcdpat);
+    //ui->lcdNumber_3->setStyleSheet("background-color: black");
+    ui->lcdNumber_3->display(0);
+
+    ui->lcdNumber_4->setDigitCount(3);
+    ui->lcdNumber_4->setMode(QLCDNumber::Dec);
+    ui->lcdNumber_4->setSegmentStyle(QLCDNumber::Flat);
+    ui->lcdNumber_4->setPalette(lcdpat);
+    //ui->lcdNumber_4->setStyleSheet("background-color: black");
+    ui->lcdNumber_4->display(0);
+#endif
+    // 新建qimage
+    // QImage img,img2,img3,img4;
+    // 加载图片
+    img.load(":/light_image/diaotou-black.png");
+    img = img.scaled(66,66,Qt::IgnoreAspectRatio);
+    ui->label_38->setPixmap(QPixmap::fromImage(img));
+    img2.load(":/light_image/zuoguai-black.png");
+    img2 = img2.scaled(66,66,Qt::IgnoreAspectRatio);
+    ui->label_33->setPixmap(QPixmap::fromImage(img2));
+    img3.load(":/light_image/zhixing-black.png");
+    img3 = img3.scaled(66,66,Qt::IgnoreAspectRatio);
+    ui->label_35->setPixmap(QPixmap::fromImage(img3));
+    img4.load(":/light_image/youguai-black.png");
+    img4 = img4.scaled(66,66,Qt::IgnoreAspectRatio);
+    ui->label_32->setPixmap(QPixmap::fromImage(img4));
+
+    #if 1
+    mTimerState1.setTimerType(Qt::PreciseTimer);    //设置计时器的精确程度    Qt::PreciseTimer值为0,含义:精确定时器试图保持毫秒精度
+    connect(&mTimerState1,SIGNAL(timeout()),this,SLOT(onStateTimer1()));//广播发送UDP数据报
+    mTimerState1.start(100);   //定时100ms
+    #endif
+
 }
 
 /**
@@ -345,15 +420,7 @@ void ADCIntelligentVehicle::savestabuyEditinfo(const QString &txt)
     //ServiceControlStatus.set_accelerate((float)txt.toDouble());
 }
 
-/**
- * @brief ADCIntelligentVehicle::gps_collector_exit
- */
-void ADCIntelligentVehicle::gps_collector_exit()
-{
-    is_gps_collector_run = false;
-    gps_connect.disconnect();
-    delete gps_collector;
-}
+
 
 /**
  * @brief ADCIntelligentVehicle::timeoutslot
@@ -820,11 +887,18 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         navigation_data = m_navigation_data;
         mMutexNavi.unlock();
 
-        std::vector<iv::Point2D> myplan;
+        std::vector<iv::Point2D> myplan,myplan_left,myplan_right;
         mMutexPlan.lock();
         myplan = m_plan;
         mMutexPlan.unlock();
 
+        mMutexPlan_left.lock();
+        myplan_left = m_plan_left;
+        mMutexPlan_left.unlock();
+
+        mMutexPlan_right.lock();
+        myplan_right = m_plan_right;
+        mMutexPlan_right.unlock();
 //        std::cout<<"plan size is "<<myplan.size()<<std::endl;
 
 
@@ -936,10 +1010,17 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
             y0[i] = xx * sin(lng[0] * PI / 180) + yy * cos(lng[0] * PI / 180);
             k1 = sin((90 + (lng[i] - lng[0])) * PI / 180);
             k2 = cos((90 + (lng[i] - lng[0])) * PI / 180);
+            #if 0
             x1[i] = x0[i] + k1 * 5;
             y1[i] = y0[i] + k2 * 5;
             x2[i] = x0[i] - k1 * 5;
             y2[i] = y0[i] - k2 * 5;
+            #else
+            x1[i] = x0[i] + k1 * 1.75;
+            y1[i] = y0[i] + k2 * 1.75;
+            x2[i] = x0[i] - k1 * 1.75;
+            y2[i] = y0[i] - k2 * 1.75;
+            #endif
         }
 
         double kx_small = (double)(600) / (abs(y_max - y_min));//x轴的系数
@@ -983,13 +1064,45 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         QPointF tracePoints[myplan.size()];
         if(myplan.size()>2)
         {
-        for(int i=0;i<(myplan.size()-1);i++){
-            tracePoints[i].setX((float)(450+myplan[i].x*kx));
-            tracePoints[i].setY((float)(700-myplan[i].y*ky));
-            painter->drawLine((float)(450+myplan[i].x*kx),(float)(700-myplan[i].y*ky),
-                              (float)(450+myplan[i+1].x*kx),(float)(700-myplan[i+1].y*ky));
+            for(int i=0;i<(myplan.size()-1);i++)
+            {
+                tracePoints[i].setX((float)(450+myplan[i].x*kx));
+                tracePoints[i].setY((float)(700-myplan[i].y*ky));
+                painter->drawLine((float)(450+myplan[i].x*kx),(float)(700-myplan[i].y*ky),
+                                  (float)(450+myplan[i+1].x*kx),(float)(700-myplan[i+1].y*ky));
+            }
+        }
+
+        penPoint.setColor(Qt::blue);
+        penPoint.setWidth(2);
+        painter->setPen(penPoint);
+        QPointF tracePoints_left[myplan_left.size()];
+        if(myplan_left.size()>2)
+        {
+            for(int i=0;i<(myplan_left.size()-1);i++)
+            {
+                tracePoints_left[i].setX((float)(450+myplan_left[i].x*kx));
+                tracePoints_left[i].setY((float)(700-myplan_left[i].y*ky));
+                painter->drawLine((float)(450+myplan_left[i].x*kx),(float)(700-myplan_left[i].y*ky),
+                                  (float)(450+myplan_left[i+1].x*kx),(float)(700-myplan_left[i+1].y*ky));
+            }
         }
+
+        penPoint.setColor(Qt::blue);
+        penPoint.setWidth(2);
+        painter->setPen(penPoint);
+        QPointF tracePoints_right[myplan_right.size()];
+        if(myplan_right.size()>2)
+        {
+            for(int i=0;i<(myplan_right.size()-1);i++)
+            {
+                tracePoints_right[i].setX((float)(450+myplan_right[i].x*kx));
+                tracePoints_right[i].setY((float)(700-myplan_right[i].y*ky));
+                painter->drawLine((float)(450+myplan_right[i].x*kx),(float)(700-myplan_right[i].y*ky),
+                                  (float)(450+myplan_right[i+1].x*kx),(float)(700-myplan_right[i+1].y*ky));
+            }
         }
+
  //       painter->drawPolyline(tracePoints,myplan.size());
         // draw plan trace end
 /////////////////////////////////////apollo add car icon  20200409
@@ -1161,22 +1274,6 @@ void ADCIntelligentVehicle::on_hs_wheel_angle_valueChanged(int value) {
     //ServiceControlStatus.set_wheel_angle((float)value);
 }
 
-/**
- * @brief ADCIntelligentVehicle::on_pushButton_2_clicked
- */
-void ADCIntelligentVehicle::on_pushButton_2_clicked(){
-    if(is_gps_collector_run == false)
-    {
-        gps_collector = new GPS_Collect;
-        gps_connect = gps_collector->gps_collector_close.connect(boost::bind(&ADCIntelligentVehicle::gps_collector_exit,this));
-        is_gps_collector_run = true;
-        gps_collector->show();
-    }
-    else
-    {
-        QMessageBox::information(NULL, QStringLiteral("提示"), QStringLiteral("程序已打开"));
-    }
-}
 
 /**
  * @brief ADCIntelligentVehicle::on_pushButton_3_clicked
@@ -1296,6 +1393,37 @@ void ADCIntelligentVehicle::UpdatePlanTrace(const char * strdata,const unsigned
     mMutexPlan.unlock();
 }
 
+void ADCIntelligentVehicle::UpdatePlanTrace_left(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    mMutexPlan_left.lock();
+    m_plan_left.clear();
+    int nplansize = nSize/sizeof(iv::Point2D);
+    int npsize = sizeof(iv::Point2D);
+    int i;
+    for(i=0;i<nplansize;i++)
+    {
+        iv::Point2D x;
+        memcpy(&x,strdata + i*npsize,npsize);
+        m_plan_left.push_back(x);
+    }
+    mMutexPlan_left.unlock();
+}
+
+void ADCIntelligentVehicle::UpdatePlanTrace_right(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    mMutexPlan_right.lock();
+    m_plan_right.clear();
+    int nplansize = nSize/sizeof(iv::Point2D);
+    int npsize = sizeof(iv::Point2D);
+    int i;
+    for(i=0;i<nplansize;i++)
+    {
+        iv::Point2D x;
+        memcpy(&x,strdata + i*npsize,npsize);
+        m_plan_right.push_back(x);
+    }
+    mMutexPlan_right.unlock();
+}
 
 
 /**
@@ -1866,3 +1994,159 @@ void ADCIntelligentVehicle::on_pb_v2xEn_clicked()
     gIvlog->info("hmi","v2x enable:%d", mv2xStEn);
     UpdateV2xStEn(mv2xStEn);
 }
+
+
+void ADCIntelligentVehicle::shareMapReqMsg()
+{
+
+    iv::map::mapreq x;
+    x.set_maptype(1);
+    int nsize = x.ByteSize();
+    char * str = new char[nsize];
+    if(x.SerializeToArray(str,nsize))
+    {
+        iv::modulecomm::ModuleSendMsg(mpamapreq,str,nsize);
+    }
+    else
+    {
+        std::cout<<"iv::map::mapreq serialize error."<<std::endl;
+    }
+    std::cout<<"iv::map::mapreq serialize OK."<<std::endl;
+    delete str;
+}
+
+void ADCIntelligentVehicle::UpdateVbox(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    iv::vbox::vbox xvbox;
+    if(!xvbox.ParseFromArray(strdata,nSize))
+    {
+        gIvlog->warn("ADCIntelligentVehicle::UpdateVbox parse errror. nSize is %d",nSize);
+        return;
+    }
+    ServiceCarStatus.st_straight = xvbox.st_straight();
+    ServiceCarStatus.st_left = xvbox.st_left();
+    ServiceCarStatus.st_right = xvbox.st_right();
+    ServiceCarStatus.st_turn = xvbox.st_turn();
+    ServiceCarStatus.time_straight = xvbox.time_straight();
+    ServiceCarStatus.time_left = xvbox.time_left();
+    ServiceCarStatus.time_right = xvbox.time_right();
+    ServiceCarStatus.time_turn = xvbox.time_turn();
+
+
+}
+
+void ADCIntelligentVehicle::onStateTimer1()
+{
+    ui->lcdNumber->display((int)ServiceCarStatus.time_turn);
+    ui->lcdNumber_2->display((int)ServiceCarStatus.time_left);
+    ui->lcdNumber_3->display((int)ServiceCarStatus.time_straight);
+    ui->lcdNumber_4->display((int)ServiceCarStatus.time_right);
+    switch (ServiceCarStatus.st_turn) {
+    case 0:
+        img.load(":/light_image/diaotou-black.png");
+        img = img.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_38->setPixmap(QPixmap::fromImage(img));
+        break;
+    case 1:
+        img.load(":/light_image/diaotou-green.png");
+        img = img.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_38->setPixmap(QPixmap::fromImage(img));
+        break;
+    case 2:
+        img.load(":/light_image/diaotou-red.png");
+        img = img.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_38->setPixmap(QPixmap::fromImage(img));
+        break;
+    case 3:
+        img.load(":/light_image/diaotou-yellow.png");
+        img = img.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_38->setPixmap(QPixmap::fromImage(img));
+        break;
+    default:
+        img.load(":/light_image/diaotou-black.png");
+        img = img.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_38->setPixmap(QPixmap::fromImage(img));
+        break;
+    }
+    switch (ServiceCarStatus.st_left) {
+    case 0:
+        img2.load(":/light_image/zuoguai-black.png");
+        img2 = img2.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_33->setPixmap(QPixmap::fromImage(img2));
+        break;
+    case 1:
+        img2.load(":/light_image/zuoguai-green.png");
+        img2 = img2.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_33->setPixmap(QPixmap::fromImage(img2));
+        break;
+    case 2:
+        img2.load(":/light_image/zuoguai-red.png");
+        img2 = img2.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_33->setPixmap(QPixmap::fromImage(img2));
+        break;
+    case 3:
+        img2.load(":/light_image/zuoguai-yellow.png");
+        img2 = img2.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_33->setPixmap(QPixmap::fromImage(img2));
+        break;
+    default:
+        img2.load(":/light_image/zuoguai-black.png");
+        img2 = img2.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_33->setPixmap(QPixmap::fromImage(img2));
+        break;
+    }
+    switch (ServiceCarStatus.st_straight) {
+    case 0:
+        img3.load(":/light_image/zhixing-black.png");
+        img3 = img3.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_35->setPixmap(QPixmap::fromImage(img3));
+        break;
+    case 1:
+        img3.load(":/light_image/zhixing-green.png");
+        img3 = img3.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_35->setPixmap(QPixmap::fromImage(img3));
+        break;
+    case 2:
+        img3.load(":/light_image/zhixing-red.png");
+        img3 = img3.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_35->setPixmap(QPixmap::fromImage(img3));
+        break;
+    case 3:
+        img3.load(":/light_image/zhixing-yellow.png");
+        img3 = img3.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_35->setPixmap(QPixmap::fromImage(img3));
+        break;
+    default:
+        img3.load(":/light_image/zhixing-black.png");
+        img3 = img3.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_35->setPixmap(QPixmap::fromImage(img3));
+        break;
+    }
+    switch (ServiceCarStatus.st_right) {
+    case 0:
+        img4.load(":/light_image/youguai-black.png");
+        img4 = img4.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_32->setPixmap(QPixmap::fromImage(img4));
+        break;
+    case 1:
+        img4.load(":/light_image/youguai-green.png");
+        img4 = img4.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_32->setPixmap(QPixmap::fromImage(img4));
+        break;
+    case 2:
+        img4.load(":/light_image/youguai-red.png");
+        img4 = img4.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_32->setPixmap(QPixmap::fromImage(img4));
+        break;
+    case 3:
+        img4.load(":/light_image/youguai-yellow.png");
+        img4 = img4.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_32->setPixmap(QPixmap::fromImage(img4));
+        break;
+    default:
+        img4.load(":/light_image/youguai-black.png");
+        img4 = img4.scaled(66,66,Qt::IgnoreAspectRatio);
+        ui->label_32->setPixmap(QPixmap::fromImage(img4));
+        break;
+    }
+}

+ 24 - 8
src/ui/ui_ads_hmi/ADCIntelligentVehicle.h

@@ -9,7 +9,6 @@
 #include "ui_ADCIntelligentVehicle.h"
 //#include <decition/brain.h>
 //#include <control/can.h>
-#include "gps_collect.h"
 #include "look.h"
 #include <common/car_status.h>
 #include <qtimer.h>
@@ -62,6 +61,9 @@
 #include "canstate.pb.h"
 #include "v2x.pb.h"
 #include "ivlog.h"
+#include "mapreq.pb.h"
+#include "vbox.pb.h"
+
 extern iv::Ivlog * gIvlog;
 
 #define USE_PAD_CTRL
@@ -144,7 +146,6 @@ class ADCIntelligentVehicle : public QMainWindow
 
 public:
     explicit ADCIntelligentVehicle(QWidget *parent = 0);
-    void gps_collector_exit();
     //~ADCIntelligentVehicle();
 
 public slots:
@@ -164,7 +165,7 @@ public slots:
     void on_hs_accelerate_percent_valueChanged(int value);	//响应油门改变
     void on_hs_wheel_angle_valueChanged(int value);		//响应方向盘改变
 
-    void on_pushButton_2_clicked();
+//    void on_pushButton_2_clicked();    //打开地图采集器
     void on_pushButton_3_clicked();
     void on_pushButton_4_clicked();
 
@@ -175,6 +176,7 @@ public slots:
 
     void onRecvUDP();
     void onStateTimer();
+    void onStateTimer1();
 protected:
 
     void keyPressEvent(QKeyEvent *event) Q_DECL_OVERRIDE;// 加/减键进行缩放
@@ -211,10 +213,7 @@ private:
     bool is_3 = false;
     bool is_speed_control_mode_enable_ = false;
     bool is_show_enable = false;
-    bool is_gps_collector_run = false;
 
-    boost::signals2::connection gps_connect;
-    GPS_Collect *gps_collector;
     Look_decition *look_decition;
     Mobileye_info *mobileye_info;
     Qt::MouseButton m_translateButton;  // 平移按钮
@@ -317,10 +316,14 @@ private:
 /***********20200509****************/
 public:
     void UpdatePlanTrace(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
-    std::vector<iv::Point2D> m_plan;
-    QMutex mMutexPlan;
+    void UpdatePlanTrace_left(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+    void UpdatePlanTrace_right(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+    std::vector<iv::Point2D> m_plan,m_plan_left,m_plan_right;
+    QMutex mMutexPlan,mMutexPlan_left,mMutexPlan_right;
 private:
     void * mpaplantrace;
+    void * mpaplantrace_left;
+    void * mpaplantrace_right;
 /**************************/
 private:
     void * mpaLidar;
@@ -335,6 +338,19 @@ private:
     iv::Ivlog * mpivlog;
 
     //     iv::platform::Client mplatform_client;
+
+public:
+    void * mpamapreq;   //请求地图
+    void shareMapReqMsg();
+
+private:
+    void * mpaVbox;
+public:
+    void UpdateVbox(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+
+private:
+    QImage img,img2,img3,img4;
+    QTimer mTimerState1;
 };
 
 

+ 16 - 0
src/ui/ui_ads_hmi/ADCIntelligentVehicle.qrc

@@ -9,5 +9,21 @@
     </qresource>
     <qresource prefix="/">
         <file>adsuiicon.png</file>
+        <file>light_image/zuoguai-yellow.png</file>
+        <file>light_image/zuoguai-red.png</file>
+        <file>light_image/zuoguai-green.png</file>
+        <file>light_image/zuoguai-black.png</file>
+        <file>light_image/zhixing-yellow.png</file>
+        <file>light_image/zhixing-red.png</file>
+        <file>light_image/zhixing-green.png</file>
+        <file>light_image/zhixing-black.png</file>
+        <file>light_image/youguai-yellow.png</file>
+        <file>light_image/youguai-red.png</file>
+        <file>light_image/youguai-green.png</file>
+        <file>light_image/youguai-black.png</file>
+        <file>light_image/diaotou-yellow.png</file>
+        <file>light_image/diaotou-red.png</file>
+        <file>light_image/diaotou-green.png</file>
+        <file>light_image/diaotou-black.png</file>
     </qresource>
 </RCC>

+ 220 - 28
src/ui/ui_ads_hmi/ADCIntelligentVehicle.ui

@@ -104,8 +104,8 @@
      <widget class="QGroupBox" name="groupBox_2">
       <property name="geometry">
        <rect>
-        <x>120</x>
-        <y>440</y>
+        <x>110</x>
+        <y>310</y>
         <width>261</width>
         <height>191</height>
        </rect>
@@ -178,8 +178,8 @@
      <widget class="QGroupBox" name="groupBox_3">
       <property name="geometry">
        <rect>
-        <x>520</x>
-        <y>440</y>
+        <x>470</x>
+        <y>310</y>
         <width>221</width>
         <height>191</height>
        </rect>
@@ -355,7 +355,7 @@
       <property name="geometry">
        <rect>
         <x>150</x>
-        <y>200</y>
+        <y>90</y>
         <width>541</width>
         <height>81</height>
        </rect>
@@ -377,7 +377,7 @@
       <property name="geometry">
        <rect>
         <x>280</x>
-        <y>290</y>
+        <y>220</y>
         <width>281</width>
         <height>21</height>
        </rect>
@@ -398,6 +398,219 @@
        <string>Start A Journey Of Autopilot</string>
       </property>
      </widget>
+     <widget class="QGroupBox" name="groupBox_11">
+      <property name="geometry">
+       <rect>
+        <x>110</x>
+        <y>530</y>
+        <width>581</width>
+        <height>261</height>
+       </rect>
+      </property>
+      <property name="font">
+       <font>
+        <family>AR PL UKai CN</family>
+       </font>
+      </property>
+      <property name="styleSheet">
+       <string notr="true">color: rgb(238, 238, 236);</string>
+      </property>
+      <property name="title">
+       <string>V2X红绿灯</string>
+      </property>
+      <widget class="QLabel" name="label_37">
+       <property name="geometry">
+        <rect>
+         <x>430</x>
+         <y>190</y>
+         <width>54</width>
+         <height>26</height>
+        </rect>
+       </property>
+       <property name="styleSheet">
+        <string notr="true">color: rgb(238, 238, 236);</string>
+       </property>
+       <property name="text">
+        <string>右转</string>
+       </property>
+      </widget>
+      <widget class="QLCDNumber" name="lcdNumber_4">
+       <property name="geometry">
+        <rect>
+         <x>420</x>
+         <y>140</y>
+         <width>64</width>
+         <height>33</height>
+        </rect>
+       </property>
+       <property name="styleSheet">
+        <string notr="true"/>
+       </property>
+       <property name="digitCount">
+        <number>3</number>
+       </property>
+       <property name="segmentStyle">
+        <enum>QLCDNumber::Flat</enum>
+       </property>
+      </widget>
+      <widget class="QLCDNumber" name="lcdNumber_3">
+       <property name="geometry">
+        <rect>
+         <x>310</x>
+         <y>140</y>
+         <width>64</width>
+         <height>33</height>
+        </rect>
+       </property>
+       <property name="styleSheet">
+        <string notr="true"/>
+       </property>
+       <property name="digitCount">
+        <number>3</number>
+       </property>
+       <property name="segmentStyle">
+        <enum>QLCDNumber::Flat</enum>
+       </property>
+      </widget>
+      <widget class="QLCDNumber" name="lcdNumber">
+       <property name="geometry">
+        <rect>
+         <x>80</x>
+         <y>140</y>
+         <width>64</width>
+         <height>33</height>
+        </rect>
+       </property>
+       <property name="styleSheet">
+        <string notr="true"/>
+       </property>
+       <property name="digitCount">
+        <number>3</number>
+       </property>
+       <property name="segmentStyle">
+        <enum>QLCDNumber::Flat</enum>
+       </property>
+      </widget>
+      <widget class="QLabel" name="label_38">
+       <property name="geometry">
+        <rect>
+         <x>80</x>
+         <y>60</y>
+         <width>66</width>
+         <height>66</height>
+        </rect>
+       </property>
+       <property name="text">
+        <string>TextLabel</string>
+       </property>
+      </widget>
+      <widget class="QLabel" name="label_31">
+       <property name="geometry">
+        <rect>
+         <x>320</x>
+         <y>190</y>
+         <width>54</width>
+         <height>26</height>
+        </rect>
+       </property>
+       <property name="styleSheet">
+        <string notr="true">color: rgb(238, 238, 236);</string>
+       </property>
+       <property name="text">
+        <string>直行</string>
+       </property>
+      </widget>
+      <widget class="QLCDNumber" name="lcdNumber_2">
+       <property name="geometry">
+        <rect>
+         <x>190</x>
+         <y>140</y>
+         <width>64</width>
+         <height>33</height>
+        </rect>
+       </property>
+       <property name="styleSheet">
+        <string notr="true"/>
+       </property>
+       <property name="digitCount">
+        <number>3</number>
+       </property>
+       <property name="segmentStyle">
+        <enum>QLCDNumber::Flat</enum>
+       </property>
+      </widget>
+      <widget class="QLabel" name="label_34">
+       <property name="geometry">
+        <rect>
+         <x>90</x>
+         <y>190</y>
+         <width>54</width>
+         <height>26</height>
+        </rect>
+       </property>
+       <property name="styleSheet">
+        <string notr="true">color: rgb(238, 238, 236);</string>
+       </property>
+       <property name="text">
+        <string>掉头</string>
+       </property>
+      </widget>
+      <widget class="QLabel" name="label_32">
+       <property name="geometry">
+        <rect>
+         <x>420</x>
+         <y>60</y>
+         <width>66</width>
+         <height>66</height>
+        </rect>
+       </property>
+       <property name="text">
+        <string>TextLabel</string>
+       </property>
+      </widget>
+      <widget class="QLabel" name="label_33">
+       <property name="geometry">
+        <rect>
+         <x>190</x>
+         <y>60</y>
+         <width>66</width>
+         <height>66</height>
+        </rect>
+       </property>
+       <property name="text">
+        <string>TextLabel</string>
+       </property>
+      </widget>
+      <widget class="QLabel" name="label_35">
+       <property name="geometry">
+        <rect>
+         <x>310</x>
+         <y>60</y>
+         <width>66</width>
+         <height>66</height>
+        </rect>
+       </property>
+       <property name="text">
+        <string>TextLabel</string>
+       </property>
+      </widget>
+      <widget class="QLabel" name="label_36">
+       <property name="geometry">
+        <rect>
+         <x>200</x>
+         <y>190</y>
+         <width>54</width>
+         <height>26</height>
+        </rect>
+       </property>
+       <property name="styleSheet">
+        <string notr="true">color: rgb(238, 238, 236);</string>
+       </property>
+       <property name="text">
+        <string>左转</string>
+       </property>
+      </widget>
+     </widget>
     </widget>
     <widget class="QWidget" name="page_1">
      <widget class="QLabel" name="lb_current_speed_big">
@@ -748,27 +961,6 @@ background-color: rgb(85, 87, 83);</string>
        </property>
       </widget>
      </widget>
-     <widget class="QPushButton" name="pushButton_2">
-      <property name="geometry">
-       <rect>
-        <x>10</x>
-        <y>490</y>
-        <width>151</width>
-        <height>31</height>
-       </rect>
-      </property>
-      <property name="font">
-       <font>
-        <family>AR PL UKai CN</family>
-       </font>
-      </property>
-      <property name="styleSheet">
-       <string notr="true">color: rgb(238, 238, 236);</string>
-      </property>
-      <property name="text">
-       <string>地图采集器</string>
-      </property>
-     </widget>
      <widget class="QPushButton" name="pushButton_3">
       <property name="geometry">
        <rect>
@@ -2065,7 +2257,7 @@ p, li { white-space: pre-wrap; }
      <x>0</x>
      <y>0</y>
      <width>1900</width>
-     <height>22</height>
+     <height>28</height>
     </rect>
    </property>
   </widget>

+ 12 - 0
src/ui/ui_ads_hmi/common/car_status.h

@@ -87,6 +87,18 @@ public:
     iv::GPSData location;		//当前车辆位置
     boost::array<iv::ObstacleBasic, 64> obs_radar;//毫米波雷达的障碍物数据
     iv::ultrasonic_obs multrasonic_obs;
+
+    /*Vbox红绿灯*/
+    uint32_t st_straight;
+    uint32_t st_left;
+    uint32_t st_right;
+    uint32_t st_turn;
+    uint32_t time_straight;
+    uint32_t time_left;
+    uint32_t time_right;
+    uint32_t time_turn;
+
+
 };
 typedef boost::serialization::singleton<iv::CarStatus> CarStatusSingleton;//非线程安全,注意多线程加锁,单例模式
 }

+ 0 - 1131
src/ui/ui_ads_hmi/gps_collect.cpp

@@ -1,1131 +0,0 @@
-#include "gps_collect.h"
-
-// General constants.
-#define NOUTPUT_PACKET_LENGTH  (72)       //!< NCom packet length.
-#define NCOM_SYNC           (0xE7)        //!< NCom sync byte.
-#define PKT_PERIOD          (0.01)        //!< 10ms updates.
-#define TIME2SEC            (1e-3)        //!< Units of 1 ms.
-#define FINETIME2SEC        (4e-6)        //!< Units of 4 us.
-#define TIMECYCLE           (60000)       //!< Units of TIME2SEC (i.e. 60 seconds).
-#define WEEK2CYCLES         (10080)       //!< Time cycles in a week.
-#define ACC2MPS2            (1e-4)        //!< Units of 0.1 mm/s^2.
-#define RATE2RPS            (1e-5)        //!< Units of 0.01 mrad/s.
-#define VEL2MPS             (1e-4)        //!< Units of 0.1 mm/s.
-#define ANG2RAD             (1e-6)        //!< Units of 0.001 mrad.
-#define INNFACTOR           (0.1)         //!< Resolution of 0.1.
-#define POSA2M              (1e-3)        //!< Units of 1 mm.
-#define VELA2MPS            (1e-3)        //!< Units of 1 mm/s.
-#define ANGA2RAD            (1e-5)        //!< Units of 0.01 mrad.
-#define GB2RPS              (5e-6)        //!< Units of 0.005 mrad/s.
-#define AB2MPS2             (1e-4)        //!< Units of 0.1 mm/s^2.
-#define GSFACTOR            (1e-6)        //!< Units of 1 ppm.
-#define ASFACTOR            (1e-6)        //!< Units of 1 ppm.
-#define GBA2RPS             (1e-6)        //!< Units of 0.001 mrad/s.
-#define ABA2MPS2            (1e-5)        //!< Units of 0.01 mm/s^2.
-#define GSAFACTOR           (1e-6)        //!< Units of 1 ppm.
-#define ASAFACTOR           (1e-6)        //!< Units of 1 ppm.
-#define GPSPOS2M            (1e-3)        //!< Units of 1 mm.
-#define GPSATT2RAD          (1e-4)        //!< Units of 0.1 mrad.
-#define GPSPOSA2M           (1e-4)        //!< Units of 0.1 mm.
-#define GPSATTA2RAD         (1e-5)        //!< Units of 0.01 mrad.
-#define INNFACTOR           (0.1)         //!< Resolution of 0.1.
-#define DIFFAGE2SEC         (1e-2)        //!< Units of 0.01 s.
-#define REFPOS2M            (0.0012)      //!< Units of 1.2 mm.
-#define REFANG2RAD          (1e-4)        //!< Units of 0.1 mrad.
-#define OUTPOS2M            (1e-3)        //!< Units of 1 mm.
-#define ZVPOS2M             (1e-3)        //!< Units of 1 mm.
-#define ZVPOSA2M            (1e-4)        //!< Units of 0.1 mm.
-#define NSPOS2M             (1e-3)        //!< Units of 1 mm.
-#define NSPOSA2M            (1e-4)        //!< Units of 0.1 mm.
-#define ALIGN2RAD           (1e-4)        //!< Units of 0.1 mrad.
-#define ALIGNA2RAD          (1e-5)        //!< Units of 0.01 mrad.
-#define SZVDELAY2S          (1.0)         //!< Units of 1.0 s.
-#define SZVPERIOD2S         (0.1)         //!< Units of 0.1 s.
-#define TOPSPEED2MPS        (0.5)         //!< Units of 0.5 m/s.
-#define NSDELAY2S           (0.1)         //!< Units of 0.1 s.
-#define NSPERIOD2S          (0.02)        //!< Units of 0.02 s.
-#define NSACCEL2MPS2        (0.04)        //!< Units of 0.04 m/s^2.
-#define NSSPEED2MPS         (0.1)         //!< Units of 0.1 m/s.
-#define NSRADIUS2M          (0.5)         //!< Units of 0.5 m.
-#define INITSPEED2MPS       (0.1)         //!< Units of 0.1 m/s.
-#define HLDELAY2S           (1.0)         //!< Units of 1.0 s.
-#define HLPERIOD2S          (0.1)         //!< Units of 0.1 s.
-#define STATDELAY2S         (1.0)         //!< Units of 1.0 s.
-#define STATSPEED2MPS       (0.01)        //!< Units of 1.0 cm/s.
-#define WSPOS2M             (1e-3)        //!< Units of 1 mm.
-#define WSPOSA2M            (1e-4)        //!< Units of 0.1 mm.
-#define WSSF2PPM            (0.1)         //!< Units of 0.1 pulse per metre (ppm).
-#define WSSFA2PC            (0.002)       //!< Units of 0.002% of scale factor.
-#define WSDELAY2S           (0.1)         //!< Units of 0.1 s.
-#define WSNOISE2CNT         (0.1)         //!< Units of 0.1 count for wheel speed noise.
-#define UNDUL2M             (0.005)       //!< Units of 5 mm.
-#define DOPFACTOR           (0.1)         //!< Resolution of 0.1.
-#define OMNISTAR_MIN_FREQ   (1.52e9)      //!< (Hz) i.e. 1520.0 MHz.
-#define OMNIFREQ2HZ         (1000.0)      //!< Resolution of 1 kHz.
-#define SNR2DB              (0.2)         //!< Resolution of 0.2 dB.
-#define LTIME2SEC           (1.0)         //!< Resolution of 1.0 s.
-#define TEMPK_OFFSET        (203.15)      //!< Temperature offset in degrees K.
-#define ABSZERO_TEMPC       (-273.15)     //!< Absolute zero (i.e. 0 deg K) in deg C.
-
-// For more accurate and complete local coordinates
-#define FINEANG2RAD (1.74532925199433e-9) //!< Units of 0.1 udeg.
-#define ALT2M               (1e-3)        //!< Units of 1 mm.
-
-// For GPS supply voltage
-#define SUPPLYV2V           (0.1)         //!< Units of 0.1 V.
-
-// Mathematical constant definitions
-#ifndef M_PI
-#define M_PI (3.1415926535897932384626433832795)  //!< Pi.
-#endif
-#define DEG2RAD             (M_PI/180.0)  //!< Convert degrees to radians.
-#define RAD2DEG             (180.0/M_PI)  //!< Convert radians to degrees.
-#define POS_INT_24          (8388607)     //!< Maximum value of a two's complement 24 bit integer.
-#define NEG_INT_24          (-8388607)    //!< Minimum value of a two's complement 24 bit integer.
-#define INV_INT_24          (-8388608)    //!< Represents an invalid two's complement 24 bit integer.
-
-#define NCOM_COUNT_TOO_OLD  (150)         //!< Cycle counter for data too old.
-#define NCOM_STDCNT_MAX     (0xFF)        //!< Definition for the RTBNS accuracy counter.
-#define MIN_HORZ_SPEED      (0.07)        //!< 0.07 m/s hold distance.
-#define MIN_VERT_SPEED      (0.07)        //!< 0.07 m/s hold distance.
-#define SPEED_HOLD_FACTOR   (2.0)         //!< Hold distance when speed within 2 sigma of 0.
-#define MINUTES_IN_WEEK     (10080)       //!< Number of minutes in a week.
-
-// OmniStar status definitions
-#define NCOM_OMNI_STATUS_UNKNOWN      (0xFF)
-#define NCOM_OMNI_STATUS_VBSEXPIRED   (0x01)
-#define NCOM_OMNI_STATUS_VBSREGION    (0x02)
-#define NCOM_OMNI_STATUS_VBSNOBASE    (0x04)
-#define NCOM_OMNI_STATUS_HPEXPIRED    (0x08)
-#define NCOM_OMNI_STATUS_HPREGION     (0x10)
-#define NCOM_OMNI_STATUS_HPNOBASE     (0x20)
-#define NCOM_OMNI_STATUS_HPNOCONVERGE (0x40)
-#define NCOM_OMNI_STATUS_HPKEYINVALID (0x80)
-
-// GPS hardware status definitions
-#define NCOM_GPS_ANT_STATUS_BITMASK   (0x03)
-#define NCOM_GPS_ANT_STATUS_DONTKNOW  (0x03)
-#define NCOM_GPS_ANT_STATUS_BITSHIFT  (0)
-#define NCOM_GPS_ANT_POWER_BITMASK    (0x0C)
-#define NCOM_GPS_ANT_POWER_DONTKNOW   (0x0C)
-#define NCOM_GPS_ANT_POWER_BITSHIFT   (2)
-
-// GPS feature set 1 definitions
-#define NCOM_GPS_FEATURE_PSRDIFF      (0x01)
-#define NCOM_GPS_FEATURE_SBAS         (0x02)
-#define NCOM_GPS_FEATURE_OMNIVBS      (0x08)
-#define NCOM_GPS_FEATURE_OMNIHP       (0x10)
-#define NCOM_GPS_FEATURE_L1DIFF       (0x20)
-#define NCOM_GPS_FEATURE_L1L2DIFF     (0x40)
-
-// GPS feature set 2 definitions
-#define NCOM_GPS_FEATURE_GLONASS      (0x01)
-#define NCOM_GPS_FEATURE_GALILEO      (0x02)
-#define NCOM_GPS_FEATURE_RAWRNG       (0x04)
-#define NCOM_GPS_FEATURE_RAWDOP       (0x08)
-#define NCOM_GPS_FEATURE_RAWL1        (0x10)
-#define NCOM_GPS_FEATURE_RAWL2        (0x20)
-#define NCOM_GPS_FEATURE_RAWL5        (0x40)
-
-// GPS feature valid definition
-#define NCOM_GPS_FEATURE_VALID        (0x80)
-
-// The start of GPS time in a time_t style. In this version it is a constant, but this constant assumes that
-// the local machine uses 00:00:00 01/01/1970 as its Epoch time. If your machine is different then you need to
-// convert 00:00:00 06/01/1980 in to the local machine's time_t time.
-#define GPS_TIME_START_TIME_T         (315964800)
-
-// Second order filter class
-#define INPUT_JITTER_TOLERANCE     (0.01)  // i.e. 1%
-
-
-/*index*/
-#define		PI_SYNC             0
-#define		PI_TIME             1
-#define		PI_ACCEL_X          3
-#define		PI_ACCEL_Y          6
-#define		PI_ACCEL_Z          9
-#define		PI_ANG_RATE_X      12
-#define		PI_ANG_RATE_Y      15
-#define		PI_ANG_RATE_Z      18
-#define		PI_INS_NAV_MODE    21
-#define		PI_CHECKSUM_1      22
-#define		PI_POS_LAT         23
-#define		PI_POS_LON         31
-#define		PI_POS_ALT         39
-#define		PI_VEL_N           43
-#define		PI_VEL_E           46
-#define		PI_VEL_D           49
-#define		PI_ORIEN_H         52
-#define		PI_ORIEN_P         55
-#define		PI_ORIEN_R         58
-#define		PI_CHECKSUM_2      61
-#define		PI_CHANNEL_INDEX   62
-#define		PI_CHANNEL_STATUS  63
-#define		PI_SAT_NUM		   67
-#define		PI_RTK_STATUS	   68
-#define		PI_CHECKSUM_3      71
-
-/*RTK IMU status check*/
-#define		RTK_IMU_OK		0
-#define		IMU_STATUS_ERR	1
-#define		RTK_STATUS_ERR	2
-#define		UNKNOWN			0xFF
-
-struct GPS_INS
-{
-    int valid = 0xff;
-    int index = 0;	//gps点序号
-
-    double gps_lat = 0;//纬度
-    double gps_lng = 0;//经度
-
-    double gps_x = 0;
-    double gps_y = 0;
-    double gps_z = 0;
-
-    double ins_roll_angle = 0;	//横滚角 一般定义载体的右、前、上三个方向构成右手系,绕向前的轴旋转就是横滚角,绕向右的轴旋转就是俯仰角,绕向上的轴旋转就是航向角
-    double ins_pitch_angle = 0;	//俯仰角
-    double ins_heading_angle = 0;	//航向角
-
-    int ins_status = 0;	//惯导状态 4
-    int rtk_status = 0;	//rtk状态 6 -5 -3
-    int gps_satelites_num = 0;
-
-    //-----加速度--------------
-    double accel_x = 0;
-    double accel_y = 0;
-    double accel_z = 0;
-
-    //-------角速度------------
-    double ang_rate_x = 0;
-    double ang_rate_y = 0;
-    double ang_rate_z = 0;
-
-    //-----------方向速度--------------
-    double vel_N = 0;
-    double vel_E = 0;
-    double vel_D = 0;
-
-    int speed_mode = 0;
-    int mode2 = 0;
-    double speed = 0;			//速度  若导航点则为导航预设速度  若为当前点则为当前车速
-
-};
-
-typedef boost::shared_ptr<GPS_INS> GPSData;
-
-class CarStatus : public boost::noncopyable {
-public:
-    float speed;			//车速
-    std::int16_t wheel_angle;		//方向盘转角
-    std::uint8_t braking_pressure;	//刹车压力
-    GPSData location;		//当前车辆位置
-
-    CarStatus() {
-        speed = 0;
-        braking_pressure = 0;
-        wheel_angle = 0;
-        location = boost::shared_ptr<GPS_INS>(new GPS_INS);
-    }
-    ~CarStatus() {
-
-    }
-};
-typedef boost::serialization::singleton<CarStatus> CarStatusSingleton;
-
-#define ServiceCarStatus CarStatusSingleton::get_mutable_instance()
-
-
-static double   cast_8_byte_to_double(const uint8_t *b);
-static int32_t cast_3_byte_to_int32(const uint8_t *b);
-
-GPSSensor::GPSSensor() {
-}
-
-GPSSensor::~GPSSensor() {
-
-}
-
-void GPSSensor::start()
-{
-    thread_sensor_run_ = new boost::thread(boost::bind(&GPSSensor::processSensor, this));
-}
-
-void GPSSensor::stop()
-{
-    thread_sensor_run_->interrupt();
-    thread_sensor_run_->join();
-}
-
-void GPSSensor::obs_modechange(int rec)
-{
-    _mtx.lock();
-    obs_modes = rec;
-    _mtx.unlock();
-}
-
-void GPSSensor::speed_modechange(int rec)
-{
-    _mtx.lock();
-    speed_modes = rec;
-    _mtx.unlock();
-}
-
-void GPSSensor::lane_num_modechange(int rec)
-{
-    _mtx.lock();
-    lane_num = rec;
-    _mtx.unlock();
-}
-
-void GPSSensor::lane_status_modechange(int rec)
-{
-    _mtx.lock();
-    lane_status = rec;
-    _mtx.unlock();
-}
-
-void GPSSensor::start_or_end(bool rec)
-{
-    _mtx2.lock();
-    writegps = rec;
-    _mtx2.unlock();
-}
-
-void GPSSensor::collect_modechange(bool rec)
-{
-    _mtx3.lock();
-    is_forbidden = rec;
-    _mtx3.unlock();
-}
-
-void GPSSensor::jianju_change(double rec)
-{
-    _mtx4.lock();
-    jianju = rec;
-    _mtx4.unlock();
-}
-
-bool GPSSensor::isRunning() const
-{
-    return (thread_sensor_run_ != NULL && !thread_sensor_run_->timed_join(boost::posix_time::milliseconds(10)));
-}
-
-void GPSSensor::processSensor()
-{
-    //todo  GPS/惯导 设备接口 对接
-    /*Initialize udp server, listen on port 3000.*/
-    /*int sockfd;
-    struct sockaddr_in addr;
-    socklen_t addrlen;
-    sockfd = socket(AF_INET, SOCK_DGRAM, 0);
-    if (sockfd < 0)
-    {
-       printf("socket failed\n");
-       exit(EXIT_FAILURE);
-    }
-    addrlen = sizeof(struct sockaddr_in);
-    bzero(&addr, addrlen);
-    addr.sin_family = AF_INET;
-    addr.sin_addr.s_addr = htonl(INADDR_ANY);
-    addr.sin_port = htons(3000);
-    if (bind(sockfd, (struct sockaddr*)(&addr), addrlen) < 0)
-    {
-       printf("bind fail\n");
-       exit(EXIT_FAILURE);
-    }*/
-    QUdpSocket *udpsocket;//summer
-    udpsocket = new QUdpSocket();
-    udpsocket->bind(QHostAddress::Any, 3000);
-    /*    udpsocket->bind(3000);
-    if(!udpsocket->waitForConnected())
-    {
-        printf("bind fail\n");
-        exit(EXIT_FAILURE);
-    }
-*/
-    unsigned char recvBuf[100] = { 0 };
-
-    GPSData data(new GPS_INS);
-    int x;
-
-    ServiceCarStatus.location->gps_x = 0;
-    ServiceCarStatus.location->gps_y = 0;
-
-    std::string sk;
-    std::stringstream ss;
-    while (true)
-    {
-        ss.clear();
-        ss.str("");
-        sk.clear();
-        gps_index = 0;
-        testcount = 0;
-        _mtx2.lock();
-        while (writegps == false)
-        {
-            _mtx2.unlock();
-            if(should_exit == true)
-            {
-                udpsocket->close();
-                ready_exit++;
-                return;
-            }
-            //boost::this_thread::sleep(boost::posix_time::milliseconds(10));
-
-#ifdef linux
-            usleep(10000);
-#endif
-#ifdef WIN32
-            boost::this_thread::sleep(boost::posix_time::milliseconds(10));
-            //         Sleep(10);
-#endif
-            _mtx2.lock();
-        }
-        std::ofstream fout;
-        fout.setf(std::ios::fixed, std::ios::floatfield);  // 设定为 fixed 模式,以小数点表示浮点数
-        fout.precision(12);  // 设置精度 2
-        time_t now;
-        struct tm *timenow;
-        time(&now);
-        timenow = localtime(&now);
-        ss << "/home/adc/" << timenow->tm_year+1900 << "-" << timenow->tm_mon+1 << "-" << timenow->tm_mday << "-" << timenow->tm_hour << "h-" << timenow->tm_min << "m-" << timenow->tm_sec << "s.txt";
-        sk = ss.str();
-        fout.open(sk);
-        while (writegps) {
-            _mtx2.unlock();
-            if(should_exit == true)
-            {
-                udpsocket->close();
-                fout.close();
-                ready_exit++;
-                return;
-            }
-            char *buf = new char[100];
-            memset(buf,0,100);
-            int rec = 0;
-            if(udpsocket->waitForReadyRead())
-                rec = udpsocket->read(buf,100);
-            convertStrToUnChar(buf,recvBuf);
-            //int rec = recvfrom(sockfd, recvBuf, 100, 0, (struct sockaddr *)(&addr), &addrlen);
-
-            if (rec != NOUTPUT_PACKET_LENGTH) {
-                std::cout << "ERR: rec must be 72 bytes\n" << std::endl;
-                continue;
-            }
-
-            if (recvBuf[PI_SYNC] != NCOM_SYNC) {
-                std::cout << "ERR: head always be 0xE7\n" << std::endl;
-                continue;
-            }
-            data->gps_lat = cast_8_byte_to_double(recvBuf + PI_POS_LAT) * RAD2DEG;
-            data->gps_lng = cast_8_byte_to_double(recvBuf + PI_POS_LON) * RAD2DEG;
-
-            x = cast_3_byte_to_int32(recvBuf + PI_ORIEN_H);
-            if (x != INV_INT_24) data->ins_heading_angle = x * (ANG2RAD * RAD2DEG);
-            if (data->ins_heading_angle < 0.0)
-            {
-                data->ins_heading_angle += 360.0;
-            }
-
-            if (abs(data->gps_lng - 117.0) < 5)
-            {
-                ServiceCarStatus.location->gps_lat = data->gps_lat;
-                ServiceCarStatus.location->gps_lng = data->gps_lng;
-                ServiceCarStatus.location->ins_heading_angle = data->ins_heading_angle;
-                if (testcount < 1000)
-                {
-                    testcount++;
-                }
-                else
-                {
-                    double x = (ServiceCarStatus.location->gps_x - data->gps_x)*(ServiceCarStatus.location->gps_x - data->gps_x) + (ServiceCarStatus.location->gps_y - data->gps_y)*(ServiceCarStatus.location->gps_y - data->gps_y);
-
-                    if (x > (jianju*jianju))
-                    {
-                        if (is_forbidden == false)
-                        {
-                            _mtx.try_lock();
-                            fout << gps_index << "\t" << data->gps_lng << "\t" << data->gps_lat << "\t" << ServiceCarStatus.location->speed_mode << "\t" << ServiceCarStatus.location->mode2 << "\t" << data->ins_heading_angle << "\t" << obs_modes << "\t" << speed_modes << "\t" << lane_num << "\t" << lane_status << std::endl;
-                            _mtx.unlock();
-                        }
-                        else
-                        {
-                            _mtx.try_lock();
-                            fout << gps_index << "\t" << data->gps_lng << "\t" << data->gps_lat << "\t" << ServiceCarStatus.location->speed_mode << "\t" << ServiceCarStatus.location->mode2 << "\t" << data->ins_heading_angle << std::endl;
-                            _mtx.unlock();
-                        }
-                        gps_index++;
-                        ServiceCarStatus.location->gps_x = data->gps_x;
-                        ServiceCarStatus.location->gps_y = data->gps_y;
-                    }
-                }
-            }
-            _mtx2.lock();
-        }
-        _mtx2.unlock();
-        fout.close();                  //关闭文件
-    }
-    udpsocket->close();
-}
-
-void GPSSensor::wait_exit()
-{
-    while(true)
-    {
-        should_exit = true;
-#ifdef linux
-        usleep(5000);
-#endif
-#ifdef WIN32
-        boost::this_thread::sleep(boost::posix_time::milliseconds(5));
-        //           Sleep(5);
-#endif
-        if(ready_exit == 1)
-        {
-            return;
-        }
-    }
-}
-
-static double cast_8_byte_to_double(const uint8_t *b)
-{
-    union { double x; uint8_t c[8]; } u;
-    u.c[0] = b[0];
-    u.c[1] = b[1];
-    u.c[2] = b[2];
-    u.c[3] = b[3];
-    u.c[4] = b[4];
-    u.c[5] = b[5];
-    u.c[6] = b[6];
-    u.c[7] = b[7];
-    return u.x;
-}
-
-static int32_t cast_3_byte_to_int32(const uint8_t *b)
-{
-    union { int32_t x; uint8_t c[4]; } u;
-    u.c[1] = b[0];
-    u.c[2] = b[1];
-    u.c[3] = b[2];
-    return u.x >> 8;
-}
-
-GPS_Collect::GPS_Collect(QWidget *parent):
-    QWidget(parent)
-{
-    //gps_collector_close = new boost::signals2::signal<void()>();
-
-    this->setObjectName(QStringLiteral("GPS_Collector"));
-    this->resize(800, 700);
-    frame = new QFrame(this);
-    frame->setObjectName(QStringLiteral("frame"));
-    frame->setGeometry(QRect(440, 390, 120, 80));
-    frame->setFrameShape(QFrame::StyledPanel);
-    frame->setFrameShadow(QFrame::Raised);
-    label = new QLabel(this);
-    label->setObjectName(QStringLiteral("label"));
-    label->setGeometry(QRect(20, 20, 90, 35));
-    comboBox = new QComboBox(this);
-    comboBox->setObjectName(QStringLiteral("comboBox"));
-    comboBox->setGeometry(QRect(120, 60, 100, 35));
-    QFont font;
-    font.setPointSize(16);
-    comboBox->setFont(font);
-    label_2 = new QLabel(this);
-    label_2->setObjectName(QStringLiteral("label_2"));
-    label_2->setGeometry(QRect(20, 60, 90, 35));
-    lineEdit = new QLineEdit(this);
-    lineEdit->setObjectName(QStringLiteral("lineEdit"));
-    lineEdit->setGeometry(QRect(120, 20, 100, 35));
-    lineEdit->setFont(font);
-    lineEdit->setAlignment(Qt::AlignCenter);
-    label_3 = new QLabel(this);
-    label_3->setObjectName(QStringLiteral("label_3"));
-    label_3->setGeometry(QRect(270, 20, 30, 16));
-    label_4 = new QLabel(this);
-    label_4->setObjectName(QStringLiteral("label_4"));
-    label_4->setGeometry(QRect(270, 40, 30, 16));
-    label_5 = new QLabel(this);
-    label_5->setObjectName(QStringLiteral("label_5"));
-    label_5->setGeometry(QRect(270, 60, 60, 16));
-    label_6 = new QLabel(this);
-    label_6->setObjectName(QStringLiteral("label_6"));
-    label_6->setGeometry(QRect(440, 20, 80, 16));
-    label_7 = new QLabel(this);
-    label_7->setObjectName(QStringLiteral("label_7"));
-    label_7->setGeometry(QRect(440, 80, 80, 16));
-    label_8 = new QLabel(this);
-    label_8->setObjectName(QStringLiteral("label_8"));
-    label_8->setGeometry(QRect(440, 40, 80, 16));
-    label_9 = new QLabel(this);
-    label_9->setObjectName(QStringLiteral("label_9"));
-    label_9->setGeometry(QRect(440, 60, 80, 16));
-    lineEdit_2 = new QLineEdit(this);
-    lineEdit_2->setObjectName(QStringLiteral("lineEdit_2"));
-    lineEdit_2->setGeometry(QRect(310, 20, 120, 20));
-    lineEdit_3 = new QLineEdit(this);
-    lineEdit_3->setObjectName(QStringLiteral("lineEdit_3"));
-    lineEdit_3->setGeometry(QRect(310, 40, 120, 20));
-    lineEdit_4 = new QLineEdit(this);
-    lineEdit_4->setObjectName(QStringLiteral("lineEdit_4"));
-    lineEdit_4->setGeometry(QRect(340, 60, 90, 20));
-    lineEdit_5 = new QLineEdit(this);
-    lineEdit_5->setObjectName(QStringLiteral("lineEdit_5"));
-    lineEdit_5->setGeometry(QRect(520, 20, 90, 20));
-    lineEdit_6 = new QLineEdit(this);
-    lineEdit_6->setObjectName(QStringLiteral("lineEdit_6"));
-    lineEdit_6->setGeometry(QRect(520, 40, 90, 20));
-    lineEdit_7 = new QLineEdit(this);
-    lineEdit_7->setObjectName(QStringLiteral("lineEdit_7"));
-    lineEdit_7->setGeometry(QRect(520, 60, 90, 20));
-    lineEdit_8 = new QLineEdit(this);
-    lineEdit_8->setObjectName(QStringLiteral("lineEdit_8"));
-    lineEdit_8->setGeometry(QRect(520, 80, 90, 20));
-
-    this->setWindowTitle(QApplication::translate("GPS_Collector", "GPS_Collector", nullptr));
-    label->setText(QApplication::translate("GPS_Collector", "\351\207\207\351\233\206\347\202\271\351\227\264\350\267\235(m)", nullptr));
-    label_2->setText(QApplication::translate("GPS_Collector", "\347\246\201\347\224\250\351\231\204\345\212\240\345\261\236\346\200\247", nullptr));
-    label_3->setText(QApplication::translate("GPS_Collector", "\347\273\217\345\272\246", nullptr));
-    label_4->setText(QApplication::translate("GPS_Collector", "\347\272\254\345\272\246", nullptr));
-    label_5->setText(QApplication::translate("GPS_Collector", "\345\267\262\351\207\207\351\233\206\347\202\271\346\225\260", nullptr));
-    label_6->setText(QApplication::translate("GPS_Collector", "\351\201\277\351\232\234\346\250\241\345\274\217", nullptr));
-    label_7->setText(QApplication::translate("GPS_Collector", "\346\211\200\345\234\250\350\275\246\351\201\223", nullptr));
-    label_8->setText(QApplication::translate("GPS_Collector", "\351\200\237\345\272\246\346\216\247\345\210\266\346\250\241\345\274\217", nullptr));
-    label_9->setText(QApplication::translate("GPS_Collector", "\350\275\246\351\201\223\346\200\273\346\225\260", nullptr));
-
-    pushButtonstart = new QPushButton(this);
-    pushButtonstart->setObjectName(QStringLiteral("pushButtonstart"));
-    pushButtonstart->setGeometry(QRect(630, 11, 158, 50));
-    pushButtonstart->setText("start");
-    connect(pushButtonstart, SIGNAL(clicked()), this, SLOT(ClickButton_start()));
-    pushButtonend = new QPushButton(this);
-    pushButtonend->setObjectName(QStringLiteral("pushButtonend"));
-    pushButtonend->setGeometry(QRect(630, 70, 158, 50));
-    pushButtonend->setText("end");
-    connect(pushButtonend, SIGNAL(clicked()), this, SLOT(ClickButton_end()));
-
-    pushButton0 = new QPushButton(this);
-    pushButton0->setObjectName(QStringLiteral("pushButton0"));
-    pushButton0->setGeometry(QRect(20, 130, 192, 93));
-    pushButton0->setText(QStringLiteral("停障"));
-    connect(pushButton0, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_0()));
-    pushButton1 = new QPushButton(this);
-    pushButton1->setObjectName(QStringLiteral("pushButton1"));
-    pushButton1->setGeometry(QRect(20, 223, 192, 93));
-    pushButton1->setText(QStringLiteral("避障"));
-    connect(pushButton1, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_1()));
-    pushButton2 = new QPushButton(this);
-    pushButton2->setObjectName(QStringLiteral("pushButton2"));
-    pushButton2->setGeometry(QRect(20, 316, 192, 93));
-    pushButton2->setText(QStringLiteral("不停不避"));
-    connect(pushButton2, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_2()));
-    pushButton33 = new QPushButton(this);
-    pushButton33->setObjectName(QStringLiteral("pushButton33"));
-    pushButton33->setGeometry(QRect(20, 409, 192, 93));
-    pushButton33->setText(QStringLiteral("保留"));
-    connect(pushButton33, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_33()));
-    pushButton34 = new QPushButton(this);
-    pushButton34->setObjectName(QStringLiteral("pushButton34"));
-    pushButton34->setGeometry(QRect(20, 502, 192, 93));
-    pushButton34->setText(QStringLiteral("保留"));
-    connect(pushButton34, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_34()));
-
-    pushButton3 = new QPushButton(this);
-    pushButton3->setObjectName(QStringLiteral("pushButton3"));
-    pushButton3->setGeometry(QRect(212, 130, 96, 46));
-    pushButton3->setText(QStringLiteral("常速行驶"));
-    connect(pushButton3, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_3()));
-    pushButton4 = new QPushButton(this);
-    pushButton4->setObjectName(QStringLiteral("pushButton4"));
-    pushButton4->setGeometry(QRect(308, 130, 96, 46));
-    pushButton4->setText(QStringLiteral("入口"));
-    connect(pushButton4, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_4()));
-    pushButton5 = new QPushButton(this);
-    pushButton5->setObjectName(QStringLiteral("pushButton5"));
-    pushButton5->setGeometry(QRect(212, 176, 96, 47));
-    pushButton5->setText(QStringLiteral("事故区"));
-    connect(pushButton5, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_5()));
-    pushButton6 = new QPushButton(this);
-    pushButton6->setObjectName(QStringLiteral("pushButton6"));
-    pushButton6->setGeometry(QRect(308, 176, 96, 47));
-    pushButton6->setText(QStringLiteral("驻车点"));
-    connect(pushButton6, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_6()));
-    pushButton7 = new QPushButton(this);
-    pushButton7->setObjectName(QStringLiteral("pushButton7"));
-    pushButton7->setGeometry(QRect(212, 223, 96, 46));
-    pushButton7->setText(QStringLiteral("隧道"));
-    connect(pushButton7, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_7()));
-    pushButton18 = new QPushButton(this);
-    pushButton18->setObjectName(QStringLiteral("pushButton18"));
-    pushButton18->setGeometry(QRect(308, 223, 96, 46));
-    pushButton18->setText(QStringLiteral("低速"));
-    connect(pushButton18, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_18()));
-    pushButton19 = new QPushButton(this);
-    pushButton19->setObjectName(QStringLiteral("pushButton19"));
-    pushButton19->setGeometry(QRect(212, 269, 96, 47));
-    pushButton19->setText(QStringLiteral("红绿灯"));
-    connect(pushButton19, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_19()));
-    pushButton20 = new QPushButton(this);
-    pushButton20->setObjectName(QStringLiteral("pushButton20"));
-    pushButton20->setGeometry(QRect(308, 269, 96, 47));
-    pushButton20->setText(QStringLiteral("行人"));
-    connect(pushButton20, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_20()));
-    pushButton21 = new QPushButton(this);
-    pushButton21->setObjectName(QStringLiteral("pushButton21"));
-    pushButton21->setGeometry(QRect(212, 316, 96, 46));
-    pushButton21->setText(QStringLiteral("雾区"));
-    connect(pushButton21, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_21()));
-    pushButton22 = new QPushButton(this);
-    pushButton22->setObjectName(QStringLiteral("pushButton22"));
-    pushButton22->setGeometry(QRect(308, 316, 96, 46));
-    pushButton22->setText(QStringLiteral("变道停车"));
-    connect(pushButton22, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_22()));
-    pushButton23 = new QPushButton(this);
-    pushButton23->setObjectName(QStringLiteral("pushButton23"));
-    pushButton23->setGeometry(QRect(212, 362, 96, 47));
-    pushButton23->setText(QStringLiteral("等人停车"));
-    connect(pushButton23, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_23()));
-    pushButton24 = new QPushButton(this);
-    pushButton24->setObjectName(QStringLiteral("pushButton24"));
-    pushButton24->setGeometry(QRect(308, 362, 96, 47));
-    pushButton24->setText(QStringLiteral("疯狂加速"));
-    connect(pushButton24, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_24()));
-    pushButton25 = new QPushButton(this);
-    pushButton25->setObjectName(QStringLiteral("pushButton25"));
-    pushButton25->setGeometry(QRect(212, 409, 96, 46));
-    pushButton25->setText(QStringLiteral("跟随"));
-    connect(pushButton25, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_25()));
-    pushButton26 = new QPushButton(this);
-    pushButton26->setObjectName(QStringLiteral("pushButton26"));
-    pushButton26->setGeometry(QRect(308, 409, 96, 46));
-    pushButton26->setText(QStringLiteral("保留"));
-    connect(pushButton26, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_26()));
-    pushButton27 = new QPushButton(this);
-    pushButton27->setObjectName(QStringLiteral("pushButton27"));
-    pushButton27->setGeometry(QRect(212, 455, 96, 47));
-    pushButton27->setText(QStringLiteral("保留"));
-    connect(pushButton27, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_27()));
-    pushButton28 = new QPushButton(this);
-    pushButton28->setObjectName(QStringLiteral("pushButton28"));
-    pushButton28->setGeometry(QRect(308, 455, 96, 47));
-    pushButton28->setText(QStringLiteral("保留"));
-    connect(pushButton28, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_28()));
-    pushButton29 = new QPushButton(this);
-    pushButton29->setObjectName(QStringLiteral("pushButton29"));
-    pushButton29->setGeometry(QRect(212, 502, 96, 46));
-    pushButton29->setText(QStringLiteral("保留"));
-    connect(pushButton29, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_29()));
-    pushButton30 = new QPushButton(this);
-    pushButton30->setObjectName(QStringLiteral("pushButton30"));
-    pushButton30->setGeometry(QRect(308, 502, 96, 46));
-    pushButton30->setText(QStringLiteral("保留"));
-    connect(pushButton30, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_30()));
-    pushButton31 = new QPushButton(this);
-    pushButton31->setObjectName(QStringLiteral("pushButton31"));
-    pushButton31->setGeometry(QRect(212, 548, 96, 47));
-    pushButton31->setText(QStringLiteral("保留"));
-    connect(pushButton31, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_31()));
-    pushButton32 = new QPushButton(this);
-    pushButton32->setObjectName(QStringLiteral("pushButton32"));
-    pushButton32->setGeometry(QRect(308, 548, 96, 47));
-    pushButton32->setText(QStringLiteral("保留"));
-    connect(pushButton32, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_32()));
-
-    pushButton8 = new QPushButton(this);
-    pushButton8->setObjectName(QStringLiteral("pushButton8"));
-    pushButton8->setGeometry(QRect(404, 130, 192, 93));
-    pushButton8->setText(QStringLiteral("单车道"));
-    connect(pushButton8, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_8()));
-    pushButton9 = new QPushButton(this);
-    pushButton9->setObjectName(QStringLiteral("pushButton9"));
-    pushButton9->setGeometry(QRect(404, 223, 192, 93));
-    pushButton9->setText(QStringLiteral("双车道"));
-    connect(pushButton9, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_9()));
-    pushButton10 = new QPushButton(this);
-    pushButton10->setObjectName(QStringLiteral("pushButton10"));
-    pushButton10->setGeometry(QRect(404, 316, 192, 93));
-    pushButton10->setText(QStringLiteral("三车道"));
-    connect(pushButton10, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_10()));
-    pushButton11 = new QPushButton(this);
-    pushButton11->setObjectName(QStringLiteral("pushButton11"));
-    pushButton11->setGeometry(QRect(404, 409, 192, 93));
-    pushButton11->setText(QStringLiteral("四车道"));
-    connect(pushButton11, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_11()));
-    pushButton12 = new QPushButton(this);
-    pushButton12->setObjectName(QStringLiteral("pushButton12"));
-    pushButton12->setGeometry(QRect(404, 502, 192, 93));
-    pushButton12->setText(QStringLiteral("五车道"));
-    connect(pushButton12, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_12()));
-
-    pushButton13 = new QPushButton(this);
-    pushButton13->setObjectName(QStringLiteral("pushButton13"));
-    pushButton13->setGeometry(QRect(596, 130, 192, 93));
-    pushButton13->setText(QStringLiteral("在车道0"));
-    connect(pushButton13, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_13()));
-    pushButton14 = new QPushButton(this);
-    pushButton14->setObjectName(QStringLiteral("pushButton0"));
-    pushButton14->setGeometry(QRect(596, 223, 192, 93));
-    pushButton14->setText(QStringLiteral("在车道1"));
-    connect(pushButton14, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_14()));
-    pushButton15 = new QPushButton(this);
-    pushButton15->setObjectName(QStringLiteral("pushButton0"));
-    pushButton15->setGeometry(QRect(596, 316, 192, 93));
-    pushButton15->setText(QStringLiteral("在车道2"));
-    connect(pushButton15, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_15()));
-    pushButton16 = new QPushButton(this);
-    pushButton16->setObjectName(QStringLiteral("pushButton0"));
-    pushButton16->setGeometry(QRect(596, 409, 192, 93));
-    pushButton16->setText(QStringLiteral("在车道3"));
-    connect(pushButton16, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_16()));
-    pushButton17 = new QPushButton(this);
-    pushButton17->setObjectName(QStringLiteral("pushButton0"));
-    pushButton17->setGeometry(QRect(596, 502, 192, 93));
-    pushButton17->setText(QStringLiteral("在车道4"));
-    connect(pushButton17, SIGNAL(clicked()), this, SLOT(ClickButton_nomall_17()));
-
-    lineEdit->setText(QStringLiteral("0.1"));
-    connect(lineEdit, SIGNAL(textEdited(const QString &)), this, SLOT(savestabuyEditinfo(const QString &)));
-    comboBox->addItem(QStringLiteral("  禁用"));
-    comboBox->addItem(QStringLiteral(" 不禁用"));
-    connect(comboBox, SIGNAL(currentIndexChanged(const QString &)), this, SLOT(mycombox(const QString &)));
-
-    timer = new QTimer(this);
-    connect(timer, SIGNAL(timeout()), this, SLOT(timeoutslot1()));
-    connect(timer, SIGNAL(timeout()), this, SLOT(timeoutslot2()));
-    timer->start(20);
-
-    sensor_gps = new GPSSensor();
-    sensor_gps->start();
-
-}
-
-GPS_Collect::~GPS_Collect()
-{
-
-}
-//刷新
-void GPS_Collect::paintEvent(QPaintEvent *)
-{
-
-}
-
-void GPS_Collect::savestabuyEditinfo(const QString &txt)
-{
-    jianju = txt.toDouble();
-    if (jianju > 0.01)
-    {
-        sensor_gps->jianju_change(jianju);
-    }
-}
-
-void GPS_Collect::mycombox(const QString &txt)
-{
-    if (txt == QStringLiteral("  禁用"))
-    {
-        is_forbidden = true;
-    }
-    else
-    {
-        is_forbidden = false;
-    }
-    sensor_gps->collect_modechange(is_forbidden);
-}
-
-void GPS_Collect::timeoutslot1()
-{
-    //update();
-}
-
-void GPS_Collect::timeoutslot2()
-{
-    lineEdit_2->setText(QString::number(ServiceCarStatus.location->gps_lng));
-    lineEdit_3->setText(QString::number(ServiceCarStatus.location->gps_lat));
-    lineEdit_4->setText(QString::number(sensor_gps->gps_index));
-    lineEdit_5->setText(QString::number(obs_modes));
-    lineEdit_6->setText(QString::number(speed_modes));
-    lineEdit_7->setText(QString::number(lane_num));
-    lineEdit_8->setText(QString::number(lane_status));
-}
-
-void GPS_Collect::ClickButton_start()
-{
-    starts = true;
-    sensor_gps->start_or_end(starts);
-}
-void GPS_Collect::ClickButton_end()
-{
-    starts = false;
-    sensor_gps->start_or_end(starts);
-}
-
-
-
-
-/////////////////////////////////////////////////////
-void GPS_Collect::ClickButton_nomall_0()
-{
-    obs_modes = 0;
-    sensor_gps->obs_modechange(obs_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_1()
-{
-    obs_modes = 1;
-    sensor_gps->obs_modechange(obs_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_2()
-{
-    obs_modes = 2;
-    sensor_gps->obs_modechange(obs_modes);
-}
-
-
-
-
-////////////////////////////////////////////////////////
-void GPS_Collect::ClickButton_nomall_3()
-{
-    speed_modes = 0;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_4()
-{
-    speed_modes = 1;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_5()
-{
-    speed_modes = 2;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_6()
-{
-    speed_modes = 3;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_7()
-{
-    speed_modes = 4;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-
-
-/////////////////////////////////////////////////////////
-void GPS_Collect::ClickButton_nomall_8()
-{
-    lane_num = 1;
-    sensor_gps->lane_num_modechange(lane_num);
-}
-
-void GPS_Collect::ClickButton_nomall_9()
-{
-    lane_num = 2;
-    sensor_gps->lane_num_modechange(lane_num);
-}
-
-void GPS_Collect::ClickButton_nomall_10()
-{
-    lane_num = 3;
-    sensor_gps->lane_num_modechange(lane_num);
-}
-
-void GPS_Collect::ClickButton_nomall_11()
-{
-    lane_num = 4;
-    sensor_gps->lane_num_modechange(lane_num);
-}
-
-void GPS_Collect::ClickButton_nomall_12()
-{
-    lane_num = 5;
-    sensor_gps->lane_num_modechange(lane_num);
-}
-
-
-
-//////////////////////////////////////////////////////////
-void GPS_Collect::ClickButton_nomall_13()
-{
-    lane_status = 0;
-    sensor_gps->lane_status_modechange(lane_status);
-}
-
-void GPS_Collect::ClickButton_nomall_14()
-{
-    lane_status = 1;
-    sensor_gps->lane_status_modechange(lane_status);
-}
-
-void GPS_Collect::ClickButton_nomall_15()
-{
-    lane_status = 2;
-    sensor_gps->lane_status_modechange(lane_status);
-}
-
-void GPS_Collect::ClickButton_nomall_16()
-{
-    lane_status = 3;
-    sensor_gps->lane_status_modechange(lane_status);
-}
-
-void GPS_Collect::ClickButton_nomall_17()
-{
-    lane_status = 4;
-    sensor_gps->lane_status_modechange(lane_status);
-}
-
-
-
-/////////////////////////////////////////////////////////
-void GPS_Collect::ClickButton_nomall_18()
-{
-    speed_modes = 5;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_19()
-{
-    speed_modes = 6;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_20()
-{
-    speed_modes = 7;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_21()
-{
-    speed_modes = 8;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_22()
-{
-    speed_modes = 9;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_23()
-{
-    speed_modes = 10;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_24()
-{
-    speed_modes = 11;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_25()
-{
-    speed_modes = 12;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_26()
-{
-    speed_modes = 13;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_27()
-{
-    speed_modes = 14;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_28()
-{
-    speed_modes = 15;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_29()
-{
-    speed_modes = 16;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_30()
-{
-    speed_modes = 17;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_31()
-{
-    speed_modes = 18;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_32()
-{
-    speed_modes = 19;
-    sensor_gps->speed_modechange(speed_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_33()
-{
-    obs_modes = 3;
-    sensor_gps->obs_modechange(obs_modes);
-}
-
-void GPS_Collect::ClickButton_nomall_34()
-{
-    obs_modes = 4;
-    sensor_gps->obs_modechange(obs_modes);
-}
-
-
-void GPS_Collect::closeEvent(QCloseEvent *event)
-{
-    if(should_close == false)
-    {
-        QMessageBox::StandardButton button;
-        button=QMessageBox::question(this,tr("退出程序"),QString(tr("确认退出程序")),QMessageBox::Yes|QMessageBox::No);
-        if(button==QMessageBox::No)
-        {
-            event->ignore(); // 忽略退出信号,程序继续进行
-        }
-        else if(button==QMessageBox::Yes)
-        {
-            sensor_gps->wait_exit();
-            event->accept(); // 接受退出信号,程序退出
-            gps_collector_close();
-        }
-    }
-    else
-    {
-        event->accept(); // 接受退出信号,程序退出
-    }
-}
-
-void GPSSensor::convertStrToUnChar(char* str, unsigned char* UnChar)
-{
-    int i = strlen(str), j = 0, counter = 0;
-    char c[2];
-    unsigned int bytes[2];
-
-    for (j = 0; j < i; j += 2)
-    {
-        if(0 == j % 2)
-        {
-            c[0] = str[j];
-            c[1] = str[j + 1];
-            sscanf(c, "%02x" , &bytes[0]);
-            UnChar[counter] = bytes[0];
-            counter++;
-        }
-    }
-}

+ 0 - 216
src/ui/ui_ads_hmi/gps_collect.h

@@ -1,216 +0,0 @@
-#ifndef GPS_COLLECT_H
-#define GPS_COLLECT_H
-
-#include <QWidget>
-#include <QCloseEvent>
-#include <QtWidgets/qpushbutton.h>
-#include <qtimer.h>
-#include <qpainter.h>
-#include <QGraphicsView>
-#include <QWheelEvent>
-#include <QKeyEvent>
-#include <QPoint>
-#include <QPointF>
-#include <qfiledialog.h>
-#include <qmessagebox.h>
-#include <qabstractscrollarea.h>
-#include <QGraphicsItem>
-#include <QKeyEvent>
-#include <qpainter.h>
-#include <QDebug>
-#include <QtCore/QVariant>
-#include <QtWidgets/QAction>
-#include <QtWidgets/QApplication>
-#include <QtWidgets/QButtonGroup>
-#include <QtWidgets/QComboBox>
-#include <QtWidgets/QFrame>
-#include <QtWidgets/QHeaderView>
-#include <QtWidgets/QLabel>
-#include <QtWidgets/QLineEdit>
-#include <QtWidgets/QMainWindow>
-#include <QtWidgets/QMenuBar>
-#include <QtWidgets/QStatusBar>
-#include <QtWidgets/QWidget>
-#include <boost/serialization/singleton.hpp>
-#include <boost/signals2/slot.hpp>
-#include <boost/thread/mutex.hpp>
-#include <boost/shared_ptr.hpp>
-#include <boost/signals2.hpp>
-#include <boost/thread.hpp>
-#include <iostream>
-#include <fstream>
-#include <sstream>
-#include <stdio.h>
-#include <math.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <time.h>
-#include <stdlib.h>
-#include <string.h>
-#include <sys/types.h>
-#include <QtNetwork/QUdpSocket>
-
-class GPSSensor
-{
-public:
-    GPSSensor();
-    ~GPSSensor();
-
-    void start();
-    void stop();
-    void obs_modechange(int rec);
-    void speed_modechange(int rec);
-    void lane_num_modechange(int rec);
-    void lane_status_modechange(int rec);
-    void start_or_end(bool rec);
-    void collect_modechange(bool rec);
-    void jianju_change(double rec);
-    bool isRunning() const;
-    void processSensor();
-    void wait_exit();
-    void convertStrToUnChar(char* str, unsigned char* UnChar);//summer
-
-    boost::mutex _mtx, _mtx2, _mtx3, _mtx4;
-    boost::thread* thread_sensor_run_;			//传感器运行的线程
-    bool should_exit = false;
-    int ready_exit = 0;
-    bool writegps = false;
-    bool is_forbidden = true;
-    int obs_modes = 0, speed_modes = 0, lane_num = 1, lane_status = 0;
-    int gps_index, testcount;
-    double jianju = 0.1;
-};
-
-class GPS_Collect : public QWidget
-{
-    Q_OBJECT
-
-public:
-    explicit GPS_Collect(QWidget *parent = 0);
-    ~GPS_Collect();
-    bool should_close = false;
-    boost::signals2::signal<void()> gps_collector_close;
-
-public slots:
-    void savestabuyEditinfo(const QString &txt);
-    void mycombox(const QString &txt);
-    void timeoutslot1();
-    void timeoutslot2();
-    void ClickButton_start();
-    void ClickButton_end();
-    void ClickButton_nomall_0();
-    void ClickButton_nomall_1();
-    void ClickButton_nomall_2();
-    void ClickButton_nomall_3();
-    void ClickButton_nomall_4();
-    void ClickButton_nomall_5();
-    void ClickButton_nomall_6();
-    void ClickButton_nomall_7();
-    void ClickButton_nomall_8();
-    void ClickButton_nomall_9();
-    void ClickButton_nomall_10();
-    void ClickButton_nomall_11();
-    void ClickButton_nomall_12();
-    void ClickButton_nomall_13();
-    void ClickButton_nomall_14();
-    void ClickButton_nomall_15();
-    void ClickButton_nomall_16();
-    void ClickButton_nomall_17();
-    void ClickButton_nomall_18();
-    void ClickButton_nomall_19();
-    void ClickButton_nomall_20();
-    void ClickButton_nomall_21();
-    void ClickButton_nomall_22();
-    void ClickButton_nomall_23();
-    void ClickButton_nomall_24();
-    void ClickButton_nomall_25();
-    void ClickButton_nomall_26();
-    void ClickButton_nomall_27();
-    void ClickButton_nomall_28();
-    void ClickButton_nomall_29();
-    void ClickButton_nomall_30();
-    void ClickButton_nomall_31();
-    void ClickButton_nomall_32();
-    void ClickButton_nomall_33();
-    void ClickButton_nomall_34();
-
-protected:
-    void paintEvent(QPaintEvent *);
-    void closeEvent(QCloseEvent *event);
-private:
-    QWidget *centralWidget;
-    QFrame *frame;
-    QLabel *label;
-    QComboBox *comboBox;
-    QLabel *label_2;
-    QLineEdit *lineEdit;
-    QLabel *label_3;
-    QLabel *label_4;
-    QLabel *label_5;
-    QLabel *label_6;
-    QLabel *label_7;
-    QLabel *label_8;
-    QLabel *label_9;
-    QLineEdit *lineEdit_2;
-    QLineEdit *lineEdit_3;
-    QLineEdit *lineEdit_4;
-    QLineEdit *lineEdit_5;
-    QLineEdit *lineEdit_6;
-    QLineEdit *lineEdit_7;
-    QLineEdit *lineEdit_8;
-    QMenuBar *menuBar;
-    QStatusBar *statusBar;
-    GPSSensor* sensor_gps;
-    QGraphicsView *view;
-    QImage *image;
-    QPainter *painter;
-    QTimer *timer;
-    QGraphicsScene *scene;
-    QPushButton *pushButtonstart;
-    QPushButton *pushButtonend;
-    QPushButton *pushButton0;
-    QPushButton *pushButton1;
-    QPushButton *pushButton2;
-    QPushButton *pushButton3;
-    QPushButton *pushButton4;
-    QPushButton *pushButton5;
-    QPushButton *pushButton6;
-    QPushButton *pushButton7;
-    QPushButton *pushButton8;
-    QPushButton *pushButton9;
-    QPushButton *pushButton10;
-    QPushButton *pushButton11;
-    QPushButton *pushButton12;
-    QPushButton *pushButton13;
-    QPushButton *pushButton14;
-    QPushButton *pushButton15;
-    QPushButton *pushButton16;
-    QPushButton *pushButton17;
-    QPushButton *pushButton18;
-    QPushButton *pushButton19;
-    QPushButton *pushButton20;
-    QPushButton *pushButton21;
-    QPushButton *pushButton22;
-    QPushButton *pushButton23;
-    QPushButton *pushButton24;
-    QPushButton *pushButton25;
-    QPushButton *pushButton26;
-    QPushButton *pushButton27;
-    QPushButton *pushButton28;
-    QPushButton *pushButton29;
-    QPushButton *pushButton30;
-    QPushButton *pushButton31;
-    QPushButton *pushButton32;
-    QPushButton *pushButton33;
-    QPushButton *pushButton34;
-    QString qstr;
-    std::string sk;
-    std::stringstream ss;
-    int obs_modes = 0, speed_modes = 0, lane_num = 1, lane_status = 0;
-    int ready_exit = 0;
-    double jianju = 0.0;
-    bool starts = false;
-    bool is_forbidden = false;
-};
-
-#endif // GPS_COLLECT_H

BIN
src/ui/ui_ads_hmi/light_image/diaotou-black.png


BIN
src/ui/ui_ads_hmi/light_image/diaotou-green.png


BIN
src/ui/ui_ads_hmi/light_image/diaotou-red.png


BIN
src/ui/ui_ads_hmi/light_image/diaotou-yellow.png


BIN
src/ui/ui_ads_hmi/light_image/youguai-black.png


BIN
src/ui/ui_ads_hmi/light_image/youguai-green.png


BIN
src/ui/ui_ads_hmi/light_image/youguai-red.png


BIN
src/ui/ui_ads_hmi/light_image/youguai-yellow.png


BIN
src/ui/ui_ads_hmi/light_image/zhixing-black.png


BIN
src/ui/ui_ads_hmi/light_image/zhixing-green.png


BIN
src/ui/ui_ads_hmi/light_image/zhixing-red.png


BIN
src/ui/ui_ads_hmi/light_image/zhixing-yellow.png


BIN
src/ui/ui_ads_hmi/light_image/zuoguai-black.png


BIN
src/ui/ui_ads_hmi/light_image/zuoguai-green.png


BIN
src/ui/ui_ads_hmi/light_image/zuoguai-red.png


BIN
src/ui/ui_ads_hmi/light_image/zuoguai-yellow.png


+ 8 - 1
src/ui/ui_ads_hmi/look.cpp

@@ -104,8 +104,15 @@ Look_decition::~Look_decition()
 
 void Look_decition::timeoutslot()
 {
+    look1 = ServiceCarStatus.mfAcc;
+    look2 = ServiceCarStatus.mfBrake;
+    look3 = ServiceCarStatus.mfWheel;
+    look4 = ServiceCarStatus.speed;
+    look5 = ServiceCarStatus.mLidarObs;
+    look6 = ServiceCarStatus.mRadarObs;
+    look7 = ServiceCarStatus.mObs;
     lineEdit->setText(QString::number(look1));//决策油门
-    lineEdit_2->setText(QString::number(0.0));//决策刹车
+    lineEdit_2->setText(QString::number(look2));//决策刹车
     lineEdit_3->setText(QString::number(look3));//决策转向
     lineEdit_4->setText(QString::number(look4));//决策速度
     lineEdit_5->setText(QString::number(look5));//激光雷达距离

+ 1 - 0
src/ui/ui_ads_hmi/main.cpp

@@ -57,5 +57,6 @@ int main(int argc, char *argv[])
     w.setWindowTitle("ADS-UI-Ver2.0 ");
 //    w.showMinimized();  //apollo_fu 20200413
     w.showMaximized();
+
     return a.exec();
 }

+ 6 - 4
src/ui/ui_ads_hmi/ui_ads_hmi.pro

@@ -38,7 +38,6 @@ include(common/common.pri)
 SOURCES += \
         main.cpp \
         ADCIntelligentVehicle.cpp \
-    gps_collect.cpp \
     look.cpp \
     mobileye_info.cpp \
     perceptionoutput.cpp \
@@ -51,11 +50,12 @@ SOURCES += \
     ../../include/msgtype/gpsimu.pb.cc \
     ../../include/msgtype/canstate.pb.cc \
     ../../include/msgtype/v2x.pb.cc \
-    ../../include/msgtype/chassis.pb.cc
+    ../../include/msgtype/chassis.pb.cc \
+    ../../include/msgtype/mapreq.pb.cc  \
+    ../../include/msgtype/vbox.pb.cc
 
 HEADERS += \
         ADCIntelligentVehicle.h \
-    gps_collect.h \
     look.h \
     mobileye_info.h \
     ultrasonic_type.h \
@@ -69,7 +69,9 @@ HEADERS += \
     ../../include/msgtype/canstate.pb.h \
     ../../include/msgtype/gpsimu.pb.h \
     ../../include/msgtype/v2x.pb.h \
-    ../../include/msgtype/chassis.pb.h
+    ../../include/msgtype/chassis.pb.h \
+    ../../include/msgtype/mapreq.pb.h \
+    ../../include/msgtype/vbox.pb.h
 
 
 FORMS += \