main.cpp 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959
  1. #include <QCoreApplication>
  2. #include <QTime>
  3. #include <QMutex>
  4. #include "xmlparam.h"
  5. #include "modulecomm.h"
  6. #include "ivbacktrace.h"
  7. #include "ivversion.h"
  8. #include "canmsg.pb.h"
  9. #include "decition.pb.h"
  10. #include "chassis.pb.h"
  11. #include "torquebrake.h"
  12. #include <thread>
  13. #include <math.h>
  14. #ifdef Q_OS_LINUX
  15. #include <signal.h>
  16. #endif
  17. #include "candbc.h"
  18. #include "sterraes.h"
  19. #include "dbcsigpacker.h"
  20. std::string gstrdbcpath;
  21. bool gbUseOutDBC;
  22. sterraes * gpsterraes;
  23. static void * gpacansend;
  24. static void * gpadecition;
  25. static void * gpachassis;
  26. static std::string gstrmemdecition;
  27. static std::string gstrmemcansend;
  28. static std::string gstrmemchassis;
  29. static bool gbSendRun = true;
  30. static bool gbChassisEPS = false;
  31. static iv::brain::decition gdecition_def;
  32. static iv::brain::decition gdecition;
  33. static QTime gTime;
  34. static int gnLastSendTime = 0;
  35. static int gnLastRecvDecTime = -1000;
  36. static int gnDecitionNum = 0; //when is zero,send default;
  37. const int gnDecitionNumMax = 100;
  38. static int gnIndex = 0;
  39. static bool gbHaveVehSpd = false;
  40. static double gfVehSpd = 0.0;
  41. static bool gbHaveWheelAngle = false;
  42. static double gfWheelAngle = 0.0;
  43. static double gfWheelSpeedLim = 300; //300 degrees per second
  44. static QMutex gMutex;
  45. static std::thread * gpsendthread = NULL;
  46. unsigned char ADS_EPS_1[24];// 0x195/405
  47. unsigned char ADS_EPS_3[24]; // 0x1BC/444
  48. unsigned char ADS_ONEBOX_1[24];// 0x159/345
  49. unsigned char ADS_VCU_1[24]; // 0x167/359
  50. unsigned char ADS_ONEBOX_2[24];
  51. unsigned char ADS_ONEBOX_3[24];
  52. unsigned char ADS_COM2[8];
  53. unsigned char ADS_COM3[24];
  54. static int gnState = 0; //0 not act 1 act
  55. double gfWheelReq = 0.0;
  56. double gfTorqueReq = 0.0;
  57. double gfBrakeReq = 0.0;
  58. static bool gbSendBrake = false;
  59. static double kp = 0.5;
  60. static double ki = 0.0;
  61. static double kd = 0.0;
  62. static double MAXACC = 3.0;
  63. static int64_t gnLastAccUptime = 0;
  64. static bool gbUsePID = true;
  65. static bool gbPrintPIDOut = true;
  66. static double TorqueRatio = 1.4;
  67. static double gfVehAcc = 0.0;
  68. void SetMsgSignal(std::string strmsgname,std::string strsigname,double fvalue){
  69. gpsterraes->SetMsgSignal(strmsgname,strsigname,fvalue);
  70. }
  71. void ExecSend();
  72. double acctotorque(double facc)
  73. {
  74. double fVehWeight = 1800;
  75. double fRollForce = 50;
  76. const double fRatio = 2.5;
  77. double fNeed = fRollForce + fVehWeight*facc;
  78. double ftorque = fNeed/fRatio;
  79. return ftorque;
  80. }
  81. double PIDTorque(double torque)
  82. {
  83. if(gbUsePID == false)return torque;
  84. int64_t nnow = std::chrono::system_clock::now().time_since_epoch().count();
  85. if((nnow - gnLastAccUptime)>1e9)return torque;
  86. std::vector<int64_t> xvectorintegtime;
  87. std::vector<double> xvectorintegerr;
  88. static double error_previous = 0.0;
  89. static double integral = 0.0;
  90. double fVehWeight = 1800;
  91. double fRollForce = 50;
  92. const double fRatio = 2.5;
  93. double accAim = (torque * fRatio - fRollForce)/fVehWeight;
  94. static bool bPrintTitle = false;
  95. double error = accAim - gfVehAcc;
  96. double dt = 0.01; //10ms
  97. double diff = (error - error_previous)/dt;
  98. // integral = integral + error * dt * ki;
  99. xvectorintegtime.push_back(nnow);
  100. xvectorintegerr.push_back(error);
  101. unsigned int i;
  102. unsigned int nsize = 0;//static_cast<unsigned int>(xvectorintegerr.size());
  103. while(xvectorintegerr.size()>0)
  104. {
  105. if(abs(nnow - xvectorintegtime[0])>1e9){
  106. xvectorintegerr.erase(xvectorintegerr.begin());xvectorintegtime.erase(xvectorintegtime.begin());
  107. }
  108. else {
  109. break;
  110. }
  111. }
  112. integral = 0;
  113. nsize = static_cast<unsigned int>(xvectorintegerr.size());
  114. for(i=0;i<nsize;i++)integral = xvectorintegerr[i]*dt*ki;
  115. double output = error * kp + integral + diff * kd;
  116. double fAccAjust = accAim + output;
  117. if(fAccAjust>MAXACC)fAccAjust = MAXACC;
  118. if(fAccAjust<=0)fAccAjust = 0.0;
  119. double ftorqueAjust = acctotorque(fAccAjust);
  120. error_previous = error;
  121. if(bPrintTitle == false)
  122. {
  123. std::cout<<"Time\t"<<"Speed(km/h)\t"<<"RealAcc(m/s2)\t"<<"AimAcc(m/s2)\t"<<"AjustAcc(m/s2)\t"<<"Error(m/s2)\t"<<"RawTorque\t"<<"AjustTorque"<<std::endl;
  124. bPrintTitle = true;
  125. }
  126. if(gbPrintPIDOut)
  127. {
  128. int64_t timesecond = nnow/1e9;
  129. int64_t timepart = nnow - timesecond * 1e9;
  130. double fnow = timepart; fnow = fnow/1e9;
  131. fnow = fnow + timesecond;
  132. std::cout<<fnow<<"\t"<<gfVehSpd<<"\t"<<gfVehAcc<<accAim<<"\t"<<fAccAjust<<"\t"<<error<<"\t"<<torque<<"\t"<<ftorqueAjust<<std::endl;
  133. }
  134. return ftorqueAjust;
  135. }
  136. #ifdef TESTBRAKE
  137. int testnum = 0;
  138. #endif
  139. int testwheel = 0;
  140. #ifdef PIDTEST
  141. int pidtestnstep = 0;
  142. double fpidtestacc = 1.0;
  143. double fpidtestmaxvel = 15.0;
  144. #endif
  145. void executeDecition(const iv::brain::decition &decition)
  146. {
  147. double fwheel = decition.wheelangle()*0.9;
  148. if(fwheel<-430)fwheel = 430;
  149. if(fwheel>380)fwheel = 380;
  150. double ftorque = decition.torque() * TorqueRatio;
  151. double fbrake = decition.brake();
  152. #ifdef PIDTEST
  153. if(gfVehSpd>=fpidtestmaxvel)
  154. {
  155. pidtestnstep = 1;
  156. }
  157. if(pidtestnstep == 1)
  158. {
  159. ftorque = 0;
  160. fbrake = -1.0;
  161. }
  162. if(pidtestnstep == 0)
  163. {
  164. ftorque = PIDTorque(acctotorque(fpidtestacc));
  165. fbrake = 0;
  166. }
  167. #else
  168. ftorque = PIDTorque(ftorque);
  169. #endif
  170. SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgReq",fwheel);
  171. SetMsgSignal("ADS_EPS_1","ADS_1_LdwWarningCmdVld",2.0);
  172. SetMsgSignal("ADS_EPS_1","ADS_1_SteerMaxTqReq",3.0);
  173. SetMsgSignal("ADS_EPS_1","ADS_1_SteerMinTqReq",-3.0);
  174. SetMsgSignal("ADS_EPS_1","ADS_1_ADSHealthSts",1.0);
  175. SetMsgSignal("ADS_EPS_1","CutOutFreshvalues_2CB_S",1.0);
  176. SetMsgSignal("ADS_EPS_1","CutOutMAC_2CB_S",1.0);
  177. #ifdef TESTBRAKE
  178. if((testnum < 1000) || (testnum > 1500))
  179. {
  180. #endif
  181. if(fbrake<(-0.0001))
  182. {
  183. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",0.0);
  184. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
  185. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",1.0);
  186. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",decition.brake());
  187. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
  188. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotCtrlType",0.0);
  189. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",1.0);
  190. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",1.0);
  191. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
  192. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",0.0);
  193. if(gbSendBrake == false) //if brake is unavailable
  194. {
  195. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
  196. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",0.0);
  197. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",0.0);
  198. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
  199. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotCtrlType",0.0);
  200. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",0.0);
  201. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",0.0);
  202. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
  203. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
  204. if(fabs(gfVehSpd)>0.1)
  205. {
  206. std::cout<<std::chrono::system_clock::now().time_since_epoch().count()<<" Warning: can't brake."<<std::endl;
  207. }
  208. }
  209. // ADS_1_PilotParkCtrlRepMod = 1.0;
  210. // std::cout<<" send brake "<<std::endl;
  211. }
  212. else
  213. {
  214. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",ftorque);
  215. if(fabs(gfVehSpd) < 0.1)
  216. {
  217. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",1.0);
  218. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",1.0);
  219. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",1.0);
  220. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",1.0);
  221. }
  222. else
  223. {
  224. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",0.0);
  225. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
  226. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",0.0);
  227. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",0.0);
  228. }
  229. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
  230. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",0.0);
  231. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
  232. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
  233. }
  234. #ifdef TESTBRAKE
  235. }
  236. else
  237. {
  238. if(fabs(gfVehSpd) < 0.1)
  239. {
  240. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",1.0);
  241. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",1.0);
  242. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",1.0);
  243. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",1.0);
  244. }
  245. else
  246. {
  247. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",0.0);
  248. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
  249. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",0.0);
  250. }
  251. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
  252. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
  253. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",0.0);
  254. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
  255. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",300);
  256. }
  257. testnum++;
  258. if(testnum > 1500)testnum = 0;
  259. #endif
  260. // std::cout<<" send dec. "<<std::endl;
  261. // ADS_1_SteerAgReq = 90.0;//decition.wheelangle();
  262. }
  263. void Activate()
  264. {
  265. // for(int j=0;j<100000;j++)
  266. // {
  267. std::cout<<" activate "<<std::endl;
  268. for(int i = 0; i < 3; i++){
  269. SetMsgSignal("ADS_VCU_1","ADS_1_DrvCtrlReq",1.0);
  270. SetMsgSignal("ADS_VCU_1","ADS_1_CtrlReqMod",1.0);
  271. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTqVld",1.0);
  272. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTqEnable",1.0);
  273. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",0.0);
  274. SetMsgSignal("ADS_VCU_1","ADS_1_ADCCAvl",1.0);
  275. SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgReq",gfWheelReq);
  276. SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgVld",1.0);
  277. SetMsgSignal("ADS_EPS_1","ADS_1_SteerPilotAgEna",2.0);
  278. SetMsgSignal("ADS_EPS_1","ADS_1_LdwWarningCmdVld",2.0);
  279. SetMsgSignal("ADS_EPS_1","ADS_1_SteerMaxTqReq",3.0);
  280. SetMsgSignal("ADS_EPS_1","ADS_1_SteerMinTqReq",-3.0);
  281. SetMsgSignal("ADS_EPS_1","ADS_1_ADSHealthSts",1.0);
  282. SetMsgSignal("ADS_EPS_1","CutOutFreshvalues_2CB_S",1.0);
  283. SetMsgSignal("ADS_EPS_1","CutOutMAC_2CB_S",1.0);
  284. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
  285. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",0.0);
  286. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",0.0);
  287. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
  288. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotCtrlType",0.0);
  289. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",0.0);
  290. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",0.0);
  291. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
  292. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
  293. SetMsgSignal("ADS_ONEBOX_2","FCM_2_Avl",1.0);
  294. SetMsgSignal("ADS_COM_2","FCM_2_SysStatus",0.0);
  295. SetMsgSignal("ADS_COM_2","ADS_2_AEBStatus",0.0);
  296. SetMsgSignal("ADS_COM_3","ADS_3_ACCSts",3.0);
  297. // std::cout<<"activate."<<std::endl;
  298. ExecSend();
  299. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  300. }
  301. // }
  302. }
  303. void UnAcitvate()
  304. {
  305. for(int i = 0; i < 3; i++){
  306. SetMsgSignal("ADS_VCU_1","ADS_1_DrvCtrlReq",0.0);
  307. SetMsgSignal("ADS_VCU_1","ADS_1_CtrlReqMod",0.0);
  308. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTqVld",0.0);
  309. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTqEnable",0.0);
  310. SetMsgSignal("ADS_VCU_1","ADS_1_DrvTarTq",0.0);
  311. SetMsgSignal("ADS_VCU_1","ADS_1_ADCCAvl",0.0);
  312. SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgReq",0.0);
  313. SetMsgSignal("ADS_EPS_1","ADS_1_SteerAgVld",0.0);
  314. SetMsgSignal("ADS_EPS_1","ADS_1_SteerPilotAgEna",0.0);
  315. SetMsgSignal("ADS_EPS_1","ADS_1_LdwWarningCmdVld",2.0);
  316. SetMsgSignal("ADS_EPS_1","ADS_1_SteerMaxTqReq",3.0);
  317. SetMsgSignal("ADS_EPS_1","ADS_1_SteerMinTqReq",-3.0);
  318. SetMsgSignal("ADS_EPS_1","ADS_1_ADSHealthSts",1.0);
  319. SetMsgSignal("ADS_EPS_1","CutOutFreshvalues_2CB_S",1.0);
  320. SetMsgSignal("ADS_EPS_1","CutOutMAC_2CB_S",1.0);
  321. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDriOffReq",0.0);
  322. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotDec2StpReq",0.0);
  323. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotkBrkDecTar",0.0);
  324. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarVld",1.0);
  325. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotCtrlType",0.0);
  326. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotBrkDecTarReq",0.0);
  327. SetMsgSignal("ADS_ONEBOX_3","FCM_3_PilotParkCtrlRepSta",0.0);
  328. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDecVld",1.0);
  329. SetMsgSignal("ADS_ONEBOX_2","FCM_2_AebTarDec",1.0);
  330. SetMsgSignal("ADS_ONEBOX_2","FCM_2_Avl",1.0);
  331. SetMsgSignal("ADS_COM_2","FCM_2_SysStatus",1.0);
  332. SetMsgSignal("ADS_COM_2","ADS_2_AEBStatus",0.0);
  333. SetMsgSignal("ADS_COM_3","ADS_3_ACCSts",0.0);
  334. ExecSend();
  335. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  336. }
  337. }
  338. void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
  339. {
  340. (void)index;
  341. (void)dt;
  342. (void)strmemname;
  343. iv::chassis xchassis;
  344. // static int ncount = 0;
  345. if(!xchassis.ParseFromArray(strdata,nSize))
  346. {
  347. std::cout<<"iv::decition::BrainDecition::UpdateChassis ParseFrom Array Error."<<std::endl;
  348. return;
  349. }
  350. if(xchassis.has_epsmode())
  351. {
  352. if(xchassis.epsmode() == 0)
  353. {
  354. gbChassisEPS = true;
  355. }
  356. }
  357. if(xchassis.has_vel())
  358. {
  359. gfVehSpd = xchassis.vel();
  360. gbHaveVehSpd = true;
  361. // std::cout<<" gf Veh speed : "<<gfVehSpd<<std::endl;
  362. }
  363. if(xchassis.has_angle_feedback())
  364. {
  365. gfWheelAngle = xchassis.angle_feedback();
  366. gbHaveWheelAngle = true;
  367. }
  368. }
  369. void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  370. {
  371. (void)index;
  372. (void)dt;
  373. (void)strmemname;
  374. static qint64 oldtime = QDateTime::currentMSecsSinceEpoch();
  375. iv::brain::decition xdecition;
  376. if(!xdecition.ParseFromArray(strdata,nSize))
  377. {
  378. std::cout<<"ListenDecition parse error."<<std::endl;
  379. return;
  380. }
  381. // if(xdecition.gear() != 4)
  382. // {
  383. // qDebug("not D");
  384. // }
  385. xdecition.set_angle_mode(1);
  386. xdecition.set_angle_active(1);
  387. xdecition.set_acc_active(1);
  388. xdecition.set_brake_active(1);
  389. // xdecition.set_brake_type(1);
  390. xdecition.set_auto_mode(3);
  391. // std::cout<<"decition acc: "<<xdecition.accelerator()<<std::endl;
  392. // xdecition.set_wheelangle(45.0);
  393. if((oldtime - QDateTime::currentMSecsSinceEpoch())<-100)qDebug("dection time is %lld diff is %lld ",QDateTime::currentMSecsSinceEpoch(),oldtime - QDateTime::currentMSecsSinceEpoch());
  394. oldtime = QDateTime::currentMSecsSinceEpoch();
  395. gMutex.lock();
  396. gdecition.CopyFrom(xdecition);
  397. gMutex.unlock();
  398. gnDecitionNum = gnDecitionNumMax;
  399. gbChassisEPS = false;
  400. }
  401. void PrepareMsg()
  402. {
  403. static int rollcouter = 0;
  404. // std::cout<<" roll count:: "<<rollcouter<<std::endl;
  405. SetMsgSignal("ADS_EPS_1","ADS_1_RollgCntr1",rollcouter);
  406. SetMsgSignal("ADS_EPS_1","ADS_1_RollgCntr2",rollcouter);
  407. // set_EPS1_signal("CutOutFreshvalues_2CB_S",1.0);
  408. // set_EPS1_signal("CutOutMAC_2CB_S",1.0);
  409. gpsterraes->GetEPS1Data(ADS_EPS_1);
  410. SetMsgSignal("ADS_VCU_1","ADS_1_RollgCntr1",rollcouter);
  411. SetMsgSignal("ADS_VCU_1","ADS_1_RollgCntr2",rollcouter);
  412. gpsterraes->GetVCU1Data(ADS_VCU_1);
  413. SetMsgSignal("ADS_ONEBOX_2","FCM_2_RollgCntr1",rollcouter);
  414. gpsterraes->GetONEBOX2Data(ADS_ONEBOX_2);
  415. SetMsgSignal("ADS_ONEBOX_3","FCM_3_RollgCntr1",rollcouter);
  416. gpsterraes->GetONEBOX3Data(ADS_ONEBOX_3);
  417. SetMsgSignal("ADS_COM_3","ADS_3_RollgCntr1",rollcouter);
  418. gpsterraes->GetADSCOM3Data(ADS_COM3);
  419. SetMsgSignal("ADS_COM_2","ADS_2_RollgCntr1",rollcouter);
  420. gpsterraes->GetADSCOM2Data(ADS_COM2);
  421. rollcouter++;
  422. if(rollcouter>=14)rollcouter = 0;
  423. }
  424. void ExecSend()
  425. {
  426. static int nrd = 0;
  427. PrepareMsg();
  428. // gpsterraes->GetEPS1Data(ADS_EPS_1);
  429. static int nCount = 0;
  430. nCount++;
  431. iv::can::canmsg xmsg;
  432. iv::can::canraw xraw;
  433. // unsigned char * strp = (unsigned char *)&(ServiceControlStatus.command10.byte[0]);
  434. // 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]);
  435. xraw.set_id(0x195);
  436. xraw.set_data(ADS_EPS_1,24);
  437. xraw.set_bext(false);
  438. xraw.set_bremote(false);
  439. xraw.set_len(24);
  440. iv::can::canraw * pxraw195 = xmsg.add_rawmsg();
  441. pxraw195->CopyFrom(xraw);
  442. // qDebug(" 0x144: %02X %02X %02X %02X %02X %02X %02X %02X",byte_144[0],byte_144[1],byte_144[2],byte_144[3],
  443. // byte_144[4],byte_144[5],byte_144[6],byte_144[7]);
  444. xmsg.set_channel(0);
  445. xmsg.set_index(gnIndex);
  446. xraw.set_id(0x1BC);
  447. xraw.set_data(ADS_EPS_3,24);
  448. xraw.set_bext(false);
  449. xraw.set_bremote(false);
  450. xraw.set_len(24);
  451. xmsg.set_channel(0);
  452. // iv::can::canraw * pxraw1BC = xmsg.add_rawmsg();
  453. // pxraw1BC->CopyFrom(xraw);
  454. xraw.set_id(0x159);
  455. xraw.set_data(ADS_ONEBOX_1,24);
  456. xraw.set_bext(false);
  457. xraw.set_bremote(false);
  458. xraw.set_len(24);
  459. // iv::can::canraw * pxraw159 = xmsg.add_rawmsg();
  460. // pxraw159->CopyFrom(xraw);
  461. xraw.set_id(0x145);
  462. xraw.set_data(ADS_ONEBOX_2,24);
  463. xraw.set_bext(false);
  464. xraw.set_bremote(false);
  465. xraw.set_len(24);
  466. iv::can::canraw * pxraw145 = xmsg.add_rawmsg();
  467. pxraw145->CopyFrom(xraw);
  468. if(nrd == 0)
  469. {
  470. xraw.set_id(0x31A);
  471. xraw.set_data(ADS_COM3,24);
  472. xraw.set_bext(false);
  473. xraw.set_bremote(false);
  474. xraw.set_len(24);
  475. iv::can::canraw * pxraw31A = xmsg.add_rawmsg();
  476. pxraw31A->CopyFrom(xraw);
  477. xraw.set_id(0x314);
  478. xraw.set_data(ADS_COM2,8);
  479. xraw.set_bext(false);
  480. xraw.set_bremote(false);
  481. xraw.set_len(8);
  482. iv::can::canraw * pxraw314 = xmsg.add_rawmsg();
  483. pxraw314->CopyFrom(xraw);
  484. }
  485. xraw.set_id(0x14A);
  486. xraw.set_data(ADS_ONEBOX_3,24);
  487. xraw.set_bext(false);
  488. xraw.set_bremote(false);
  489. xraw.set_len(24);
  490. iv::can::canraw * pxraw14A = xmsg.add_rawmsg();
  491. pxraw14A->CopyFrom(xraw);
  492. xraw.set_id(0x167);
  493. xraw.set_data(ADS_VCU_1,24);
  494. xraw.set_bext(false);
  495. xraw.set_bremote(false);
  496. xraw.set_len(24);
  497. iv::can::canraw * pxraw167 = xmsg.add_rawmsg();
  498. pxraw167->CopyFrom(xraw);
  499. xmsg.set_channel(0);
  500. xmsg.set_index(gnIndex);
  501. gnIndex++;
  502. xmsg.set_mstime(QDateTime::currentMSecsSinceEpoch());
  503. int ndatasize = xmsg.ByteSize();
  504. char * strser = new char[ndatasize];
  505. std::shared_ptr<char> pstrser;
  506. pstrser.reset(strser);
  507. if(xmsg.SerializeToArray(strser,ndatasize))
  508. {
  509. iv::modulecomm::ModuleSendMsg(gpacansend,strser,ndatasize);
  510. }
  511. else
  512. {
  513. std::cout<<"MainWindow::onTimer serialize error."<<std::endl;
  514. }
  515. nrd++;
  516. if(nrd == 5)nrd = 0;
  517. }
  518. void initial()
  519. {
  520. for (uint8_t i = 0; i < 24; i++) //CAN to canfd
  521. {
  522. //byte_36E[i] = 0;
  523. }
  524. }
  525. void sendthread()
  526. {
  527. initial();
  528. iv::brain::decition xdecition;
  529. UnAcitvate();
  530. // UnAcitvate();
  531. int nstate = 0; //0 Un 1 Activate
  532. // Activate();
  533. while(gbSendRun)
  534. {
  535. if(gnDecitionNum <= 0)
  536. {
  537. if(nstate == 1)
  538. {
  539. UnAcitvate();
  540. nstate = 0;
  541. }
  542. xdecition.CopyFrom(gdecition_def);
  543. }
  544. else
  545. {
  546. if(nstate == 0)
  547. {
  548. Activate();
  549. nstate = 1;
  550. }
  551. gMutex.lock();
  552. xdecition.CopyFrom(gdecition);
  553. gMutex.unlock();
  554. gnDecitionNum--;
  555. }
  556. #ifdef TORQUEBRAKETEST
  557. if(gnothavetb < 10)
  558. {
  559. iv::controller::torquebrake xtb;
  560. gMutextb.lock();
  561. xtb.CopyFrom(gtb);
  562. gMutextb.unlock();
  563. if(xtb.enable())
  564. {
  565. xdecition.set_torque(xtb.torque());
  566. xdecition.set_brake(xtb.brake());
  567. std::cout<<" use xtb. torque: "<<xtb.torque()<<" brake: "<<xtb.brake()<<std::endl;
  568. // gcontroller->control_torque(xtb.torque());
  569. // gcontroller->control_brake(xtb.brake());
  570. // qDebug("use tb value torque is %f brake is %f",xtb.torque(),xtb.brake());
  571. }
  572. else
  573. {
  574. // qDebug("torquebrake not enable.");
  575. }
  576. gnothavetb++;
  577. }
  578. #endif
  579. executeDecition(xdecition);
  580. if(gbChassisEPS == false) ExecSend();
  581. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  582. }
  583. UnAcitvate();
  584. }
  585. #ifdef Q_OS_LINUX
  586. void sig_int(int signo)
  587. {
  588. (void)signo;
  589. gbSendRun = false;
  590. gpsendthread->join();
  591. iv::modulecomm::Unregister(gpacansend);
  592. iv::modulecomm::Unregister(gpachassis);
  593. iv::modulecomm::Unregister(gpadecition);
  594. std::cout<<" controller exit."<<std::endl;
  595. exit(0);
  596. }
  597. #endif
  598. // void processStream(std::istream& stream) {
  599. // std::string line;
  600. // while (std::getline(stream, line)) {
  601. // std::cout << "Read line: " << line << std::endl;
  602. // }
  603. // }
  604. void LoadXML(std::string strxmlpath){
  605. iv::xmlparam::Xmlparam xp(strxmlpath);
  606. gbUseOutDBC = xp.GetParam("UseOutDBC",false);
  607. gstrdbcpath = xp.GetParam("dbcpath","./ADCC_CH.dbc");
  608. }
  609. void Listencanrecv0()
  610. {
  611. void * pblambda = iv::modulecomm::RegisterRecv("canrecv0",[](const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname){
  612. (void)strdata;
  613. (void)nSize;
  614. (void)index;
  615. (void)dt;
  616. (void)strmemname;
  617. iv::can::canmsg xmsg;
  618. if(false == xmsg.ParseFromArray(strdata,nSize))
  619. {
  620. std::cout<<"controller Listencan0 fail."<<std::endl;
  621. return;
  622. }
  623. int i;
  624. for(i=0;i<xmsg.rawmsg_size();i++)
  625. {
  626. iv::can::canraw * praw = xmsg.mutable_rawmsg(i);
  627. if(praw->id() == 0x14f)
  628. {
  629. unsigned char byte[24];
  630. if(praw->len() == 24)
  631. {
  632. memcpy(byte,praw->data().data(),24);
  633. unsigned int value;
  634. value = byte[2]&0x01;
  635. if(value == 0)
  636. {
  637. gbSendBrake = true;//std::cout<<" brake available."<<std::endl;
  638. }
  639. else
  640. {
  641. gbSendBrake = false;//std::cout<<" warning: no brake unavailable."<<std::endl;
  642. }
  643. }
  644. }
  645. if(praw->id() == 0x21)
  646. {
  647. unsigned char xdata[8];
  648. if(praw->len() == 8)
  649. {
  650. memcpy(xdata,praw->data().data(),8);
  651. unsigned int value;
  652. value = xdata[2]&0xff;
  653. value = value<<8;
  654. value =value + (xdata[3]&0xff);
  655. double facc = value;
  656. facc = facc * 0.001 - 2.0;
  657. gfVehAcc = facc*9.8;
  658. gnLastAccUptime = std::chrono::system_clock::now().time_since_epoch().count();
  659. // std::cout<<" acc : "<<gfVehAcc<<std::endl;
  660. }
  661. }
  662. }
  663. });
  664. (void)pblambda;
  665. }
  666. #include <QFile>
  667. #include <QTextStream>
  668. #include <strings.h>
  669. #include <streambuf>
  670. #include <sstream>
  671. #include <iostream>
  672. #include <istream>
  673. #include <fstream>
  674. int main(int argc, char *argv[])
  675. {
  676. // std::istringstream iss("First line.\nSecond line.\n");
  677. // // 将 iss 传递给 processStream,这是合法的
  678. // processStream(iss);
  679. RegisterIVBackTrace();
  680. showversion("controller_changan_shenlan");
  681. QCoreApplication a(argc, argv);
  682. QString strpath = QCoreApplication::applicationDirPath();
  683. if(argc < 2)
  684. strpath = strpath + "/controller_chery_sterra_es_fcm.xml";
  685. else
  686. strpath = argv[1];
  687. std::cout<<strpath.toStdString()<<std::endl;
  688. LoadXML(strpath.toStdString());
  689. if(gbUseOutDBC == false)
  690. {
  691. QFile xFile;
  692. xFile.setFileName(":/FCM.dbc");
  693. if(xFile.open(QIODevice::ReadOnly))
  694. {
  695. std::cout<<" open qrc dbc file success. "<<std::endl;
  696. QTextStream in(&xFile);
  697. QString content = in.readAll(); // 读取文件全部内容到QString
  698. xFile.close();
  699. // 将QString转换为std::string,然后传递给std::istringstream
  700. std::istringstream iss(content.toStdString());
  701. gpsterraes = new sterraes(std::string(":/ADCC_CH.dbc"),iss);
  702. dbcsigpacker * ppac = new dbcsigpacker(std::string(":/ADCC_CH.dbc"),iss);
  703. ppac->SetMsgSignal("ADS_EPS_1","hi",1);
  704. }
  705. else
  706. std::cout<<" open qrc dbc file fail. "<<std::endl;
  707. }
  708. else
  709. {
  710. gpsterraes = new sterraes(gstrdbcpath);
  711. }
  712. // gdecition_def.set_accelerator(-0.5);
  713. gdecition_def.set_brake(0);
  714. gdecition_def.set_rightlamp(false);
  715. gdecition_def.set_leftlamp(false);
  716. gdecition_def.set_wheelangle(0);
  717. gdecition_def.set_angle_mode(0);
  718. gdecition_def.set_angle_active(0);
  719. gdecition_def.set_acc_active(0);
  720. // gdecition_def.set_brake_active(1);
  721. gdecition_def.set_brake_type(0);
  722. gdecition_def.set_auto_mode(0);
  723. iv::xmlparam::Xmlparam xp(strpath.toStdString());
  724. gstrmemcansend = xp.GetParam("cansend","cansend0");
  725. gstrmemdecition = xp.GetParam("dection","deciton");
  726. gstrmemchassis = xp.GetParam("chassismsgname","chassis");
  727. kp = xp.GetParam("kp",0.5);
  728. ki = xp.GetParam("ki",0.3);
  729. kd = xp.GetParam("kd",0.01);
  730. gbPrintPIDOut = xp.GetParam("PringtPIDOut",false);
  731. TorqueRatio = xp.GetParam("TorqueRatio",1.4);
  732. gpacansend = iv::modulecomm::RegisterSend(gstrmemcansend.data(),10000,1);
  733. gpadecition = iv::modulecomm::RegisterRecv(gstrmemdecition.data(),ListenDeciton);
  734. gpachassis = iv::modulecomm::RegisterRecv(gstrmemchassis.data(),UpdateChassis);
  735. #ifdef TORQUEBRAKETEST
  736. EnableTorqueBrakeTest();
  737. #endif
  738. // testes();
  739. // return 0;
  740. Listencanrecv0();
  741. std::thread xthread(sendthread);
  742. gpsendthread = &xthread;
  743. #ifdef Q_OS_LINUX
  744. signal(SIGINT, sig_int);
  745. signal(SIGTERM,sig_int);
  746. #endif
  747. return a.exec();
  748. }