Browse Source

complete ros2 fcm. add ros2 lidar_cnn,not complete.

yuchuli 3 months ago
parent
commit
7a3c89475f

+ 1 - 0
src/ros2/AutoWare2025/src/adc_controller_chery_sterra_es_fcm/include/adc_controller_chery_sterra_es/adc_controller_chery_sterra_es_core.hpp

@@ -64,6 +64,7 @@ private:
     void Activate();
     void UnAcitvate();
     void initial();
+    void PrepareMsg();
 
 private:
     bool gbHaveVehSpd = false;

+ 299 - 321
src/ros2/AutoWare2025/src/adc_controller_chery_sterra_es_fcm/src/adc_controller_chery_sterra_es_core.cpp

@@ -12,81 +12,39 @@
 
 #include "adc_controller_chery_sterra_es/fcm.h"
 
-using std::placeholders::_1;
-using std::placeholders::_2;
+#include "candbc.h"
+#include "adc_controller_chery_sterra_es/sterraes.h"
 
-// signal: @ACC_LatAngReq    //更改CANid
-#define ECU_1C4_ACC_LatAngReq_CovFactor (0.1)
-// conversion value to CAN signal
-#define ECU_1C4_ACC_LatAngReq_toS(x) ((int16_t)((x) / 0.1 + 7200))
+sterraes * gpsterraes;
 
-// signal: @ACC_MotorTorqueMaxLimitRequest
-#define ECU_1C4_ACC_MotorTorqueMaxLimitRequest_CovFactor (0.02)
-// conversion value to CAN signal
-#define ECU_1C4_ACC_MotorTorqueMaxLimitRequest_toS(x) ((int16_t)((x) / 0.02 + 1024))
+unsigned char ADS_EPS_1[24];// 0x195/405
+unsigned char ADS_EPS_3[24]; // 0x1BC/444
+unsigned char ADS_ONEBOX_1[24];// 0x159/345
+unsigned char ADS_VCU_1[24];   // 0x167/359
+unsigned char ADS_ONEBOX_2[24];
+unsigned char ADS_ONEBOX_3[24];
+unsigned char ADS_COM2[8];
+unsigned char ADS_COM3[24];
 
-// signal: @ACC_MotorTorqueMinLimitRequest
-#define ECU_1C4_ACC_MotorTorqueMinLimitRequest_CovFactor (0.02)
-// conversion value to CAN signal
-#define ECU_1C4_ACC_MotorTorqueMinLimitRequest_toS(x) ((int16_t)((x) / 0.02 + 1024))
+static int gnState = 0; //0 not act  1 act
 
-typedef struct
-{
-    int16_t ACC_LatAngReq;
-    //uint8_t ADS_Reqmode;  //20221102, 新车没有此信号
-    int16_t ACC_MotorTorqueMaxLimitRequest;
-    uint8_t ACC_LatAngReqActive;
-    int16_t ACC_MotorTorqueMinLimitRequest;
-    //uint8_t ACC_ADCReqType; //20221102, 新车没有此信号
-} ECU_1C4_t;
-
-// signal: @ACC_AccTrqReq
-#define ECU_24E_ACC_AccTrqReq_CovFactor (1)
-// conversion value to CAN signal
-#define ECU_24E_ACC_AccTrqReq_toS(x) ((int16_t)((x) + 16384))
-
-// signal: @ACC_ACCTargetAcceleration
-#define ECU_24E_ACC_ACCTargetAcceleration_CovFactor (0.05)
-// conversion value to CAN signal
-#define ECU_24E_ACC_ACCTargetAcceleration_toS(x) ((int16_t)((x) / 0.05 + 100))
-
-// signal: @ACC_AEBTargetDeceleration
-#define ECU_24E_ACC_AEBTargetDeceleration_CovFactor (0.0005)
-// conversion value to CAN signal
-#define ECU_24E_ACC_AEBTargetDeceleration_toS(x) ((int32_t)((x) / 0.0005 + 32000))
+double gfWheelReq = 0.0;
+double gfTorqueReq = 0.0;
+double gfBrakeReq = 0.0;
 
+static bool gbSendBrake = false;
+
+static double TorqueRatio = 1.4;
+
+
+using std::placeholders::_1;
+using std::placeholders::_2;
 
-static int gnState = 0; //0 not act  1 act
-typedef struct
-{
-    int16_t ACC_AccTrqReq;
-    uint8_t ACC_AccTrqReqActive;
-    int16_t ACC_ACCTargetAcceleration;
-    int32_t ACC_AEBTargetDeceleration;
-    uint8_t ACC_AEBVehilceHoldReq;
-    uint8_t ADCReqMode;
-    uint8_t ACC_AEBActive;
-    uint8_t ACC_Driveoff_Request;
-    uint8_t ACC_DecToStop;
-    uint8_t ACC_CDDActive;
-    uint8_t ACC_ACCMode;
-} ECU_24E_t;
-
-typedef struct
-{
-    uint8_t CdcDoor;
-    uint8_t res1;
-    uint8_t res2;
-    uint8_t ADS_UDLCTurnLightReq;
-} ECU_25E_t;  //zhuanxiangdeng IDgenghuan
 
-unsigned char byte_1C4[64];//byte_144[8];
-unsigned char byte_24E[64];
-unsigned char byte_25E[32];
 
-ECU_1C4_t _m1C4 = {0,0,0,0};
-ECU_24E_t _m24E = {0,0,0,0,0,0,0,0,0,0,0};
-ECU_25E_t _m25E = {0,0,0,0};
+static void SetMsgSignal(std::string strmsgname,std::string strsigname,double fvalue){
+    gpsterraes->SetMsgSignal(strmsgname,strsigname,fvalue);
+}
 
 
 void service1_enablechassis(const std::shared_ptr<adc_autoware_msgs::srv::ChassisEnableCtrl::Request> request,
@@ -274,225 +232,170 @@ void adc_controller_chery_sterra_es_core::topic_cmd_callback(const autoware_cont
 
 void adc_controller_chery_sterra_es_core::executeDecition(const iv::brain::decition &decition)
 {
+    double fwheel = decition.wheelangle();
+    if(fwheel<-430)fwheel = 430;
+    if(fwheel>380)fwheel = 380;
 
+    double ftorque = decition.torque() * TorqueRatio;
+    if((ftorque>30)&&(ftorque<150))ftorque = 150;
+    double fbrake = decition.brake();
 
 
 
-    static int xieya = 50;
-//     std::cout<<"acc is "<<decition.torque()<<" ang is "<<decition.wheelangle()<<std::endl;
-//     std::cout<<"angle_mode is "<<decition.angle_mode()<<" angle_active is "<<decition.angle_active()<<std::endl;
-//     std::cout<<"brake_type is "<<decition.brake_type()<<" acc_active is "<<decition.acc_active()<<std::endl;
-//     std::cout<<"brake is "<<decition.brake()<<" brake_active is "<<decition.brake_active()<<std::endl;
-//     std::cout<<"auto_mode is "<<decition.auto_mode()<<" rightlamp is "<<decition.rightlamp()<<std::endl;
-
-    double fWheelAngleReq = decition.wheelangle();
- //   double fsendinter = 0.02;
-//    if(fabs(fWheelAngleReq - gfWheelAngle)/fsendinter > gfWheelSpeedLim)
-//    {
-//        if(fWheelAngleReq > gfWheelAngle)
-//        {
-//            fWheelAngleReq = gfWheelAngle + fsendinter * gfWheelSpeedLim;
-//        }
-//        else
-//        {
-//            fWheelAngleReq = gfWheelAngle - fsendinter * gfWheelSpeedLim;
-//        }
 
-//    }
+    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);
 
-//    std::cout<<" wheel req: "<<decition.wheelangle()<<" real send : "<<fWheelAngleReq<<" real whhel:"<<gfWheelAngle<< std::endl;
-
-    _m1C4.ACC_LatAngReq = ECU_1C4_ACC_LatAngReq_toS(fWheelAngleReq);
-    //_m1C4.ADS_Reqmode = decition.angle_mode(); //20221102,新车没有此信号
-    _m1C4.ACC_MotorTorqueMaxLimitRequest = ECU_1C4_ACC_MotorTorqueMaxLimitRequest_toS(10);
-    _m1C4.ACC_LatAngReqActive = decition.angle_active();
-    _m1C4.ACC_MotorTorqueMinLimitRequest = ECU_1C4_ACC_MotorTorqueMinLimitRequest_toS(-10);
-//    _m144.ACC_ADCReqType = decition.brake_type();//ADC请求类型(制动时为1,其余情况为0)
-    if(decition.brake()>(-0.0000001))
+#ifdef TESTBRAKE
+    if((testnum < 1000) || (testnum > 1500))
     {
-        //_m144.ACC_ADCReqType = 0;//ADC请求类型(制动时为1,其余情况为0)//20221102,新车没有此信号
-       // _m24B.ADCReqMode = 0;//20221102,新车没有此信号
-        _m24E.ACC_DecToStop =0;
-    }
-    else
+#endif
+    if(fbrake<(-0.0001))
     {
-        //_m144.ACC_ADCReqType = 1;//20221102,新车没有此信号
-       // _m24B.ADCReqMode = 1;//20221102,新车没有此信号
-         _m24E.ACC_DecToStop =1;
-    }
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",0.0);
 
-//    std::cout<<" type: "<<(int)_m144.ACC_ADCReqType<<std::endl;
+        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);
 
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",0.0);
 
-    /*制动过程用的减速度,加速用扭矩*/
-    _m24E.ACC_AccTrqReq = ECU_24E_ACC_AccTrqReq_toS(decition.torque());
-    _m24E.ACC_AccTrqReqActive = decition.acc_active();
-    if(decition.brake()<(-5.0))
-    {
-        _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(-5.0);
-    }
-    else
-        _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(decition.brake());
+        if(gbSendBrake == false)   //if brake is unavailable
+        {
 
+            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);
 
- //   std::cout<<" brake : "<<decition.brake()<<std::endl;
- //   std::cout<<"brake acctive. "<<decition.brake_active()<<std::endl;
-    if(decition.brake()>(-0.0000001))
-    {
+            SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
+            SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
 
-        if(xieya > 0)
+            if(fabs(gfVehSpd)>0.1)
+            {
+                std::cout<<std::chrono::system_clock::now().time_since_epoch().count()<<" Warning: can't brake."<<std::endl;
+            }
+        }
+ //       ADS_1_PilotParkCtrlRepMod = 1.0;
+ //       std::cout<<" send brake "<<std::endl;
+    }
+
+    else
+    {
+        SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",ftorque);
+        if(fabs(gfVehSpd) < 0.1)
         {
-            _m24E.ACC_CDDActive = 1;
-            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0.5);
-            _m24E.ACC_AccTrqReq = ECU_24E_ACC_AccTrqReq_toS(0);
-            _m24E.ACC_Driveoff_Request = 1;
-
-            //_m144.ACC_ADCReqType = 1;//20221102,新车没有此信号
-            //_m24B.ADCReqMode = 1;   //20221102,新车没有此信号
-             _m24E.ACC_DecToStop =1;
-            xieya--;
-            std::cout<<" xieya. now veh speed: "<<gfVehSpd<<std::endl;
+            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
         {
-            _m24E.ACC_CDDActive = 0;
-            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0);
-            _m24E.ACC_Driveoff_Request = 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);
         }
-    }
-    else
-    {
-        _m24E.ACC_CDDActive = 1;
 
-        _m24E.ACC_Driveoff_Request = 0;
+        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);
 
     }
 
+#ifdef TESTBRAKE
+   }
 
- //       _m24B.ACC_CDDActive = decition.brake_active();
+   else
+   {
 
+       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);
 
-//    std::cout<<" req mode: "<<_m144.ADS_Reqmode<<std::endl;
-    //byte_144[0] = ((_m144.ACC_LatAngReq >> 9) & (0x1FU)) | ((_m144.ADS_Reqmode & (0x07U)) << 5);
- //   qDebug(" req mode: %d byte: %02X  ",_m144.ADS_Reqmode, byte_144[0]);
-   // byte_144[1] = ((_m144.ACC_LatAngReq >> 1) & (0xFFU));
-    //byte_144[2] = ((_m144.ACC_LatAngReq & (0x01U)) << 7) | ((_m144.ACC_MotorTorqueMaxLimitRequest >> 5) & (0x3FU)) | ((_m144.ACC_LatAngReqActive & (0x01U)) << 6);
-    //byte_144[3] = ((_m144.ACC_MotorTorqueMaxLimitRequest & (0x1FU)) << 3) | ((_m144.ACC_MotorTorqueMinLimitRequest >> 8) & (0x07U));
-    //byte_144[4] = (_m144.ACC_MotorTorqueMinLimitRequest & (0xFFU));
-    //byte_144[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
+       SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",300);
 
 
-    byte_1C4[0] = ((_m1C4.ACC_MotorTorqueMaxLimitRequest >> 3) & (0xFFU));
- //   qDebug(" req mode: %d byte: %02X  ",_m144.ADS_Reqmode, byte_144[0]);
-    byte_1C4[1] = ((_m1C4.ACC_MotorTorqueMaxLimitRequest & (0x07U)) << 5) | ((_m1C4.ACC_MotorTorqueMinLimitRequest >> 6) & (0x1FU));
-    byte_1C4[2] = ((_m1C4.ACC_MotorTorqueMinLimitRequest & (0x3FU)) << 2) | ((_m1C4.ACC_LatAngReq >> 12) & (0x03U));
-    byte_1C4[3] = (((_m1C4.ACC_LatAngReq>>4 )& (0xFFU)));
-   // byte_1C4[4] = (((_m1C4.ACC_LatAngReq<<4) & (0xF0U)))|((_m1C4.ACC_LatAngReqActive&(0x01U))<<3);
-    byte_1C4[4] = (((_m1C4.ACC_LatAngReq)& (0x0fU))<<4)|((_m1C4.ACC_LatAngReqActive&(0x01U))<<3);
-    //byte_1C4[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
+   }
 
-    //    _m24B.ACC_AEBTargetDeceleration = 0;
-    //    _m24B.ACC_AEBVehilceHoldReq = 0;
-    //    _m24B.ADCReqMode = 0;
-    //    _m24B.ACC_AEBActive = 0;
-    //    _m24B.ACC_Driveoff_Request = 0;
-    //    _m24B.ACC_DecToStop = 0;
-//    std::cout<<" brake : "<<decition.brake()<<std::endl;
-//    std::cout<<"brake acctive. "<<decition.brake_active()<<std::endl;
-    if(decition.brake()>(-0.0000001))
-    {
-        _m24E.ACC_CDDActive = 0;
-        _m24E.ACC_Driveoff_Request = 1;
-        if(xieya > 0)
-        {
-            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0.5);
-            xieya--;
-        }
-        else
-        {
-            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0);
-        }
-        _m24E.ACC_AccTrqReqActive = 1;
-        _m24E.ACC_DecToStop = 0;
+   testnum++;
+   if(testnum > 1500)testnum = 0;
+#endif
 
-    }
-    else
-    {
-        _m24E.ACC_CDDActive = 1;
 
-        _m24E.ACC_Driveoff_Request = 0;
 
-        if(gbHaveVehSpd)
-        {
-            if(gfVehSpd < 0.01)
-            {
-                if(xieya != 50)std::cout<<"need xieya. "<<std::endl;
-                xieya = 50;
+//    std::cout<<" send dec. "<<std::endl;
 
-            }
-        }
+//    ADS_1_SteerAgReq = 90.0;//decition.wheelangle();
 
-        _m24E.ACC_AccTrqReqActive = 0;
-        _m24E.ACC_DecToStop = 1;
-    }
- //       _m24B.ACC_CDDActive = decition.brake_active();
-    _m24E.ACC_ACCMode = decition.auto_mode();
+}
 
+void adc_controller_chery_sterra_es_core::PrepareMsg()
+{
+    static int rollcouter = 0;
+    //    std::cout<<" roll count:: "<<rollcouter<<std::endl;
+    SetMsgSignal("ADS_EPS_1","ADS_1_RollgCntr1",rollcouter);
+    SetMsgSignal("ADS_EPS_1","ADS_1_RollgCntr2",rollcouter);
+    // set_EPS1_signal("CutOutFreshvalues_2CB_S",1.0);
+    // set_EPS1_signal("CutOutMAC_2CB_S",1.0);
+    gpsterraes->GetEPS1Data(ADS_EPS_1);
 
-    if(gnState == 0)
-    {
-        _m24E.ACC_CDDActive = 0;
-        _m24E.ACC_Driveoff_Request = 0;
-        _m24E.ACC_ACCMode = 0;
-        _m24E.ACC_ACCTargetAcceleration = 0;
-        _m24E.ACC_AccTrqReqActive = 0;
-        _m24E.ACC_DecToStop = 0;
+    SetMsgSignal("ADS_VCU_1","ADS_1_RollgCntr1",rollcouter);
+    SetMsgSignal("ADS_VCU_1","ADS_1_RollgCntr2",rollcouter);
+    gpsterraes->GetVCU1Data(ADS_VCU_1);
 
-    }
-//    std::cout<<"acc mode: "<<(int)_m24B.ACC_ACCMode<<std::endl;
-
-
-   // byte_24B[0] = ((_m24B.ACC_AccTrqReq >> 7) & (0xFFU));
-    //byte_24B[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
-    //byte_24B[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
-    //byte_24B[3] = ((_m24B.ACC_ACCTargetAcceleration & (0x07U)) << 5) | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
-    //byte_24B[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
-    //byte_24B[5] = ((_m24B.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24B.ACC_AEBVehilceHoldReq & (0x01U));
-    //byte_24B[6] = ((_m24B.ADCReqMode & (0x03U)) << 1) | ((_m24B.ACC_AEBActive & (0x01U)) << 3) | ((_m24B.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24B.ACC_DecToStop & (0x01U)) << 6) | ((_m24B.ACC_CDDActive & (0x01U)) << 7);
-    //byte_24B[7] = (_m24B.ACC_ACCMode & (0x07U));
-
-
-    byte_24E[0] = ((_m24E.ACC_ACCTargetAcceleration) & (0xFFU));
-    //byte_24E[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
-    //byte_24E[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
-    byte_24E[3] = ((_m24E.ACC_DecToStop & (0x01U)) << 7);// | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
-    //byte_24E[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
-    byte_24E[5] = ((_m24E.ACC_CDDActive & (0x01U)) << 4);//((_m24E.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24E.ACC_AEBVehilceHoldReq & (0x01U));
-    byte_24E[6] = ((_m24E.ACC_Driveoff_Request & (0x01U)) << 7)|((_m24E.ACC_ACCMode & (0x07U))<<4);//((_m24E.ADCReqMode & (0x03U)) << 1) | ((_m24E.ACC_AEBActive & (0x01U)) << 3) | ((_m24E.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24E.ACC_DecToStop & (0x01U)) << 6) | ((_m24E.ACC_CDDActive & (0x01U)) << 7);
-    byte_24E[8] = ((_m24E.ACC_AEBTargetDeceleration>>8) & (0xFFU));
-    byte_24E[9] = ((_m24E.ACC_AEBTargetDeceleration) & (0xFFU));
-    byte_24E[10] = ((_m24E.ACC_AEBActive & (0x01U)) << 7);
-    byte_24E[11] = ((_m24E.ACC_AccTrqReq>>13 )& (0x03U));
-    byte_24E[12] = ((_m24E.ACC_AccTrqReq>>5 )& (0xFFU));
-    //byte_24E[13] = ((_m24E.ACC_AccTrqReq & (0x1FU)<<3))| ((_m24E.ACC_AccTrqReqActive & (0x01U)) << 2);
-    byte_24E[13] = (((_m24E.ACC_AccTrqReq & (0x1FU))<<3))| ((_m24E.ACC_AccTrqReqActive & (0x01U)) << 2);
-
-    if(decition.leftlamp() == true && decition.rightlamp() == false)
-        _m25E.ADS_UDLCTurnLightReq = 3;
-    else if(decition.leftlamp() == false && decition.rightlamp() == true)
-        _m25E.ADS_UDLCTurnLightReq = 4;
-    else
-        _m25E.ADS_UDLCTurnLightReq = 0;
+    SetMsgSignal("ADS_ONEBOX_2","FCM_2_RollgCntr1",rollcouter);
+    gpsterraes->GetONEBOX2Data(ADS_ONEBOX_2);
 
-    byte_25E[3] = ((_m25E.ADS_UDLCTurnLightReq & (0x07U)));
+    SetMsgSignal("ADS_ONEBOX_3","FCM_3_RollgCntr1",rollcouter);
+    gpsterraes->GetONEBOX3Data(ADS_ONEBOX_3);
 
-}
+    SetMsgSignal("ADS_COM_3","ADS_3_RollgCntr1",rollcouter);
+    gpsterraes->GetADSCOM3Data(ADS_COM3);
 
+    SetMsgSignal("ADS_COM_2","ADS_2_RollgCntr1",rollcouter);
+    gpsterraes->GetADSCOM2Data(ADS_COM2);
+
+    rollcouter++;
+    if(rollcouter>=14)rollcouter = 0;
+}
 
 void adc_controller_chery_sterra_es_core::ExecSend()
 {
+    static int nrd = 0;
+    PrepareMsg();
+//    gpsterraes->GetEPS1Data(ADS_EPS_1);
     static int nCount = 0;
     nCount++;
 
@@ -503,9 +406,9 @@ void adc_controller_chery_sterra_es_core::ExecSend()
     xraw.header.frame_id = "adc";
     xraw.header.stamp.sec = nnow/1e9;
     xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
-    xraw.id = 0x1C4;
-    memcpy(xraw.data.data(),byte_1C4,32);
-    xraw.dlc = 32;
+    xraw.id = 0x195;
+    memcpy(xraw.data.data(),ADS_EPS_1,24);
+    xraw.dlc = 24;
     xraw.is_error = false;
     xraw.is_extended = false;
     xraw.is_rtr = false;
@@ -515,35 +418,90 @@ void adc_controller_chery_sterra_es_core::ExecSend()
     xraw.header.frame_id = "adc";
     xraw.header.stamp.sec = nnow/1e9;
     xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
-    xraw.id = 0x24E;
-    memcpy(xraw.data.data(),byte_24E,32);
-    xraw.dlc = 64;
+    xraw.id = 0x1BC;
+    memcpy(xraw.data.data(),ADS_EPS_3,24);
+    xraw.dlc = 24;
     xraw.is_error = false;
     xraw.is_extended = false;
     xraw.is_rtr = false;
     xmsg.frames.push_back(xraw);
-    if(nCount%2 == 1)
-    {
-        xmsg.frames.push_back(xraw);
-    }
 
     nnow = std::chrono::system_clock::now().time_since_epoch().count();
     xraw.header.frame_id = "adc";
     xraw.header.stamp.sec = nnow/1e9;
     xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
-    xraw.id = 0x25E;
-    memcpy(xraw.data.data(),byte_25E,32);
-    xraw.dlc = 32;
+    xraw.id = 0x159;
+    memcpy(xraw.data.data(),ADS_ONEBOX_1,24);
+    xraw.dlc = 24;
     xraw.is_error = false;
     xraw.is_extended = false;
     xraw.is_rtr = false;
     xmsg.frames.push_back(xraw);
-    if(nCount%2 == 1)
+
+    nnow = std::chrono::system_clock::now().time_since_epoch().count();
+    xraw.header.frame_id = "adc";
+    xraw.header.stamp.sec = nnow/1e9;
+    xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+    xraw.id = 0x145;
+    memcpy(xraw.data.data(),ADS_ONEBOX_2,24);
+    xraw.dlc = 24;
+    xraw.is_error = false;
+    xraw.is_extended = false;
+    xraw.is_rtr = false;
+    xmsg.frames.push_back(xraw);
+
+    if(nrd == 0)
     {
+        nnow = std::chrono::system_clock::now().time_since_epoch().count();
+        xraw.header.frame_id = "adc";
+        xraw.header.stamp.sec = nnow/1e9;
+        xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+        xraw.id = 0x31A;
+        memcpy(xraw.data.data(),ADS_COM3,24);
+        xraw.dlc = 24;
+        xraw.is_error = false;
+        xraw.is_extended = false;
+        xraw.is_rtr = false;
+        xmsg.frames.push_back(xraw);
+
+        nnow = std::chrono::system_clock::now().time_since_epoch().count();
+        xraw.header.frame_id = "adc";
+        xraw.header.stamp.sec = nnow/1e9;
+        xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+        xraw.id = 0x314;
+        memcpy(xraw.data.data(),ADS_COM2,24);
+        xraw.dlc = 24;
+        xraw.is_error = false;
+        xraw.is_extended = false;
+        xraw.is_rtr = false;
         xmsg.frames.push_back(xraw);
     }
 
 
+    nnow = std::chrono::system_clock::now().time_since_epoch().count();
+    xraw.header.frame_id = "adc";
+    xraw.header.stamp.sec = nnow/1e9;
+    xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+    xraw.id = 0x14A;
+    memcpy(xraw.data.data(),ADS_ONEBOX_3,24);
+    xraw.dlc = 24;
+    xraw.is_error = false;
+    xraw.is_extended = false;
+    xraw.is_rtr = false;
+    xmsg.frames.push_back(xraw);
+
+    nnow = std::chrono::system_clock::now().time_since_epoch().count();
+    xraw.header.frame_id = "adc";
+    xraw.header.stamp.sec = nnow/1e9;
+    xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+    xraw.id = 0x167;
+    memcpy(xraw.data.data(),ADS_VCU_1,24);
+    xraw.dlc = 24;
+    xraw.is_error = false;
+    xraw.is_extended = false;
+    xraw.is_rtr = false;
+    xmsg.frames.push_back(xraw);
+
     nnow = std::chrono::system_clock::now().time_since_epoch().count();
     xmsg.header.frame_id = "adc";
     xmsg.header.stamp.sec = nnow/1e9;
@@ -558,71 +516,96 @@ void adc_controller_chery_sterra_es_core::ExecSend()
 
 void adc_controller_chery_sterra_es_core::Activate()
 {
-    std::this_thread::sleep_for(std::chrono::milliseconds(100));
-    iv::brain::decition xdecition;
-    xdecition.set_brake(0.0);
-    xdecition.set_torque(0.0);
-//    for(int j=0;j<100000;j++)
-//    {
-        std::cout<<" run "<<std::endl;
-    for(int i = 0; i < 3; i++){
-        xdecition.set_wheelangle(0.0);
-        xdecition.set_angle_mode(0);
-        xdecition.set_angle_active(0);
-        xdecition.set_acc_active(0);
-        xdecition.set_brake_active(0);
-//        xdecition.set_brake_type(0);
-        xdecition.set_auto_mode(0);
-        gnState = 0;
-        executeDecition(xdecition);
-        ExecSend();
-        std::this_thread::sleep_for(std::chrono::milliseconds(10));
-    }
-    for(int i = 0; i < 3; i++){
-        xdecition.set_wheelangle(0.0);
-        xdecition.set_angle_mode(1);
-        xdecition.set_angle_active(1);
-        xdecition.set_acc_active(1);
-        xdecition.set_brake_active(1);
-//        xdecition.set_brake_type(1);
-        xdecition.set_auto_mode(3);
-        gnState = 1;
-        executeDecition(xdecition);
-        ExecSend();
-        std::this_thread::sleep_for(std::chrono::milliseconds(10));
-    }
-//    }
+    //    for(int j=0;j<100000;j++)
+    //    {
+        std::cout<<" activate "<<std::endl;
+        for(int i = 0; i < 3; i++){
+    
+            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_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);
+    
+            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);
+            SetMsgSignal("ADS_ONEBOX_2","FCM_2_Avl",1.0);
+    
+            SetMsgSignal("ADS_COM_2","FCM_2_SysStatus",0.0);
+    
+            SetMsgSignal("ADS_COM_2","ADS_2_AEBStatus",0.0);
+            SetMsgSignal("ADS_COM_3","ADS_3_ACCSts",3.0);
+    
+    
+    
+      //      std::cout<<"activate."<<std::endl;
+    
+            ExecSend();
+            std::this_thread::sleep_for(std::chrono::milliseconds(10));
+        }
+        //    }
 }
 
 void adc_controller_chery_sterra_es_core::UnAcitvate()
 {
-    iv::brain::decition xdecition;
-
-    xdecition.set_brake(0.0);
-    xdecition.set_torque(0.0);
-    for(int i = 0; i < 3; i++){
-        xdecition.set_wheelangle(0);
-        xdecition.set_angle_mode(1);
-        xdecition.set_angle_active(1);
-        xdecition.set_acc_active(1);
-        xdecition.set_brake_active(1);
-//        xdecition.set_brake_type(1);
-        xdecition.set_auto_mode(3);
-        gnState = 1;
-        executeDecition(xdecition);
-        ExecSend();
-        std::this_thread::sleep_for(std::chrono::milliseconds(10));
-    }
     for(int i = 0; i < 3; i++){
-        xdecition.set_wheelangle(0);
-        xdecition.set_angle_mode(0);
-        xdecition.set_angle_active(0);
-        xdecition.set_acc_active(0);
-        xdecition.set_brake_active(0);
-//        xdecition.set_brake_type(0);
-        gnState = 0;
-        xdecition.set_auto_mode(0);
-        executeDecition(xdecition);
+
+        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);
+
+        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);
+        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);
+
+
+        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);
+
+        SetMsgSignal("ADS_ONEBOX_2","FCM_2_Avl",1.0);
+
+        SetMsgSignal("ADS_COM_2","FCM_2_SysStatus",1.0);
+
+        SetMsgSignal("ADS_COM_2","ADS_2_AEBStatus",0.0);
+        SetMsgSignal("ADS_COM_3","ADS_3_ACCSts",0.0);
+
+
         ExecSend();
         std::this_thread::sleep_for(std::chrono::milliseconds(10));
     }
@@ -630,12 +613,7 @@ void adc_controller_chery_sterra_es_core::UnAcitvate()
 
 void adc_controller_chery_sterra_es_core::initial()
 {
-    for (uint8_t i = 0; i < 64; i++) //CAN  to  canfd
-    {
-        byte_1C4[i] = 0;
-        byte_24E[i] = 0;
-        //byte_36E[i] = 0;
-    }
+
 }
 
 

+ 71 - 0
src/ros2/AutoWare2025/src/adc_perception_lidar_cnn/CMakeLists.txt

@@ -0,0 +1,71 @@
+cmake_minimum_required(VERSION 3.14)
+project(adc_perception_lidar_cnn)
+
+find_package(autoware_cmake REQUIRED)
+autoware_package()
+
+
+#Default to C++14
+if(NOT CMAKE_CXX_STANDARD)
+  set(CMAKE_CXX_STANDARD 14)
+endif()
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+  add_compile_options(-Wall -Wextra -Wpedantic)
+endif()
+
+
+find_package(ament_cmake REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(std_msgs REQUIRED)
+find_package(geometry_msgs REQUIRED)
+find_package(nav_msgs REQUIRED) 
+find_package(sensor_msgs REQUIRED)
+find_package(tf2_geometry_msgs REQUIRED)
+find_package(autoware_control_msgs REQUIRED)
+
+find_package(Qt5 COMPONENTS Core Widgets REQUIRED)
+
+find_package(Protobuf REQUIRED)
+
+
+include_directories(
+##  INCLUDE_DIRS include
+  ${CMAKE_CURRENT_BINARY_DIR}/..
+  ${catkin_INCLUDE_DIRS} include
+)
+
+include_directories(
+  ${CMAKE_CURRENT_SOURCE_DIR}/../include
+  ${CMAKE_CURRENT_SOURCE_DIR}/../include/adc_perception_lidar_cnn
+  ${CMAKE_CURRENT_SOURCE_DIR}/../include/msgtype
+)
+link_directories(
+  ${CMAKE_CURRENT_SOURCE_DIR}/../lib
+)
+
+
+add_executable(adc_perception_lidar_cnn
+  src/adc_perception_lidar_cnn_node.cpp
+  src/adc_perception_lidar_cnn_core.cpp
+  ./../include/msgtype/object.pb.cc
+  ./../include/msgtype/objectarray.pb.cc
+)
+
+target_link_libraries(adc_perception_lidar_cnn  ${Protobuf_LIBRARIES}  Geographic )  
+# modulecomm 
+
+ament_target_dependencies(adc_perception_lidar_cnn rclcpp std_msgs geometry_msgs 
+  tf2_geometry_msgs nav_msgs sensor_msgs autoware_control_msgs 
+   autoware_planning_msgs autoware_vehicle_msgs
+  autoware_utils  autoware_perception_msgs
+  tier4_perception_msgs)
+
+
+install(TARGETS
+adc_perception_lidar_cnn
+  DESTINATION lib/${PROJECT_NAME})
+
+ament_package()
+
+

+ 31 - 0
src/ros2/AutoWare2025/src/adc_perception_lidar_cnn/README.md

@@ -0,0 +1,31 @@
+# pilot_autoware_bridge
+
+## Purpose
+
+This `pilot_autoware_bridge` is a bridge between pilot and autoware.
+
+
+
+## Inputs / Outputs
+
+### Input
+
+| Name | Type                            | Description                                       |
+| ---- | ------------------------------- | ------------------------------------------------- |
+| pose | geometry_msgs::msg::PoseStamped | pose source to used for the velocity calculation. |
+
+### Output
+
+| Name      | Type                                  | Description                                   |
+| --------- | ------------------------------------- | --------------------------------------------- |
+| twist     | geometry_msgs::msg::TwistStamped      | twist calculated from the input pose history. |
+| linear_x  | tier4_debug_msgs::msg::Float32Stamped | linear-x field of the output twist.           |
+| angular_z | tier4_debug_msgs::msg::Float32Stamped | angular-z field of the output twist.          |
+
+## Parameters
+
+none.
+
+## Assumptions / Known limits
+
+none.

+ 121 - 0
src/ros2/AutoWare2025/src/adc_perception_lidar_cnn/include/adc_perception_lidar_cnn/adc_perception_lidar_cnn_core.hpp

@@ -0,0 +1,121 @@
+// Copyright 2015-2019 Autoware Foundation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef PILOT_AUTOWARE_BRIDGE_CORE_HPP_
+#define PILOT_AUTOWARE_BRIDGE_CORE_HPP_
+
+#include <rclcpp/rclcpp.hpp>
+
+#include <geometry_msgs/msg/pose_stamped.hpp>
+#include <geometry_msgs/msg/twist_stamped.hpp>
+
+#include "autoware_control_msgs/msg/control.hpp"
+//#include "autoware_auto_geometry_msgs/msg/complex32.hpp"
+//#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp"
+#include "autoware_planning_msgs/msg/trajectory.hpp"
+#include "autoware_vehicle_msgs/msg/control_mode_report.hpp"
+#include "autoware_vehicle_msgs/msg/engage.hpp"
+#include "autoware_vehicle_msgs/msg/gear_command.hpp"
+#include "autoware_vehicle_msgs/msg/gear_report.hpp"
+#include "autoware_vehicle_msgs/msg/hazard_lights_command.hpp"
+#include "autoware_vehicle_msgs/msg/hazard_lights_report.hpp"
+#include "autoware_vehicle_msgs/msg/steering_report.hpp"
+#include "autoware_vehicle_msgs/msg/turn_indicators_command.hpp"
+#include "autoware_vehicle_msgs/msg/turn_indicators_report.hpp"
+#include "autoware_vehicle_msgs/msg/velocity_report.hpp"
+#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp"
+#include "geometry_msgs/msg/pose.hpp"
+#include "geometry_msgs/msg/pose_stamped.hpp"
+#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
+#include "geometry_msgs/msg/transform_stamped.hpp"
+#include "geometry_msgs/msg/twist.hpp"
+#include "geometry_msgs/msg/twist_stamped.hpp"
+#include "nav_msgs/msg/odometry.hpp"
+#include "sensor_msgs/msg/imu.hpp"
+
+#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp"
+#include "geometry_msgs/msg/pose.hpp"
+#include "geometry_msgs/msg/pose_stamped.hpp"
+#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
+#include "geometry_msgs/msg/transform_stamped.hpp"
+#include "geometry_msgs/msg/twist.hpp"
+#include "geometry_msgs/msg/twist_stamped.hpp"
+#include "nav_msgs/msg/odometry.hpp"
+#include "sensor_msgs/msg/imu.hpp"
+
+#include <tf2_ros/buffer.h>
+#include <tf2_ros/transform_listener.h>
+
+#include <string>
+
+#include <pcl/point_types.h>
+#include <pcl_conversions/pcl_conversions.h>
+
+#include "autoware_utils/geometry/geometry.hpp"
+#include "autoware_utils/ros/msg_covariance.hpp"
+#include "autoware_utils/ros/update_param.hpp"
+
+#include <autoware_control_msgs/msg/control.hpp>
+
+#include <autoware_perception_msgs/msg/detected_objects.hpp>
+#include <autoware_perception_msgs/msg/tracked_objects.hpp>
+#include <sensor_msgs/msg/point_cloud2.hpp>
+#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>
+
+#include "chassis.pb.h"
+#include "objectarray.pb.h"
+
+using autoware_control_msgs::msg::Control;
+//using autoware_auto_geometry_msgs::msg::Complex32;
+//using autoware_auto_mapping_msgs::msg::HADMapBin;
+using autoware_planning_msgs::msg::Trajectory;
+using autoware_vehicle_msgs::msg::ControlModeReport;
+using autoware_vehicle_msgs::msg::Engage;
+using autoware_vehicle_msgs::msg::GearCommand;
+using autoware_vehicle_msgs::msg::GearReport;
+using autoware_vehicle_msgs::msg::HazardLightsCommand;
+using autoware_vehicle_msgs::msg::HazardLightsReport;
+using autoware_vehicle_msgs::msg::SteeringReport;
+using autoware_vehicle_msgs::msg::TurnIndicatorsCommand;
+using autoware_vehicle_msgs::msg::TurnIndicatorsReport;
+using autoware_vehicle_msgs::msg::VelocityReport;
+
+using geometry_msgs::msg::AccelWithCovarianceStamped;
+using geometry_msgs::msg::Pose;
+using geometry_msgs::msg::PoseStamped;
+using geometry_msgs::msg::PoseWithCovarianceStamped;
+using geometry_msgs::msg::TransformStamped;
+using geometry_msgs::msg::Twist;
+using geometry_msgs::msg::TwistStamped;
+using nav_msgs::msg::Odometry;
+using sensor_msgs::msg::Imu;
+using autoware_control_msgs::msg::Control;
+
+class adc_perception_lidar_cnn : public rclcpp::Node
+{
+public:
+    adc_perception_lidar_cnn();
+    ~adc_perception_lidar_cnn() = default;
+
+private:
+ 
+
+
+private:
+
+
+
+};
+
+#endif  

+ 9 - 0
src/ros2/AutoWare2025/src/adc_perception_lidar_cnn/launch/adc_perception_lidar_cnn.xml

@@ -0,0 +1,9 @@
+<launch>
+  <arg name="input_pose_topic" default="/localization/pose_estimator/pose" description=""/>
+  <arg name="output_twist_topic" default="/estimate_twist" description=""/>
+
+  <node pkg="testpose" exec="testpose" name="testpose" output="log">
+    <remap from="pose" to="$(var input_pose_topic)"/>
+    <remap from="twist" to="$(var output_twist_topic)"/>
+  </node>
+</launch>

+ 33 - 0
src/ros2/AutoWare2025/src/adc_perception_lidar_cnn/package.xml

@@ -0,0 +1,33 @@
+<?xml version="1.0"?>
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+  <name>adc_perception_lidar_cnn</name>
+  <version>0.1.0</version>
+  <description>use raw cnn cafel model</description>
+  <maintainer email="yuchuli@catarc.ac.cn">Yu Chuli</maintainer>
+  <license>Apache License 2.0</license>
+  <author email="yuchuli@catarc.ac.cn">Yu Chuli</author>
+
+  <buildtool_depend>ament_cmake</buildtool_depend>
+
+  <depend>autoware_control_msgs</depend>
+  <depend>autoware_mapping_msgs</depend>
+  <depend>autoware_planning_msgs</depend>
+  <depend>autoware_tf2</depend>
+  <depend>autoware_vehicle_msgs</depend>
+
+  <depend>tier4_api_utils</depend>
+  <depend>autoware_utils</depend>
+  <depend>tier4_external_api_msgs</depend>
+  <depend>tier4_vehicle_msgs</depend>
+  <depend>tier4_perception_msgs</depend>
+  <depend>geometry_msgs</depend>
+  <depend>nav_msgs</depend>
+  <depend>sensor_msgs</depend>
+  <depend>rclcpp</depend>
+
+
+ <export>
+   <build_type>ament_cmake</build_type>
+ </export>
+</package>

+ 52 - 0
src/ros2/AutoWare2025/src/adc_perception_lidar_cnn/src/adc_perception_lidar_cnn_core.cpp

@@ -0,0 +1,52 @@
+// Copyright 2015-2019 Autoware Foundation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "adc_perception_lidar_cnn/adc_perception_lidar_cnn_core.hpp"
+
+#ifdef ROS_DISTRO_GALACTIC
+#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
+#else
+#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
+#endif
+
+#include <cmath>
+#include <cstddef>
+#include <functional>
+
+#include <time.h>
+#include <sstream>
+
+#include <iostream>
+
+#include <GeographicLib/MGRS.hpp>
+#include <GeographicLib/UTMUPS.hpp>
+
+#include <QString>
+
+#include <chrono>
+
+//#include "modulecomm.h"   
+using namespace std;
+
+
+
+adc_perception_lidar_cnn::adc_perception_lidar_cnn() : Node("adc_perception_lidar_cnn")
+{
+ 
+
+
+
+
+}
+

+ 29 - 0
src/ros2/AutoWare2025/src/adc_perception_lidar_cnn/src/adc_perception_lidar_cnn_node.cpp

@@ -0,0 +1,29 @@
+// Copyright 2015-2019 Autoware Foundation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "adc_perception_lidar_cnn/adc_perception_lidar_cnn_core.hpp"
+
+#include <rclcpp/rclcpp.hpp>
+
+#include <memory>
+
+int main(int argc, char ** argv)
+{
+  rclcpp::init(argc, argv);
+
+  rclcpp::spin(std::make_shared<adc_perception_lidar_cnn>());
+  rclcpp::shutdown();
+
+  return 0;
+}