Ver Fonte

change controller_chery_sterra_es. add test code.

yuchuli há 1 mês atrás
pai
commit
dc2aaa4481

+ 29 - 1
src/controller/controller_chery_sterra_es/controller_chery_sterra_es.pro

@@ -7,9 +7,37 @@ CONFIG += c++17 cmdline
 #DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
 
 SOURCES += \
-        main.cpp
+        main.cpp \
+        sterraes.cpp
 
 # Default rules for deployment.
 qnx: target.path = /tmp/$${TARGET}/bin
 else: unix:!android: target.path = /opt/$${TARGET}/bin
 !isEmpty(target.path): INSTALLS += target
+
+#include($$PWD/control/control.pri)
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}
+
+!include(../../../include/ivprotobuf.pri ) {
+    error( "Couldn't find the ivprotobuf.pri file!" )
+}
+
+!include(../../../include/ivboost.pri ) {
+    error( "Couldn't find the ivboost.pri file!" )
+}
+
+!include(../controllercommon/controllercommon.pri ) {
+    error( "Couldn't find the controllercommon.pri.pri file!" )
+}
+
+INCLUDEPATH += $$PWD/../controllercommon
+
+LIBS += -livprotoif
+
+LIBS += -lcandbc
+
+HEADERS += \
+    sterraes.h

+ 540 - 0
src/controller/controller_chery_sterra_es/main.cpp

@@ -1,8 +1,548 @@
 #include <QCoreApplication>
 
+#include <QTime>
+
+#include <QMutex>
+
+#include "xmlparam.h"
+#include "modulecomm.h"
+#include "ivbacktrace.h"
+#include "ivversion.h"
+
+#include "canmsg.pb.h"
+#include "decition.pb.h"
+#include "chassis.pb.h"
+
+#include "torquebrake.h"
+
+#include <thread>
+
+#ifdef Q_OS_LINUX
+#include <signal.h>
+#endif
+
+#include "candbc.h"
+#include "sterraes.h"
+
+sterraes * gpsterraes;
+
+static void * gpacansend;
+static void * gpadecition;
+static void * gpachassis;
+
+static std::string gstrmemdecition;
+static std::string gstrmemcansend;
+static std::string gstrmemchassis;
+static bool gbSendRun = true;
+
+static bool gbChassisEPS = false;
+
+static iv::brain::decition gdecition_def;
+static iv::brain::decition gdecition;
+
+static QTime gTime;
+static int gnLastSendTime = 0;
+static int gnLastRecvDecTime = -1000;
+static int gnDecitionNum = 0; //when is zero,send default;
+const int gnDecitionNumMax = 100;
+static int gnIndex = 0;
+
+static bool gbHaveVehSpd = false;
+static double gfVehSpd = 0.0;
+
+static bool gbHaveWheelAngle = false;
+static double gfWheelAngle = 0.0;
+
+static double gfWheelSpeedLim = 300; //300 degrees per second
+
+
+static QMutex gMutex;
+
+static std::thread * gpsendthread = NULL;
+
+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
+
+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;
+
+
+
+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 ExecSend();
+
+void executeDecition(const iv::brain::decition &decition)
+{
+
+
+
+}
+
+void 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));
+    }
+    //    }
+}
+
+void 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);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+}
+
+void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
+{
+    (void)index;
+    (void)dt;
+    (void)strmemname;
+    iv::chassis xchassis;
+    //    static int ncount = 0;
+    if(!xchassis.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"iv::decition::BrainDecition::UpdateChassis ParseFrom Array Error."<<std::endl;
+        return;
+    }
+
+    if(xchassis.has_epsmode())
+    {
+        if(xchassis.epsmode() == 0)
+        {
+            gbChassisEPS = true;
+        }
+    }
+
+    if(xchassis.has_vel())
+    {
+        gfVehSpd = xchassis.vel();
+        gbHaveVehSpd = true;
+        //      std::cout<<" gf Veh speed : "<<gfVehSpd<<std::endl;
+    }
+
+    if(xchassis.has_angle_feedback())
+    {
+        gfWheelAngle = xchassis.angle_feedback();
+        gbHaveWheelAngle = true;
+    }
+}
+
+
+void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    (void)index;
+    (void)dt;
+    (void)strmemname;
+    static qint64 oldtime = QDateTime::currentMSecsSinceEpoch();
+    iv::brain::decition xdecition;
+
+    if(!xdecition.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"ListenDecition parse error."<<std::endl;
+        return;
+    }
+
+
+
+    //    if(xdecition.gear() != 4)
+    //    {
+    //        qDebug("not D");
+    //    }
+    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);
+
+    //   xdecition.set_wheelangle(45.0);
+
+    if((oldtime - QDateTime::currentMSecsSinceEpoch())<-100)qDebug("dection time is %lld diff is %lld ",QDateTime::currentMSecsSinceEpoch(),oldtime - QDateTime::currentMSecsSinceEpoch());
+    oldtime = QDateTime::currentMSecsSinceEpoch();
+    gMutex.lock();
+    gdecition.CopyFrom(xdecition);
+    gMutex.unlock();
+    gnDecitionNum = gnDecitionNumMax;
+    gbChassisEPS = false;
+
+}
+
+void ExecSend()
+{
+    static int nCount = 0;
+    nCount++;
+    iv::can::canmsg xmsg;
+    iv::can::canraw xraw;
+    //    unsigned char * strp = (unsigned char *)&(ServiceControlStatus.command10.byte[0]);
+    //    qDebug("%02x %02x %02x %02x %02x %02x %02x %02x",strp[0],strp[1],strp[2],strp[3],strp[4],strp[5],strp[6],strp[7]);
+
+    xraw.set_id(0x195);
+    xraw.set_data(ADS_EPS_1,24);
+    xraw.set_bext(false);
+    xraw.set_bremote(false);
+    xraw.set_len(24);
+    // iv::can::canraw * pxraw195 = xmsg.add_rawmsg();
+    // pxraw195->CopyFrom(xraw);
+    //    qDebug(" 0x144: %02X %02X %02X %02X %02X %02X %02X %02X",byte_144[0],byte_144[1],byte_144[2],byte_144[3],
+    //            byte_144[4],byte_144[5],byte_144[6],byte_144[7]);
+    xmsg.set_channel(0);
+    xmsg.set_index(gnIndex);
+
+    xraw.set_id(0x1BC);
+    xraw.set_data(ADS_EPS_3,24);
+    xraw.set_bext(false);
+    xraw.set_bremote(false);
+    xraw.set_len(24);
+    xmsg.set_channel(0);
+    iv::can::canraw * pxraw1BC = xmsg.add_rawmsg();
+    pxraw1BC->CopyFrom(xraw);
+
+    xraw.set_id(0x159);
+    xraw.set_data(ADS_ONEBOX_1,24);
+    xraw.set_bext(false);
+    xraw.set_bremote(false);
+    xraw.set_len(24);
+    // iv::can::canraw * pxraw159 = xmsg.add_rawmsg();
+    // pxraw159->CopyFrom(xraw);
+
+    xraw.set_id(0x167);
+    xraw.set_data(ADS_VCU_1,24);
+    xraw.set_bext(false);
+    xraw.set_bremote(false);
+    xraw.set_len(24);
+    // iv::can::canraw * pxraw167 = xmsg.add_rawmsg();
+    // pxraw167->CopyFrom(xraw);
+
+
+    xmsg.set_channel(0);
+    xmsg.set_index(gnIndex);
+
+    gnIndex++;
+    xmsg.set_mstime(QDateTime::currentMSecsSinceEpoch());
+    int ndatasize = xmsg.ByteSize();
+    char * strser = new char[ndatasize];
+    std::shared_ptr<char> pstrser;
+    pstrser.reset(strser);
+    if(xmsg.SerializeToArray(strser,ndatasize))
+    {
+        iv::modulecomm::ModuleSendMsg(gpacansend,strser,ndatasize);
+    }
+    else
+    {
+        std::cout<<"MainWindow::onTimer serialize error."<<std::endl;
+    }
+}
+
+void initial()
+{
+    for (uint8_t i = 0; i < 24; i++) //CAN  to  canfd
+    {
+        //byte_36E[i] = 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",2.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_EPS3_signal("ADS_3_SteerParkAgEna",0.0);
+        gpsterraes->GetEPS3Data(ADS_EPS_3);
+        ExecSend();
+        rollcouter++;
+        if(rollcouter>14)rollcouter = 0;
+        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);
+        gpsterraes->GetEPS3Data(ADS_EPS_3);
+        ExecSend();
+        rollcouter++;
+        if(rollcouter>14)rollcouter = 0;
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+
+    for(i=0;i<3000;i++)
+    {
+        set_EPS3_signal("ADS_3_SteerParkAgEna",2.0);
+        set_EPS3_signal("ADS_3_SteerParkAgReq",fwheelang);
+        set_EPS3_signal("ADS_3_SteerParkAgVld",1.0);
+        gpsterraes->GetEPS3Data(ADS_EPS_3);
+        ExecSend();
+        rollcouter++;
+        if(rollcouter>14)rollcouter = 0;
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+
+    for(i=0;i<10;i++)
+    {
+        set_EPS3_signal("ADS_3_SteerParkAgEna",0.0);
+        gpsterraes->GetEPS3Data(ADS_EPS_3);
+        ExecSend();
+        rollcouter++;
+        if(rollcouter>14)rollcouter = 0;
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+}
+
+void sendthread()
+{
+    initial();
+    iv::brain::decition xdecition;
+
+    UnAcitvate();
+    //   UnAcitvate();
+
+    int nstate = 0; //0 Un 1 Activate
+    //    Activate();
+    while(gbSendRun)
+    {
+        if(gnDecitionNum <= 0)
+        {
+            if(nstate == 1)
+            {
+                UnAcitvate();
+                nstate = 0;
+            }
+            xdecition.CopyFrom(gdecition_def);
+        }
+        else
+        {
+            if(nstate == 0)
+            {
+                Activate();
+                nstate = 1;
+            }
+            gMutex.lock();
+            xdecition.CopyFrom(gdecition);
+            gMutex.unlock();
+            gnDecitionNum--;
+        }
+
+#ifdef TORQUEBRAKETEST
+        if(gnothavetb < 10)
+        {
+            iv::controller::torquebrake xtb;
+            gMutextb.lock();
+            xtb.CopyFrom(gtb);
+            gMutextb.unlock();
+            if(xtb.enable())
+            {
+
+                xdecition.set_torque(xtb.torque());
+                xdecition.set_brake(xtb.brake());
+
+                std::cout<<" use xtb. torque: "<<xtb.torque()<<" brake: "<<xtb.brake()<<std::endl;
+
+                //                gcontroller->control_torque(xtb.torque());
+                //                gcontroller->control_brake(xtb.brake());
+                //            qDebug("use tb value torque is %f brake is %f",xtb.torque(),xtb.brake());
+            }
+            else
+            {
+                //            qDebug("torquebrake not enable.");
+            }
+            gnothavetb++;
+        }
+
+#endif
+        executeDecition(xdecition);
+        if(gbChassisEPS == false) ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+    UnAcitvate();
+}
+
+#ifdef Q_OS_LINUX
+void sig_int(int signo)
+{
+    gbSendRun = false;
+    gpsendthread->join();
+
+    iv::modulecomm::Unregister(gpacansend);
+    iv::modulecomm::Unregister(gpachassis);
+    iv::modulecomm::Unregister(gpadecition);
+
+    std::cout<<" controller exit."<<std::endl;
+    exit(0);
+}
+#endif
+
 int main(int argc, char *argv[])
 {
+    RegisterIVBackTrace();
+    showversion("controller_changan_shenlan");
     QCoreApplication a(argc, argv);
 
+    QString strpath = QCoreApplication::applicationDirPath();
+
+    if(argc < 2)
+        strpath = strpath + "/controller_changan_shenlan.xml";
+    else
+        strpath = argv[1];
+    std::cout<<strpath.toStdString()<<std::endl;
+
+    gpsterraes = new sterraes();
+
+    //    gdecition_def.set_accelerator(-0.5);
+    gdecition_def.set_brake(0);
+    gdecition_def.set_rightlamp(false);
+    gdecition_def.set_leftlamp(false);
+    gdecition_def.set_wheelangle(0);
+
+    gdecition_def.set_angle_mode(0);
+    gdecition_def.set_angle_active(0);
+    gdecition_def.set_acc_active(0);
+    //    gdecition_def.set_brake_active(1);
+    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());
+
+    gstrmemcansend = xp.GetParam("cansend","cansend0");
+    gstrmemdecition = xp.GetParam("dection","deciton");
+    gstrmemchassis = xp.GetParam("chassismsgname","chassis");
+
+    gpacansend = iv::modulecomm::RegisterSend(gstrmemcansend.data(),10000,1);
+    gpadecition = iv::modulecomm::RegisterRecv(gstrmemdecition.data(),ListenDeciton);
+    gpachassis = iv::modulecomm::RegisterRecv(gstrmemchassis.data(),UpdateChassis);
+
+#ifdef TORQUEBRAKETEST
+    EnableTorqueBrakeTest();
+#endif
+
+    std::thread xthread(sendthread);
+
+    gpsendthread = &xthread;
+
+#ifdef Q_OS_LINUX
+    signal(SIGINT, sig_int);
+    signal(SIGTERM,sig_int);
+#endif
+
     return a.exec();
 }

+ 166 - 0
src/controller/controller_chery_sterra_es/sterraes.cpp

@@ -0,0 +1,166 @@
+#include "sterraes.h"
+
+#include <iostream>
+#include <memory>
+#include <string.h>
+
+sterraes::sterraes() {
+
+    mpPacker =  new CANPacker("./ADCC_CH.dbc");
+    SignalPackValue sv;
+    sv.name = "ADS_1_RollgCntr1";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_Resd1";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_SteerAgReq";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_SteerAgVld";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_SteerPilotAgEna";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_RollgCntr2";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_Resd2";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_SteerTqEna";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_LdwWarningCmd";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_LdwWarningCmdVld";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_SteerMaxTqReq";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_SteerMinTqReq";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "ADS_1_ADSHealthSts";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "CutOutFreshvalues_2CB_S";sv.value = 0;mvectorADSEPS1.push_back(sv);
+    sv.name = "CutOutMAC_2CB_S";sv.value = 0;mvectorADSEPS1.push_back(sv);
+
+    sv.name = "ADS_3_RollgCntr1";sv.value = 0;mvectorADSEPS3.push_back(sv);
+    sv.name = "ADS_3_Resd1";sv.value = 0;mvectorADSEPS3.push_back(sv);
+    sv.name = "ADS_3_SteerParkAgReq";sv.value = 0;mvectorADSEPS3.push_back(sv);
+    sv.name = "ADS_3_SteerParkAgVld";sv.value = 0;mvectorADSEPS3.push_back(sv);
+    sv.name = "ADS_3_SteerParkAgEna";sv.value = 0;mvectorADSEPS3.push_back(sv);
+    sv.name = "ADS_3_RollgCntr2";sv.value = 0;mvectorADSEPS3.push_back(sv);
+    sv.name = "ADS_3_Resd2";sv.value = 0;mvectorADSEPS3.push_back(sv);
+    sv.name = "ADS_3_ParkFcnMode";sv.value = 0;mvectorADSEPS3.push_back(sv);
+    sv.name = "ADS_3_ADSParkHealthSts";sv.value = 0;mvectorADSEPS3.push_back(sv);
+
+    sv.name = "ADS_1_RollgCntr1";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_Resd1";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PilotCtrlRepSta";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PilotParkCtrlType";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PilotParkBrkDecTar";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PilotParkCtrlRepMod";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PilotParkBrkDecTarVld";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PilotParkBrkDecTarEnable";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PilotParkDec2StpReq";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PilotParkDriOffReq";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_StopDist";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_ParkCtrlMod";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_1_PreFillReq";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_EPBCtrlReqValid";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+    sv.name = "ADS_EPBCtrlReq";sv.value = 0;mvectorADSONEBOX1.push_back(sv);
+
+    sv.name = "ADS_1_RollgCntr1";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_Resd1";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_DrvTarTq";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_DrvTarTqVld";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_DrvCtrlReq";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_CtrlReqMod";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_DrvTarTqEnable";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_AMAPRequest";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_AMAPRequestVld";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_ADCCAvl";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_AMAPTqLimit";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_AMAPTqLimitVld";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_RollgCntr2";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_Resd2";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_TarGearReq";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_TarGearReqVld";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_GearCtrlEnable";sv.value = 0;mvectorADSVCU1.push_back(sv);
+    sv.name = "ADS_1_RpaPTReadyReq";sv.value = 0;mvectorADSVCU1.push_back(sv);
+}
+
+void sterraes::setsignal(std::vector<SignalPackValue> * pvectorspv,std::string strsigname,double value){
+    int size = static_cast<int>(pvectorspv->size());
+    int i;
+    for(i=0;i<size;i++){
+        if(pvectorspv->at(i).name == strsigname){
+            pvectorspv->at(i).value = value;
+            return ;
+        }
+    }
+    std::cout<<" signal : "<<strsigname.data()<<" not found. please check signal."<<std::endl;
+    return ;
+}
+
+void sterraes::set_EPS1_signal(std::string strsigname,double value){
+    setsignal(&mvectorADSEPS1,strsigname,value);
+}
+
+void sterraes::set_EPS3_signal(std::string strsigname,double value){
+    setsignal(&mvectorADSEPS3,strsigname,value);
+}
+
+void sterraes::set_ONEBOX1_signal(std::string strsigname,double value){
+    setsignal(&mvectorADSONEBOX1,strsigname,value);
+}
+
+void sterraes::set_VCU1_signal(std::string strsigname,double value){
+    setsignal(&mvectorADSVCU1,strsigname,value);
+}
+
+unsigned char CRCCheck_SAEJ1850(unsigned char msg[], int len, unsigned char idleCrc)
+{
+    int i = 0;
+    int j = 0;
+    unsigned char crc8;
+    unsigned char poly = 0x1D;
+    crc8 = idleCrc;
+    for (i = 0; i<len; i++) {
+        crc8 ^= msg[i];
+        for (j = 0; j<8; j++) {
+            if (crc8 & 0x80) {
+                crc8 = (crc8 << 1) ^ poly;
+            }
+            else {
+                crc8 <<= 1;
+            }
+        }
+    }
+    //   crc8 ^= 0xFF;
+    crc8 ^= 0x00;//crc8 ^= 0xFF;
+    return crc8;
+}
+
+void sterraes::fillcrc(unsigned short dataid,unsigned char * pdata){
+    unsigned char xdata[9];
+    memcpy(xdata,&dataid,2);
+    memcpy(xdata+2,pdata+1,7);
+    unsigned char xcrc = CRCCheck_SAEJ1850(xdata,9,0x0);
+    pdata[0] = xcrc;
+}
+
+void sterraes::GetEPS1Data(unsigned char * pdata){
+    std::vector<uint8_t> xpack =  mpPacker->pack(0x195,mvectorADSEPS1);
+    int i;
+    for(i=0;i<24;i++)pdata[i] = xpack[i];
+
+    fillcrc(0x0004,pdata);
+    fillcrc(0x0005,pdata+8);
+}
+
+void sterraes::GetEPS3Data(unsigned char * pdata){
+    std::vector<uint8_t> xpack =  mpPacker->pack(0x1BC,mvectorADSEPS3);
+    int i;
+    for(i=0;i<24;i++)pdata[i] = xpack[i];
+
+    fillcrc(0x0006,pdata);
+    fillcrc(0x0007,pdata+8);
+}
+
+void sterraes::GetONEBOX1Data(unsigned char * pdata){
+    std::vector<uint8_t> xpack =  mpPacker->pack(0x159,mvectorADSONEBOX1);
+    int i;
+    for(i=0;i<24;i++)pdata[i] = xpack[i];
+
+    fillcrc(0x0008,pdata);
+}
+
+void sterraes::GetVCU1Data(unsigned char * pdata){
+    std::vector<uint8_t> xpack =  mpPacker->pack(0x167,mvectorADSEPS3);
+    int i;
+    for(i=0;i<24;i++)pdata[i] = xpack[i];
+
+    fillcrc(0x000B,pdata);
+    fillcrc(0x000C,pdata+8);
+}

+ 39 - 0
src/controller/controller_chery_sterra_es/sterraes.h

@@ -0,0 +1,39 @@
+#ifndef STERRAES_H
+#define STERRAES_H
+
+#include <vector>
+#include "candbc.h"
+
+class sterraes
+{
+public:
+    sterraes();
+
+private:
+    std::vector<SignalPackValue> mvectorADSEPS1;
+    std::vector<SignalPackValue> mvectorADSEPS3;
+    std::vector<SignalPackValue> mvectorADSONEBOX1;
+    std::vector<SignalPackValue> mvectorADSVCU1;
+
+    CANPacker * mpPacker;
+
+private:
+    void setsignal(std::vector<SignalPackValue> * pvectorspv,std::string strsigname,double value);
+
+    void fillcrc(unsigned short dataid,unsigned char * pdata);
+
+public:
+    void set_EPS1_signal(std::string strsigname,double value);
+    void set_EPS3_signal(std::string strsigname,double value);
+    void set_ONEBOX1_signal(std::string strsigname,double value);
+    void set_VCU1_signal(std::string strsigname,double value);
+
+    void GetEPS1Data(unsigned char * pdata);
+    void GetEPS3Data(unsigned char * pdata);
+    void GetONEBOX1Data(unsigned char * pdata);
+    void GetVCU1Data(unsigned char * pdata);
+
+
+};
+
+#endif // STERRAES_H

+ 40 - 0
src/test/testcandbc/main.cpp

@@ -2,8 +2,48 @@
 
 #include <QApplication>
 
+// #include <map>
+
+// void testmap()
+// {
+//     std::map<std::string,double> xmap;
+//     xmap.insert(std::pair<std::string,double>("first",1.0));
+//     xmap.insert(std::pair<std::string,double>("second",2.0));
+//     xmap.insert(std::pair<std::string,double>("third",3.0));
+
+//     double a = xmap.at("first");
+//     std::map<std::string,double>::iterator iter;
+//     for(iter = xmap.begin(); iter != xmap.end(); iter++)
+//     {
+//         if(iter->first == "second")
+//         {
+//             iter->second = 13.0;
+//         }
+//     }
+//     a = xmap.at("second");
+//     a = xmap.at("second");
+
+// }
+
+struct PackValue {
+    std::string name;
+    double value;
+};
+
+void testpack()
+{
+    std::vector<PackValue> xpv;
+    PackValue pv;
+    pv.name = "first";pv.value = 1.0; xpv.push_back(pv);
+    pv.name = "second"; pv.value = 2.0; xpv.push_back(pv);
+
+    xpv.at(0).value = 3.0;
+    xpv[1].value = 6.0;
+}
+
 int main(int argc, char *argv[])
 {
+//    testpack();
     QApplication a(argc, argv);
     MainWindow w;
     w.show();

+ 12 - 5
src/test/testcandbc/mainwindow.cpp

@@ -189,7 +189,8 @@ byte CRCCheck_SAEJ1850(byte msg[], int len, byte idleCrc)
             }
         }
     }
-    crc8 ^= 0xFF;
+ //   crc8 ^= 0xFF;
+    crc8 ^= 0x00;//crc8 ^= 0xFF;
     return crc8;
 }
 
@@ -212,11 +213,17 @@ void MainWindow::on_pushButton_Goto_clicked()
 
  //    xdata[2] = 0x22;
 
- //    byte msg[16];
+
+ //    byte msg[17];
  //    int j;
- //    for(j=0;j<16;j++)msg[j] = xdata[j];
+ //    for(j=0;j<16;j++)msg[j+1] = xdata[j];
+ //    msg[0] = 0x68;
+ //    msg[1] = 0x00;
+
+
+
+ //    byte crc = CRCCheck_SAEJ1850(&msg[0],9,0x0);
 
- //    byte crc = CRCCheck_SAEJ1850(msg,16,0);
 
 
     int index = ui->lineEdit_FrameGo->text().toInt();
@@ -256,7 +263,7 @@ void MainWindow::updateparse()
             unsigned int i;
             for(i=0;i<xvals.size();i++)
             {
-                snprintf(strline,1000,"%s:%f\n",xvals[i].name.data(),xvals[i].value);
+                snprintf(strline,1000,"%s:\t%f\n",xvals[i].name.data(),xvals[i].value);
                 strncat(strout,strline,10000);
             }
             ui->plainTextEdit_Value->setPlainText(strout);