#include #include #include #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 #include #ifdef Q_OS_LINUX #include #endif #include "candbc.h" #include "sterraes.h" std::string gstrdbcpath; bool gbUseOutDBC; 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 mvectorADSEPS1; std::vector mvectorADSEPS3; std::vector mvectorADSONEBOX1; std::vector 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; 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(); //int testnum = 0; void executeDecition(const iv::brain::decition &decition) { // std::cout<<"brake: "< 2500)) // { if(decition.brake()<(-0.0001)) { ADS_1_DrvTarTq = 0.0; ADS_1_ParkCtrlMod = 1.0; ADS_1_PilotParkDriOffReq = 0.0; ADS_1_PilotParkDec2StpReq = 1.0; ADS_1_PilotParkBrkDecTar = -1.0;//decition.brake(); ADS_1_PilotParkBrkDecTarVld = 1.0; ADS_1_PilotParkCtrlType = 0.0; ADS_1_PilotParkBrkDecTarEnable = 1.0; ADS_1_PilotCtrlRepSta = 1.0; ADS_1_PilotParkCtrlRepMod = 1.0; std::cout<<" send brake "< 100)ADS_1_DrvTarTq =100.0; ADS_1_PilotParkDec2StpReq = 0.0; ADS_1_PilotParkBrkDecTarEnable = 1.0; ADS_1_PilotParkBrkDecTarVld = 1.0; ADS_1_PilotParkBrkDecTar = 1.0; ADS_1_PilotCtrlRepSta = 0.0; ADS_1_PilotParkCtrlRepMod = 0.0; } // } // else // { // if(fabs(gfVehSpd) < 0.1) // { // ADS_1_PilotParkDriOffReq = 1.0; // } // ADS_1_DrvTarTq = 150; // if(ADS_1_DrvTarTq > 300)ADS_1_DrvTarTq =300.0; // ADS_1_PilotParkDec2StpReq = 0.0; // ADS_1_PilotParkBrkDecTarEnable = 1.0; // ADS_1_PilotParkBrkDecTarVld = 1.0; // ADS_1_PilotParkBrkDecTar = 1.0; // ADS_1_PilotCtrlRepSta = 0.0; // ADS_1_PilotParkCtrlRepMod = 0.0; // std::cout<<" send drive"; // } // testnum++; // std::cout<<" send dec. "<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); 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_PilotParkCtrlRepMod",ADS_1_PilotParkCtrlRepMod); gpsterraes->GetONEBOX1Data(ADS_ONEBOX_1); rollcouter++; } void ExecSend() { PrepareMsg(); // gpsterraes->GetEPS1Data(ADS_EPS_1); 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 pstrser; pstrser.reset(strser); if(xmsg.SerializeToArray(strser,ndatasize)) { iv::modulecomm::ModuleSendMsg(gpacansend,strser,ndatasize); } else { std::cout<<"MainWindow::onTimer serialize error."<GetEPS3Data(ADS_EPS_3); ExecSend(); rollcouter++; if(rollcouter>14)rollcouter = 0; } void SendEPS1() { static int rollcouter = 0; // std::cout<<" roll count:: "<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() { 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: "<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."< #include #include #include #include #include #include #include int main(int argc, char *argv[]) { // std::istringstream iss("First line.\nSecond line.\n"); // // 将 iss 传递给 processStream,这是合法的 // processStream(iss); RegisterIVBackTrace(); showversion("controller_changan_shenlan"); QCoreApplication a(argc, argv); QString strpath = QCoreApplication::applicationDirPath(); if(argc < 2) strpath = strpath + "/controller_chery_sterra_es.xml"; else strpath = argv[1]; std::cout<