Quellcode durchsuchen

Merge branch 'master' of http://116.63.46.168:3000/ADPilot/modularization

liyupeng vor 1 Monat
Ursprung
Commit
eef5eeed10

+ 4 - 0
src/controller/controller_chery_sterra_es_fcm/controller_chery_sterra_es_fcm.pro

@@ -34,8 +34,12 @@ else: unix:!android: target.path = /opt/$${TARGET}/bin
     error( "Couldn't find the controllercommon.pri.pri file!" )
 }
 
+#DEFINES += TESTBRAKE
+#DEFINES += PIDTEST
+
 INCLUDEPATH += $$PWD/../controllercommon
 
+
 LIBS += -livprotoif
 
 LIBS += -lcandbc

+ 155 - 392
src/controller/controller_chery_sterra_es_fcm/main.cpp

@@ -76,71 +76,11 @@ unsigned char ADS_COM3[24];
 
 static int gnState = 0; //0 not act  1 act
 
-CANPacker * gpPacker;
-
-
-std::vector<SignalPackValue> mvectorADSEPS1;
-std::vector<SignalPackValue> mvectorADSEPS3;
-std::vector<SignalPackValue> mvectorADSONEBOX1;
-std::vector<SignalPackValue> mvectorADSVCU1;
-
-
-double ADS_1_DrvCtrlReq = 0.0;
-double ADS_1_CtrlReqMod = 0.0;
-double ADS_1_DrvTarTqVld = 0.0;
-double ADS_1_DrvTarTqEnable = 0.0;
-double ADS_1_DrvTarTq = 0.0;
-double ADS_1_TarGearReq = 0.0;
-double ADS_1_TarGearReqVld = 0.0;
-double ADS_1_GearCtrlEnable = 1.0;
-
-
-double ADS_1_SteerAgReq = 0.0;
-double ADS_1_SteerAgVld = 0.0;
-double ADS_1_SteerPilotAgEna = 0.0;
 
 double gfWheelReq = 0.0;
 double gfTorqueReq = 0.0;
 double gfBrakeReq = 0.0;
 
-double ADS_1_PilotCtrlRepSta = 0.0;
-double ADS_1_PilotParkCtrlType =  0.0;
-double ADS_1_PilotParkBrkDecTar = 0.0;
-double ADS_1_PilotParkCtrlRepMod = 0.0;
-double ADS_1_PilotParkBrkDecTarVld = 0.0;
-double ADS_1_PilotParkBrkDecTarEnable = 0.0;
-double ADS_1_PilotParkDec2StpReq = 0.0;
-double ADS_1_PilotParkDriOffReq = 0.0;
-double ADS_1_ParkCtrlMod = 0.0;
-double ADS_1_ADCCAvl = 0.0;
-double ADS_1_StopDist = 0.0;
-
-double FCM_2_AebReqTyp = 0;
-double FCM_2_AebTarDec = 0;
-double FCM_2_AebTarDecVld = 1.0;
-double FCM_2_AwbReq = 0;
-double FCM_2_AwbLvl = 0;
-double FCM_2_BrkPreFillReq = 0;
-double FCM_2_AbaReq = 0;
-double FCM_2_AbaLvl = 0;
-double FCM_2_Avl = 1;
-
-double FCM_3_PilotParkCtrlRepSta = 0;
-double FCM_3_PilotCtrlType = 0;
-double FCM_3_PilotkBrkDecTar = 0;
-double FCM_3_PilotBrkDecTarVld = 1;
-double FCM_3_PilotBrkDecTarReq = 0;
-double FCM_3_PilotDec2StpReq = 0;
-double FCM_3_PilotDriOffReq = 0;
-double CutOutFreshvalues_2CB_S = 0.0;
-double CutOutMAC_2CB_S = 0.0;
-
-double FCM_2_SysStatus = 1;
-double ADS_2_TTC = 5.11;
-double ADS_2_AEBStatus = 0;
-double ADS_2_ClosingSpeed = 255;
-
-double ADS_3_ACCSts = 0;
 
 static bool gbSendBrake = false;
 
@@ -155,42 +95,23 @@ static bool gbPrintPIDOut = true;
 
 static double gfVehAcc = 0.0;
 
-
-
-void set_EPS1_signal(std::string strsigname,double value){
-    gpsterraes->set_EPS1_signal(strsigname,value);
-}
-
-void set_EPS3_signal(std::string strsigname,double value){
-    gpsterraes->set_EPS3_signal(strsigname,value);
-}
-
-void set_ONEBOX1_signal(std::string strsigname,double value){
-    gpsterraes->set_ONEBOX1_signal(strsigname,value);
-}
-
-void set_VCU1_signal(std::string strsigname,double value){
-    gpsterraes->set_VCU1_signal(strsigname,value);
+void SetMsgSignal(std::string strmsgname,std::string strsigname,double fvalue){
+    gpsterraes->SetMsgSignal(strmsgname,strsigname,fvalue);
 }
 
-void set_ONEBOX2_signal(std::string strsigname,double value){
-    gpsterraes->set_ONEBOX2_signal(strsigname,value);
-}
-
-void set_ONEBOX3_signal(std::string strsigname,double value){
-    gpsterraes->set_ONEBOX3_signal(strsigname,value);
-}
 
-void set_ADSCOM3_Signal(std::string strsigname,double value){
-    gpsterraes->set_ADSCOM3_signal(strsigname,value);
-}
+void ExecSend();
 
-void set_ADSCOM2_Signal(std::string strsigname,double value){
-    gpsterraes->set_ADSCOM2_signal(strsigname,value);
+double acctotorque(double facc)
+{
+    double fVehWeight = 1800;
+    double fRollForce = 50;
+    const double fRatio = 2.5;
+    double fNeed = fRollForce + fVehWeight*facc;
+    double ftorque = fNeed/fRatio;
+    return ftorque;
 }
 
-void ExecSend();
-
 double  PIDTorque(double torque)
 {
     if(gbUsePID == false)return torque;
@@ -217,8 +138,7 @@ double  PIDTorque(double torque)
     if(fAccAjust>MAXACC)fAccAjust = MAXACC;
     if(fAccAjust<=0)fAccAjust = 0.0;
 
-    double fNeed = fRollForce + fVehWeight*fAccAjust;
-    double ftorqueAjust = fNeed/fRatio;
+    double ftorqueAjust = acctotorque(fAccAjust);
 
     if(gbPrintPIDOut)
     {
@@ -232,52 +152,86 @@ double  PIDTorque(double torque)
     return ftorqueAjust;
 }
 
+#ifdef TESTBRAKE
 int testnum = 0;
+#endif
 
 int testwheel = 0;
+
+#ifdef PIDTEST
+int pidtestnstep = 0;
+double fpidtestacc = 1.0;
+double fpidtestmaxvel = 15.0;
+#endif
+
 void executeDecition(const iv::brain::decition &decition)
 {
 
-
     double fwheel = decition.wheelangle()*0.9;
     if(fwheel<-430)fwheel = 430;
     if(fwheel>380)fwheel = 380;
-    ADS_1_SteerAgReq =fwheel;
 
-//    if(testwheel<1000)ADS_1_SteerAgReq = 180;
-//    else ADS_1_SteerAgReq = -180;
-//    testwheel++;
-//    if(testwheel > 2000)testwheel = 0;
+    double ftorque = decition.torque();
+    double fbrake = decition.brake();
 
-//    std::cout<<"brake: "<<decition.brake()<<std::endl;
+#ifdef PIDTEST
+    if(gfVehSpd>=fpidtestmaxvel)
+    {
+        pidtestnstep = 1;
+    }
 
-//    if((testnum < 1000) || (testnum > 1500))
-//    {
-    if(decition.brake()<(-0.0001))
+    if(pidtestnstep == 1)
     {
-        ADS_1_DrvTarTq = 0.0;
+        ftorque = 0;
+        fbrake = -1.0;
+    }
 
-        FCM_3_PilotDriOffReq = 0.0;
-        FCM_3_PilotDec2StpReq = 1.0;
-        FCM_3_PilotkBrkDecTar = decition.brake();// 0.0;//decition.brake();
-        FCM_2_AebTarDec = 0;
-        FCM_3_PilotBrkDecTarVld = 1.0;
-        FCM_3_PilotCtrlType = 0.0;
-        FCM_3_PilotBrkDecTarReq = 1.0;
+    if(pidtestnstep == 0)
+    {
+        ftorque = PIDTorque(acctotorque(fpidtestacc));
+    }
+#endif
+
+    SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgReq",fwheel);
+    SetMsgSignal("ADS_EPS_1","ADS_1_LdwWarningCmdVld",2.0);
+    SetMsgSignal("ADS_EPS_1","ADS_1_SteerMaxTqReq",3.0);
+    SetMsgSignal("ADS_EPS_1","ADS_1_SteerMinTqReq",-3.0);
+    SetMsgSignal("ADS_EPS_1","ADS_1_ADSHealthSts",1.0);
+    SetMsgSignal("ADS_EPS_1","CutOutFreshvalues_2CB_S",1.0);
+    SetMsgSignal("ADS_EPS_1","CutOutMAC_2CB_S",1.0);
+
+#ifdef TESTBRAKE
+    if((testnum < 1000) || (testnum > 1500))
+    {
+#endif
+    if(fbrake<(-0.0001))
+    {
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",0.0);
 
-        FCM_2_AebTarDecVld = 1.0;
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",1.0);
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",decition.brake());
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotCtrlType",0.0);
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",1.0);
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",1.0);
 
-        FCM_3_PilotParkCtrlRepSta = 1.0;
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",0.0);
 
-        if(gbSendBrake == false)
+        if(gbSendBrake == false)   //if brake is unavailable
         {
-            FCM_3_PilotDec2StpReq = 0.0;
-            FCM_3_PilotBrkDecTarReq = 0.0;
-            FCM_3_PilotBrkDecTarVld = 1.0;
-            FCM_3_PilotkBrkDecTar = 0.0;
-            FCM_2_AebTarDec = 1.0;
-            FCM_3_PilotParkCtrlRepSta = 0.0;
-            FCM_2_AebTarDecVld = 1.0;
+
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",0.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",0.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotCtrlType",0.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",0.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",0.0);
+
+            SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
+            SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
 
             if(fabs(gfVehSpd)>0.1)
             {
@@ -290,63 +244,64 @@ void executeDecition(const iv::brain::decition &decition)
 
     else
     {
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",ftorque);
         if(fabs(gfVehSpd) < 0.1)
         {
-            FCM_3_PilotDriOffReq = 1.0;
-            FCM_3_PilotDec2StpReq = 0.0;
-            FCM_3_PilotBrkDecTarReq = 1.0;
-            FCM_3_PilotBrkDecTarVld = 1.0;
-            FCM_3_PilotkBrkDecTar = 1.0;
-            FCM_2_AebTarDec = 1.0;
-            FCM_3_PilotParkCtrlRepSta = 1.0;
- //           ADS_1_PilotParkCtrlRepMod = 1.0;
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",1.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",1.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",1.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",1.0);
         }
         else
         {
-            FCM_3_PilotDec2StpReq = 0.0;
-            FCM_3_PilotBrkDecTarReq = 0.0;
-            FCM_3_PilotBrkDecTarVld = 1.0;
-            FCM_3_PilotkBrkDecTar = 0.0;
-            FCM_2_AebTarDec = 1.0;
-            FCM_3_PilotParkCtrlRepSta = 0.0;
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",0.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",0.0);
+            SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",0.0);
         }
-        FCM_2_AebTarDecVld = 1.0;
-        ADS_1_DrvTarTq = decition.torque();
+
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
+        SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",0.0);
+
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
 
     }
-//    }
 
-//    else
-//    {
+#ifdef TESTBRAKE
+   }
+
+   else
+   {
 
-//        if(fabs(gfVehSpd) < 0.1)
-//        {
-//            FCM_3_PilotDriOffReq = 1.0;
-//            FCM_3_PilotDec2StpReq = 0.0;
-//            FCM_3_PilotBrkDecTarReq = 1.0;
-//            FCM_3_PilotBrkDecTarVld = 1.0;
-//            FCM_3_PilotkBrkDecTar = 1.0;
-//            FCM_2_AebTarDec = 1.0;
-//            FCM_3_PilotParkCtrlRepSta = 1.0;
-//        }
-//        else
-//        {
-//            FCM_3_PilotDec2StpReq = 0.0;
-//            FCM_3_PilotBrkDecTarReq = 0.0;
-//            FCM_3_PilotBrkDecTarVld = 1.0;
-//            FCM_3_PilotkBrkDecTar = 0.0;
-//            FCM_2_AebTarDec = 1.0;
-//            FCM_3_PilotParkCtrlRepSta = 0.0;
-//        }
-//        ADS_1_DrvTarTq = 300;
-//        FCM_2_AebTarDecVld = 1.0;
+       if(fabs(gfVehSpd) < 0.1)
+       {
+           SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",1.0);
+           SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",1.0);
+           SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",1.0);
+           SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",1.0);
+       }
+       else
+       {
+           SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",0.0);
+           SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
+           SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",0.0);
 
-//    }
+       }
+       SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
+       SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
+       SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",0.0);
+       SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
 
-//    testnum++;
-//    if(testnum > 1500)testnum = 0;
+       SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",300);
 
 
+   }
+
+   testnum++;
+   if(testnum > 1500)testnum = 0;
+#endif
+
 
 
 //    std::cout<<" send dec. "<<std::endl;
@@ -361,33 +316,24 @@ void Activate()
     //    {
     std::cout<<" activate "<<std::endl;
     for(int i = 0; i < 3; i++){
-        ADS_1_DrvCtrlReq = 1.0;
-        ADS_1_CtrlReqMod = 1.0;  //1 Pilot  2 Park
-        ADS_1_DrvTarTqVld = 1.0;
-        ADS_1_DrvTarTqEnable = 1.0;
-        ADS_1_DrvTarTq = 0.0;
-        ADS_1_TarGearReq = 4.0;  //1 P 4 D
-        ADS_1_TarGearReqVld = 1.0;
-        ADS_1_GearCtrlEnable = 0.0;
 
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvCtrlReq",1.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_CtrlReqMod",1.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTqVld",1.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTqEnable",1.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",0.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_ADCCAvl",1.0);
 
+        SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgReq",gfWheelReq);
+        SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgVld",1.0);
+        SetMsgSignal("ADS_EPS_1","ADS_1_SteerPilotAgEna",2.0);
 
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_Avl",1.0);
 
-        ADS_1_SteerAgReq = gfWheelReq;
-        ADS_1_SteerAgVld = 1.0;
-        ADS_1_SteerPilotAgEna = 2.0;
+        SetMsgSignal("ADS_COM_3","FCM_2_SysStatus",0.0);
 
-        ADS_1_PilotParkDec2StpReq = 1.0;
-        ADS_1_ParkCtrlMod = 1.0;
-
-        ADS_1_ADCCAvl = 1.0;
-
-        FCM_2_Avl = 1.0;
-
-        ADS_3_ACCSts = 3.0;
-
-        FCM_2_SysStatus = 0;
-        ADS_2_AEBStatus = 1;
+        SetMsgSignal("ADS_COM_2","ADS_2_AEBStatus",0.0);
+        SetMsgSignal("ADS_COM_2","ADS_3_ACCSts",3.0);
 
 
 
@@ -401,52 +347,27 @@ void Activate()
 
 void UnAcitvate()
 {
-    if(fabs(gfVehSpd)<0.1)
-    {
-        for(int i = 0; i < 3; i++){
-            ADS_1_DrvCtrlReq = 1.0;
-            ADS_1_CtrlReqMod = 2.0;
-            ADS_1_DrvTarTqVld = 1.0;
-            ADS_1_DrvTarTqEnable = 1.0;
-            ADS_1_DrvTarTq = 0.0;
-            ADS_1_TarGearReq = 1.0;
-            ADS_1_TarGearReqVld = 1.0;
-            ADS_1_GearCtrlEnable = 0.0;
-
-            ADS_1_SteerAgReq = 0.0;
-            ADS_1_SteerAgVld = 1.0;
-            ADS_1_SteerPilotAgEna = 1.0;
-
-
-            ExecSend();
-            std::this_thread::sleep_for(std::chrono::milliseconds(10));
-        }
-    }
+
     for(int i = 0; i < 3; i++){
-        ADS_1_DrvCtrlReq = 0.0;
-        ADS_1_CtrlReqMod = 0.0;
-        ADS_1_DrvTarTqVld = 0.0;
-        ADS_1_DrvTarTqEnable = 0.0;
-        ADS_1_DrvTarTq = 0.0;
- //       ADS_1_TarGearReq = 1.0;
-        ADS_1_TarGearReqVld = 0.0;
-        ADS_1_GearCtrlEnable = 1.0;
 
-        ADS_1_SteerAgReq = 0.0;
-        ADS_1_SteerAgVld = 0.0;
-        ADS_1_SteerPilotAgEna = 0.0;
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvCtrlReq",0.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_CtrlReqMod",0.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTqVld",0.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTqEnable",0.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",0.0);
+        SetMsgSignal("ADS_VCU_1","ADS_1_ADCCAvl",0.0);
 
-        ADS_1_PilotParkDec2StpReq = 0.0;
-        ADS_1_ParkCtrlMod = 0.0;
+        SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgReq",0.0);
+        SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgVld",0.0);
+        SetMsgSignal("ADS_EPS_1","ADS_1_SteerPilotAgEna",0.0);
 
-        ADS_1_ADCCAvl = 0.0;
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_Avl",1.0);
 
-        ADS_3_ACCSts = 0;
+        SetMsgSignal("ADS_COM_3","FCM_2_SysStatus",1.0);
 
-        FCM_2_Avl = 1.0;
+        SetMsgSignal("ADS_COM_2","ADS_2_AEBStatus",0.0);
+        SetMsgSignal("ADS_COM_2","ADS_3_ACCSts",0.0);
 
-        FCM_2_SysStatus = 1;
-        ADS_2_AEBStatus = 0;
 
         ExecSend();
         std::this_thread::sleep_for(std::chrono::milliseconds(10));
@@ -536,90 +457,25 @@ void PrepareMsg()
 {
     static int rollcouter = 0;
     //    std::cout<<" roll count:: "<<rollcouter<<std::endl;
-
-    set_EPS1_signal("ADS_1_RollgCntr1",rollcouter);
-    set_EPS1_signal("ADS_1_Resd1",0.0);
-    set_EPS1_signal("ADS_1_SteerAgReq",ADS_1_SteerAgReq);
-    set_EPS1_signal("ADS_1_SteerAgVld",ADS_1_SteerAgVld);
-    set_EPS1_signal("ADS_1_SteerPilotAgEna",ADS_1_SteerPilotAgEna);
-    set_EPS1_signal("ADS_1_RollgCntr2",rollcouter);
-    set_EPS1_signal("ADS_1_Resd2",0.0);
-    set_EPS1_signal("ADS_1_SteerTqEna",1.0);
-    set_EPS1_signal("ADS_1_LdwWarningCmd",0.0);
-    set_EPS1_signal("ADS_1_LdwWarningCmdVld",2.0);
-    set_EPS1_signal("ADS_1_SteerMaxTqReq",60.0);
-    set_EPS1_signal("ADS_1_SteerMinTqReq",-60.0);
-    set_EPS1_signal("ADS_1_ADSHealthSts",1.0);
-    set_EPS1_signal("CutOutFreshvalues_2CB_S",1.0);
-    set_EPS1_signal("CutOutMAC_2CB_S",1.0);
+    SetMsgSignal("ADS_EPS_1","ADS_1_RollgCntr1",rollcouter);
+    // set_EPS1_signal("CutOutFreshvalues_2CB_S",1.0);
+    // set_EPS1_signal("CutOutMAC_2CB_S",1.0);
     gpsterraes->GetEPS1Data(ADS_EPS_1);
 
-    set_VCU1_signal("ADS_1_RollgCntr1",rollcouter);
-    set_VCU1_signal("ADS_1_Resd1",0);
-    set_VCU1_signal("ADS_1_DrvTarTq",ADS_1_DrvTarTq);
-    set_VCU1_signal("ADS_1_DrvTarTqVld",ADS_1_DrvTarTqVld);
-    set_VCU1_signal("ADS_1_DrvCtrlReq",ADS_1_DrvCtrlReq);
-    set_VCU1_signal("ADS_1_CtrlReqMod",ADS_1_CtrlReqMod);
-    set_VCU1_signal("ADS_1_DrvTarTqEnable",ADS_1_DrvTarTqEnable);
-    set_VCU1_signal("ADS_1_RollgCntr2",rollcouter);
-    set_VCU1_signal("ADS_1_Resd2",0);
-//    set_VCU1_signal("ADS_1_TarGearReq",ADS_1_TarGearReq);
-//    set_VCU1_signal("ADS_1_TarGearReqVld",ADS_1_TarGearReqVld);
-//    set_VCU1_signal("ADS_1_GearCtrlEnable",ADS_1_GearCtrlEnable);
-    set_VCU1_signal("ADS_1_ADCCAvl",ADS_1_ADCCAvl);
+    SetMsgSignal("ADS_VCU_1","ADS_1_RollgCntr1",rollcouter);
+    SetMsgSignal("ADS_VCU_1","ADS_1_RollgCntr2",rollcouter);
     gpsterraes->GetVCU1Data(ADS_VCU_1);
 
-//    set_ONEBOX1_signal("ADS_1_RollgCntr1",rollcouter);
-//    set_ONEBOX1_signal("ADS_1_Resd1",0);
-//    set_ONEBOX1_signal("ADS_1_PilotCtrlRepSta",ADS_1_PilotCtrlRepSta);
-//    set_ONEBOX1_signal("ADS_1_PilotParkCtrlType",ADS_1_PilotParkCtrlType);
-//    set_ONEBOX1_signal("ADS_1_PilotParkBrkDecTar",ADS_1_PilotParkBrkDecTar);
-//    set_ONEBOX1_signal("ADS_1_PilotParkCtrlRepMod",ADS_1_PilotParkCtrlRepMod);
-//    set_ONEBOX1_signal("ADS_1_PilotParkBrkDecTarVld",ADS_1_PilotParkBrkDecTarVld);
-//    set_ONEBOX1_signal("ADS_1_PilotParkBrkDecTarEnable",ADS_1_PilotParkBrkDecTarEnable);
-//    set_ONEBOX1_signal("ADS_1_PilotParkDec2StpReq",ADS_1_PilotParkDec2StpReq);
-//    set_ONEBOX1_signal("ADS_1_PilotParkDriOffReq",ADS_1_PilotParkDriOffReq);
-//    set_ONEBOX1_signal("ADS_1_ParkCtrlMod",ADS_1_ParkCtrlMod);
-//    set_ONEBOX1_signal("ADS_1_PilotCtrlRepSta",ADS_1_PilotCtrlRepSta);
-//    set_ONEBOX1_signal("ADS_1_StopDist",ADS_1_StopDist);
-//    set_ONEBOX1_signal("ADS_1_PilotParkCtrlRepMod",ADS_1_PilotParkCtrlRepMod);
-//    gpsterraes->GetONEBOX1Data(ADS_ONEBOX_1);
-
-    set_ONEBOX2_signal("FCM_2_RollgCntr1",rollcouter);
-    set_ONEBOX2_signal("FCM_2_Resd1",rollcouter);
-    set_ONEBOX2_signal("FCM_2_AebReqTyp",FCM_2_AebReqTyp);
-    set_ONEBOX2_signal("FCM_2_AebTarDec",FCM_2_AebTarDec);
-    set_ONEBOX2_signal("FCM_2_AebTarDecVld",FCM_2_AebTarDecVld);
-    set_ONEBOX2_signal("FCM_2_AwbReq",FCM_2_AwbReq);
-    set_ONEBOX2_signal("FCM_2_AwbLvl",FCM_2_AwbLvl);
-    set_ONEBOX2_signal("FCM_2_BrkPreFillReq",FCM_2_BrkPreFillReq);
-    set_ONEBOX2_signal("FCM_2_AbaReq",FCM_2_AbaReq);
-    set_ONEBOX2_signal("FCM_2_AbaLvl",FCM_2_AbaLvl);
-    set_ONEBOX2_signal("FCM_2_Avl",FCM_2_Avl);
+    SetMsgSignal("ADS_ONEBOX_2","FCM_2_RollgCntr1",rollcouter);
     gpsterraes->GetONEBOX2Data(ADS_ONEBOX_2);
 
-
-    set_ONEBOX3_signal("FCM_3_RollgCntr1",rollcouter);
-    set_ONEBOX3_signal("FCM_3_Resd1",rollcouter);
-    set_ONEBOX3_signal("FCM_3_PilotParkCtrlRepSta",FCM_3_PilotParkCtrlRepSta);
-    set_ONEBOX3_signal("FCM_3_PilotCtrlType",FCM_3_PilotCtrlType);
-    set_ONEBOX3_signal("FCM_3_PilotkBrkDecTar",FCM_3_PilotkBrkDecTar);
-    set_ONEBOX3_signal("FCM_3_PilotBrkDecTarVld",FCM_3_PilotBrkDecTarVld);
-    set_ONEBOX3_signal("FCM_3_PilotBrkDecTarReq",FCM_3_PilotBrkDecTarReq);
-    set_ONEBOX3_signal("FCM_3_PilotDec2StpReq",FCM_3_PilotDec2StpReq);
-    set_ONEBOX3_signal("FCM_3_PilotDriOffReq",FCM_3_PilotDriOffReq);
-    set_ONEBOX3_signal("CutOutFreshvalues_2CB_S",CutOutFreshvalues_2CB_S);
-    set_ONEBOX3_signal("CutOutMAC_2CB_S",CutOutMAC_2CB_S);
+    SetMsgSignal("ADS_ONEBOX_3","FCM_3_RollgCntr1",rollcouter);
     gpsterraes->GetONEBOX3Data(ADS_ONEBOX_3);
 
-    set_ADSCOM3_Signal("ADS_3_RollgCntr1",rollcouter);
-    set_ADSCOM3_Signal("ADS_3_ACCSts",ADS_3_ACCSts);
+    SetMsgSignal("ADS_COM_3","ADS_3_RollgCntr1",rollcouter);
     gpsterraes->GetADSCOM3Data(ADS_COM3);
 
-    set_ADSCOM2_Signal("ADS_2_RollgCntr1",rollcouter);
-    set_ADSCOM2_Signal("ADS_2_AEBStatus",ADS_2_AEBStatus);
-    set_ADSCOM2_Signal("ADS_2_TTC",ADS_2_TTC);
-    set_ADSCOM2_Signal("FCM_2_SysStatus",FCM_2_SysStatus);
+    SetMsgSignal("ADS_COM_2","ADS_2_RollgCntr1",rollcouter);
     gpsterraes->GetADSCOM2Data(ADS_COM2);
 
     rollcouter++;
@@ -743,92 +599,6 @@ void initial()
     }
 }
 
-void SendEPS3()
-{
-    static int rollcouter = 0;
-    gpsterraes->GetEPS3Data(ADS_EPS_3);
-    ExecSend();
-    rollcouter++;
-    if(rollcouter>14)rollcouter = 0;
-}
-
-void SendEPS1()
-{
-    static int rollcouter = 0;
-//    std::cout<<" roll count:: "<<rollcouter<<std::endl;
-
-    set_EPS1_signal("ADS_1_RollgCntr1",rollcouter);
-    set_EPS1_signal("ADS_1_Resd1",0.0);
-    gpsterraes->GetEPS1Data(ADS_EPS_1);
-    ExecSend();
-    rollcouter++;
-    if(rollcouter>14)rollcouter = 0;
-}
-
-void testes()
-{
-    int i = 0;
-    int rollcouter = 0;
-    double fwheelang = 90.0;
-
-    set_EPS1_signal("ADS_1_RollgCntr1",rollcouter);
-    set_EPS1_signal("ADS_1_Resd1",0.0);
-    set_EPS1_signal("ADS_1_SteerAgReq",fwheelang);
-    set_EPS1_signal("ADS_1_SteerAgVld",1.0);
-    set_EPS1_signal("ADS_1_SteerPilotAgEna",0.0);
-    set_EPS1_signal("ADS_1_RollgCntr2",rollcouter);
-    set_EPS1_signal("ADS_1_Resd2",0.0);
-    set_EPS1_signal("ADS_1_SteerTqEna",1.0);
-    set_EPS1_signal("ADS_1_LdwWarningCmd",0.0);
-    set_EPS1_signal("ADS_1_LdwWarningCmdVld",2.0);
-    set_EPS1_signal("ADS_1_SteerMaxTqReq",10.0);
-    set_EPS1_signal("ADS_1_SteerMinTqReq",1.0);
-    set_EPS1_signal("ADS_1_ADSHealthSts",1.0);
-    set_EPS1_signal("CutOutFreshvalues_2CB_S",1.0);
-    set_EPS1_signal("CutOutMAC_2CB_S",1.0);
-
-    set_EPS3_signal("ADS_3_RollgCntr1",rollcouter);
-    set_EPS3_signal("ADS_3_Resd1",0.0);
-    set_EPS3_signal("ADS_3_SteerParkAgReq",0.0);
-    set_EPS3_signal("ADS_3_SteerParkAgVld",0.0);
-    set_EPS3_signal("ADS_3_SteerParkAgEna",0.0);
-    set_EPS3_signal("ADS_3_RollgCntr2",rollcouter);
-    set_EPS3_signal("ADS_3_Resd2",0.0);
-    set_EPS3_signal("ADS_3_ParkFcnMode",0.0);
-    set_EPS3_signal("ADS_3_ADSParkHealthSts",0.0);
-
-    for(i=0;i<10;i++)
-    {
-        set_EPS1_signal("ADS_1_SteerPilotAgEna",0.0);
-        SendEPS1();
-        std::this_thread::sleep_for(std::chrono::milliseconds(10));
-    }
-
-    // for(i=0;i<10;i++)
-    // {
-    //     set_EPS3_signal("ADS_3_SteerParkAgEna",1.0);
-    //     set_EPS3_signal("ADS_3_SteerParkAgReq",0.0);
-    //     set_EPS3_signal("ADS_3_SteerParkAgVld",0.0);
-    //     SendEPS3();
-    //     std::this_thread::sleep_for(std::chrono::milliseconds(10));
-    // }
-
-    for(i=0;i<3000;i++)
-    {
-        set_EPS1_signal("ADS_1_SteerPilotAgEna",2.0);
-        set_EPS1_signal("ADS_1_SteerAgReq",fwheelang);
-        set_EPS1_signal("ADS_1_SteerAgVld",1.0);
-        SendEPS1();
-        std::this_thread::sleep_for(std::chrono::milliseconds(10));
-    }
-
-    for(i=0;i<10;i++)
-    {
-        set_EPS1_signal("ADS_1_SteerPilotAgEna",0.0);
-        SendEPS1();
-        std::this_thread::sleep_for(std::chrono::milliseconds(10));
-    }
-}
 
 void sendthread()
 {
@@ -901,6 +671,7 @@ void sendthread()
 #ifdef Q_OS_LINUX
 void sig_int(int signo)
 {
+    (void)signo;
     gbSendRun = false;
     gpsendthread->join();
 
@@ -1078,14 +849,6 @@ int main(int argc, char *argv[])
     gdecition_def.set_brake_type(0);
     gdecition_def.set_auto_mode(0);
 
-    //    gdecition_def.set_angle_mode(0);
-    //    gdecition_def.set_angle_active(0);
-    //    gdecition_def.set_acc_active(0);
-    //    gdecition_def.set_brake_active(0);
-    //    gdecition_def.set_brake_type(0);
-    //    gdecition_def.set_auto_mode(0);
-
-  //  gTime.start();
 
     iv::xmlparam::Xmlparam xp(strpath.toStdString());