main.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739
  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. #ifdef Q_OS_LINUX
  14. #include <signal.h>
  15. #endif
  16. #include "candbc.h"
  17. #include "sterraes.h"
  18. std::string gstrdbcpath;
  19. bool gbUseOutDBC;
  20. sterraes * gpsterraes;
  21. static void * gpacansend;
  22. static void * gpadecition;
  23. static void * gpachassis;
  24. static std::string gstrmemdecition;
  25. static std::string gstrmemcansend;
  26. static std::string gstrmemchassis;
  27. static bool gbSendRun = true;
  28. static bool gbChassisEPS = false;
  29. static iv::brain::decition gdecition_def;
  30. static iv::brain::decition gdecition;
  31. static QTime gTime;
  32. static int gnLastSendTime = 0;
  33. static int gnLastRecvDecTime = -1000;
  34. static int gnDecitionNum = 0; //when is zero,send default;
  35. const int gnDecitionNumMax = 100;
  36. static int gnIndex = 0;
  37. static bool gbHaveVehSpd = false;
  38. static double gfVehSpd = 0.0;
  39. static bool gbHaveWheelAngle = false;
  40. static double gfWheelAngle = 0.0;
  41. static double gfWheelSpeedLim = 300; //300 degrees per second
  42. static QMutex gMutex;
  43. static std::thread * gpsendthread = NULL;
  44. unsigned char ADS_EPS_1[24];// 0x195/405
  45. unsigned char ADS_EPS_3[24]; // 0x1BC/444
  46. unsigned char ADS_ONEBOX_1[24];// 0x159/345
  47. unsigned char ADS_VCU_1[24]; // 0x167/359
  48. static int gnState = 0; //0 not act 1 act
  49. CANPacker * gpPacker;
  50. std::vector<SignalPackValue> mvectorADSEPS1;
  51. std::vector<SignalPackValue> mvectorADSEPS3;
  52. std::vector<SignalPackValue> mvectorADSONEBOX1;
  53. std::vector<SignalPackValue> mvectorADSVCU1;
  54. double ADS_1_DrvCtrlReq = 0.0;
  55. double ADS_1_CtrlReqMod = 0.0;
  56. double ADS_1_DrvTarTqVld = 0.0;
  57. double ADS_1_DrvTarTqEnable = 0.0;
  58. double ADS_1_DrvTarTq = 0.0;
  59. double ADS_1_TarGearReq = 0.0;
  60. double ADS_1_TarGearReqVld = 0.0;
  61. double ADS_1_GearCtrlEnable = 1.0;
  62. double ADS_1_SteerAgReq = 0.0;
  63. double ADS_1_SteerAgVld = 0.0;
  64. double ADS_1_SteerPilotAgEna = 0.0;
  65. double gfWheelReq = 0.0;
  66. double gfTorqueReq = 0.0;
  67. double gfBrakeReq = 0.0;
  68. double ADS_1_PilotCtrlRepSta = 0.0;
  69. double ADS_1_PilotParkCtrlType = 0.0;
  70. double ADS_1_PilotParkBrkDecTar = 0.0;
  71. double ADS_1_PilotParkCtrlRepMod = 0.0;
  72. double ADS_1_PilotParkBrkDecTarVld = 0.0;
  73. double ADS_1_PilotParkBrkDecTarEnable = 0.0;
  74. double ADS_1_PilotParkDec2StpReq = 0.0;
  75. double ADS_1_PilotParkDriOffReq = 0.0;
  76. double ADS_1_ParkCtrlMod = 0.0;
  77. void set_EPS1_signal(std::string strsigname,double value){
  78. gpsterraes->set_EPS1_signal(strsigname,value);
  79. }
  80. void set_EPS3_signal(std::string strsigname,double value){
  81. gpsterraes->set_EPS3_signal(strsigname,value);
  82. }
  83. void set_ONEBOX1_signal(std::string strsigname,double value){
  84. gpsterraes->set_ONEBOX1_signal(strsigname,value);
  85. }
  86. void set_VCU1_signal(std::string strsigname,double value){
  87. gpsterraes->set_VCU1_signal(strsigname,value);
  88. }
  89. void ExecSend();
  90. void executeDecition(const iv::brain::decition &decition)
  91. {
  92. if(decition.brake()<(-0.0001))
  93. {
  94. ADS_1_DrvTarTq = 0.0;
  95. ADS_1_ParkCtrlMod = 1.0;
  96. ADS_1_PilotParkDriOffReq = 0.0;
  97. ADS_1_PilotParkDec2StpReq = 1.0;
  98. ADS_1_PilotParkBrkDecTar = decition.brake();
  99. ADS_1_PilotParkBrkDecTarVld = 1.0;
  100. ADS_1_PilotParkCtrlType = 1.0;
  101. ADS_1_PilotParkBrkDecTarEnable = 1.0;
  102. }
  103. else
  104. {
  105. if(fabs(gfVehSpd) < 0.1)
  106. {
  107. ADS_1_PilotParkDriOffReq = 1.0;
  108. }
  109. ADS_1_DrvTarTq = decition.torque();
  110. if(ADS_1_DrvTarTq > 100)ADS_1_DrvTarTq =100.0;
  111. ADS_1_PilotParkDec2StpReq = 0.0;
  112. ADS_1_PilotParkBrkDecTarEnable = 0.0;
  113. ADS_1_PilotParkBrkDecTarVld = 0.0;
  114. ADS_1_PilotParkBrkDecTar = 0.0;
  115. ADS_1_SteerAgReq = decition.wheelangle();
  116. }
  117. }
  118. void Activate()
  119. {
  120. // for(int j=0;j<100000;j++)
  121. // {
  122. std::cout<<" activate "<<std::endl;
  123. for(int i = 0; i < 3; i++){
  124. ADS_1_DrvCtrlReq = 1.0;
  125. ADS_1_CtrlReqMod = 2.0; //1 Pilot 2 Park
  126. ADS_1_DrvTarTqVld = 1.0;
  127. ADS_1_DrvTarTqEnable = 1.0;
  128. ADS_1_DrvTarTq = 0.0;
  129. ADS_1_TarGearReq = 4.0; //1 P 4 D
  130. ADS_1_TarGearReqVld = 1.0;
  131. ADS_1_GearCtrlEnable = 0.0;
  132. ADS_1_SteerAgReq = gfWheelReq;
  133. ADS_1_SteerAgVld = 1.0;
  134. ADS_1_SteerPilotAgEna = 1.0;
  135. ADS_1_PilotParkDec2StpReq = 1.0;
  136. ADS_1_ParkCtrlMod = 1.0;
  137. ExecSend();
  138. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  139. }
  140. // }
  141. }
  142. void UnAcitvate()
  143. {
  144. if(fabs(gfVehSpd)<0.1)
  145. {
  146. for(int i = 0; i < 3; i++){
  147. ADS_1_DrvCtrlReq = 1.0;
  148. ADS_1_CtrlReqMod = 2.0;
  149. ADS_1_DrvTarTqVld = 1.0;
  150. ADS_1_DrvTarTqEnable = 1.0;
  151. ADS_1_DrvTarTq = 0.0;
  152. ADS_1_TarGearReq = 1.0;
  153. ADS_1_TarGearReqVld = 1.0;
  154. ADS_1_GearCtrlEnable = 0.0;
  155. ADS_1_SteerAgReq = 0.0;
  156. ADS_1_SteerAgVld = 1.0;
  157. ADS_1_SteerPilotAgEna = 1.0;
  158. ExecSend();
  159. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  160. }
  161. }
  162. for(int i = 0; i < 3; i++){
  163. ADS_1_DrvCtrlReq = 0.0;
  164. ADS_1_CtrlReqMod = 0.0;
  165. ADS_1_DrvTarTqVld = 0.0;
  166. ADS_1_DrvTarTqEnable = 0.0;
  167. ADS_1_DrvTarTq = 0.0;
  168. // ADS_1_TarGearReq = 1.0;
  169. ADS_1_TarGearReqVld = 0.0;
  170. ADS_1_GearCtrlEnable = 1.0;
  171. ADS_1_SteerAgReq = 0.0;
  172. ADS_1_SteerAgVld = 0.0;
  173. ADS_1_SteerPilotAgEna = 0.0;
  174. ADS_1_PilotParkDec2StpReq = 0.0;
  175. ADS_1_ParkCtrlMod = 0.0;
  176. ExecSend();
  177. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  178. }
  179. }
  180. void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
  181. {
  182. (void)index;
  183. (void)dt;
  184. (void)strmemname;
  185. iv::chassis xchassis;
  186. // static int ncount = 0;
  187. if(!xchassis.ParseFromArray(strdata,nSize))
  188. {
  189. std::cout<<"iv::decition::BrainDecition::UpdateChassis ParseFrom Array Error."<<std::endl;
  190. return;
  191. }
  192. if(xchassis.has_epsmode())
  193. {
  194. if(xchassis.epsmode() == 0)
  195. {
  196. gbChassisEPS = true;
  197. }
  198. }
  199. if(xchassis.has_vel())
  200. {
  201. gfVehSpd = xchassis.vel();
  202. gbHaveVehSpd = true;
  203. // std::cout<<" gf Veh speed : "<<gfVehSpd<<std::endl;
  204. }
  205. if(xchassis.has_angle_feedback())
  206. {
  207. gfWheelAngle = xchassis.angle_feedback();
  208. gbHaveWheelAngle = true;
  209. }
  210. }
  211. void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  212. {
  213. (void)index;
  214. (void)dt;
  215. (void)strmemname;
  216. static qint64 oldtime = QDateTime::currentMSecsSinceEpoch();
  217. iv::brain::decition xdecition;
  218. if(!xdecition.ParseFromArray(strdata,nSize))
  219. {
  220. std::cout<<"ListenDecition parse error."<<std::endl;
  221. return;
  222. }
  223. // if(xdecition.gear() != 4)
  224. // {
  225. // qDebug("not D");
  226. // }
  227. xdecition.set_angle_mode(1);
  228. xdecition.set_angle_active(1);
  229. xdecition.set_acc_active(1);
  230. xdecition.set_brake_active(1);
  231. // xdecition.set_brake_type(1);
  232. xdecition.set_auto_mode(3);
  233. // xdecition.set_wheelangle(45.0);
  234. if((oldtime - QDateTime::currentMSecsSinceEpoch())<-100)qDebug("dection time is %lld diff is %lld ",QDateTime::currentMSecsSinceEpoch(),oldtime - QDateTime::currentMSecsSinceEpoch());
  235. oldtime = QDateTime::currentMSecsSinceEpoch();
  236. gMutex.lock();
  237. gdecition.CopyFrom(xdecition);
  238. gMutex.unlock();
  239. gnDecitionNum = gnDecitionNumMax;
  240. gbChassisEPS = false;
  241. }
  242. void PrepareMsg()
  243. {
  244. static int rollcouter = 0;
  245. // std::cout<<" roll count:: "<<rollcouter<<std::endl;
  246. set_EPS1_signal("ADS_1_RollgCntr1",rollcouter);
  247. set_EPS1_signal("ADS_1_Resd1",0.0);
  248. set_EPS1_signal("ADS_1_SteerAgReq",ADS_1_SteerAgReq);
  249. set_EPS1_signal("ADS_1_SteerAgVld",ADS_1_SteerAgVld);
  250. set_EPS1_signal("ADS_1_SteerPilotAgEna",ADS_1_SteerPilotAgEna);
  251. set_EPS1_signal("ADS_1_RollgCntr2",rollcouter);
  252. set_EPS1_signal("ADS_1_Resd2",0.0);
  253. set_EPS1_signal("ADS_1_SteerTqEna",1.0);
  254. set_EPS1_signal("ADS_1_LdwWarningCmd",0.0);
  255. set_EPS1_signal("ADS_1_LdwWarningCmdVld",2.0);
  256. set_EPS1_signal("ADS_1_SteerMaxTqReq",10.0);
  257. set_EPS1_signal("ADS_1_SteerMinTqReq",1.0);
  258. set_EPS1_signal("ADS_1_ADSHealthSts",1.0);
  259. set_EPS1_signal("CutOutFreshvalues_2CB_S",1.0);
  260. set_EPS1_signal("CutOutMAC_2CB_S",1.0);
  261. gpsterraes->GetEPS1Data(ADS_EPS_1);
  262. set_VCU1_signal("ADS_1_RollgCntr1",rollcouter);
  263. set_VCU1_signal("ADS_1_Resd1",0);
  264. set_VCU1_signal("ADS_1_DrvTarTq",ADS_1_DrvTarTq);
  265. set_VCU1_signal("ADS_1_DrvTarTqVld",ADS_1_DrvTarTqVld);
  266. set_VCU1_signal("ADS_1_DrvCtrlReq",ADS_1_DrvCtrlReq);
  267. set_VCU1_signal("ADS_1_CtrlReqMod",ADS_1_CtrlReqMod);
  268. set_VCU1_signal("ADS_1_DrvTarTqEnable",ADS_1_DrvTarTqEnable);
  269. set_VCU1_signal("ADS_1_RollgCntr2",rollcouter);
  270. set_VCU1_signal("ADS_1_Resd2",0);
  271. set_VCU1_signal("ADS_1_TarGearReq",ADS_1_TarGearReq);
  272. set_VCU1_signal("ADS_1_TarGearReqVld",ADS_1_TarGearReqVld);
  273. set_VCU1_signal("ADS_1_GearCtrlEnable",ADS_1_GearCtrlEnable);
  274. gpsterraes->GetVCU1Data(ADS_VCU_1);
  275. set_ONEBOX1_signal("ADS_1_RollgCntr1",rollcouter);
  276. set_ONEBOX1_signal("ADS_1_Resd1",0);
  277. set_ONEBOX1_signal("ADS_1_PilotCtrlRepSta",ADS_1_PilotCtrlRepSta);
  278. set_ONEBOX1_signal("ADS_1_PilotParkCtrlType",ADS_1_PilotParkCtrlType);
  279. set_ONEBOX1_signal("ADS_1_PilotParkBrkDecTar",ADS_1_PilotParkBrkDecTar);
  280. set_ONEBOX1_signal("ADS_1_PilotParkCtrlRepMod",ADS_1_PilotParkCtrlRepMod);
  281. set_ONEBOX1_signal("ADS_1_PilotParkBrkDecTarVld",ADS_1_PilotParkBrkDecTarVld);
  282. set_ONEBOX1_signal("ADS_1_PilotParkBrkDecTarEnable",ADS_1_PilotParkBrkDecTarEnable);
  283. set_ONEBOX1_signal("ADS_1_PilotParkDec2StpReq",ADS_1_PilotParkDec2StpReq);
  284. set_ONEBOX1_signal("ADS_1_PilotParkDriOffReq",ADS_1_PilotParkDriOffReq);
  285. set_ONEBOX1_signal("ADS_1_ParkCtrlMod",ADS_1_ParkCtrlMod);
  286. gpsterraes->GetONEBOX1Data(ADS_ONEBOX_1);
  287. rollcouter++;
  288. }
  289. void ExecSend()
  290. {
  291. PrepareMsg();
  292. static int nCount = 0;
  293. nCount++;
  294. iv::can::canmsg xmsg;
  295. iv::can::canraw xraw;
  296. // unsigned char * strp = (unsigned char *)&(ServiceControlStatus.command10.byte[0]);
  297. // 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]);
  298. xraw.set_id(0x195);
  299. xraw.set_data(ADS_EPS_1,24);
  300. xraw.set_bext(false);
  301. xraw.set_bremote(false);
  302. xraw.set_len(24);
  303. iv::can::canraw * pxraw195 = xmsg.add_rawmsg();
  304. pxraw195->CopyFrom(xraw);
  305. // qDebug(" 0x144: %02X %02X %02X %02X %02X %02X %02X %02X",byte_144[0],byte_144[1],byte_144[2],byte_144[3],
  306. // byte_144[4],byte_144[5],byte_144[6],byte_144[7]);
  307. xmsg.set_channel(0);
  308. xmsg.set_index(gnIndex);
  309. xraw.set_id(0x1BC);
  310. xraw.set_data(ADS_EPS_3,24);
  311. xraw.set_bext(false);
  312. xraw.set_bremote(false);
  313. xraw.set_len(24);
  314. xmsg.set_channel(0);
  315. // iv::can::canraw * pxraw1BC = xmsg.add_rawmsg();
  316. // pxraw1BC->CopyFrom(xraw);
  317. xraw.set_id(0x159);
  318. xraw.set_data(ADS_ONEBOX_1,24);
  319. xraw.set_bext(false);
  320. xraw.set_bremote(false);
  321. xraw.set_len(24);
  322. iv::can::canraw * pxraw159 = xmsg.add_rawmsg();
  323. pxraw159->CopyFrom(xraw);
  324. xraw.set_id(0x167);
  325. xraw.set_data(ADS_VCU_1,24);
  326. xraw.set_bext(false);
  327. xraw.set_bremote(false);
  328. xraw.set_len(24);
  329. iv::can::canraw * pxraw167 = xmsg.add_rawmsg();
  330. pxraw167->CopyFrom(xraw);
  331. xmsg.set_channel(0);
  332. xmsg.set_index(gnIndex);
  333. gnIndex++;
  334. xmsg.set_mstime(QDateTime::currentMSecsSinceEpoch());
  335. int ndatasize = xmsg.ByteSize();
  336. char * strser = new char[ndatasize];
  337. std::shared_ptr<char> pstrser;
  338. pstrser.reset(strser);
  339. if(xmsg.SerializeToArray(strser,ndatasize))
  340. {
  341. iv::modulecomm::ModuleSendMsg(gpacansend,strser,ndatasize);
  342. }
  343. else
  344. {
  345. std::cout<<"MainWindow::onTimer serialize error."<<std::endl;
  346. }
  347. }
  348. void initial()
  349. {
  350. for (uint8_t i = 0; i < 24; i++) //CAN to canfd
  351. {
  352. //byte_36E[i] = 0;
  353. }
  354. }
  355. void SendEPS3()
  356. {
  357. static int rollcouter = 0;
  358. gpsterraes->GetEPS3Data(ADS_EPS_3);
  359. ExecSend();
  360. rollcouter++;
  361. if(rollcouter>14)rollcouter = 0;
  362. }
  363. void SendEPS1()
  364. {
  365. static int rollcouter = 0;
  366. // std::cout<<" roll count:: "<<rollcouter<<std::endl;
  367. set_EPS1_signal("ADS_1_RollgCntr1",rollcouter);
  368. set_EPS1_signal("ADS_1_Resd1",0.0);
  369. gpsterraes->GetEPS1Data(ADS_EPS_1);
  370. ExecSend();
  371. rollcouter++;
  372. if(rollcouter>14)rollcouter = 0;
  373. }
  374. void testes()
  375. {
  376. int i = 0;
  377. int rollcouter = 0;
  378. double fwheelang = 90.0;
  379. set_EPS1_signal("ADS_1_RollgCntr1",rollcouter);
  380. set_EPS1_signal("ADS_1_Resd1",0.0);
  381. set_EPS1_signal("ADS_1_SteerAgReq",fwheelang);
  382. set_EPS1_signal("ADS_1_SteerAgVld",1.0);
  383. set_EPS1_signal("ADS_1_SteerPilotAgEna",0.0);
  384. set_EPS1_signal("ADS_1_RollgCntr2",rollcouter);
  385. set_EPS1_signal("ADS_1_Resd2",0.0);
  386. set_EPS1_signal("ADS_1_SteerTqEna",1.0);
  387. set_EPS1_signal("ADS_1_LdwWarningCmd",0.0);
  388. set_EPS1_signal("ADS_1_LdwWarningCmdVld",2.0);
  389. set_EPS1_signal("ADS_1_SteerMaxTqReq",10.0);
  390. set_EPS1_signal("ADS_1_SteerMinTqReq",1.0);
  391. set_EPS1_signal("ADS_1_ADSHealthSts",1.0);
  392. set_EPS1_signal("CutOutFreshvalues_2CB_S",1.0);
  393. set_EPS1_signal("CutOutMAC_2CB_S",1.0);
  394. set_EPS3_signal("ADS_3_RollgCntr1",rollcouter);
  395. set_EPS3_signal("ADS_3_Resd1",0.0);
  396. set_EPS3_signal("ADS_3_SteerParkAgReq",0.0);
  397. set_EPS3_signal("ADS_3_SteerParkAgVld",0.0);
  398. set_EPS3_signal("ADS_3_SteerParkAgEna",0.0);
  399. set_EPS3_signal("ADS_3_RollgCntr2",rollcouter);
  400. set_EPS3_signal("ADS_3_Resd2",0.0);
  401. set_EPS3_signal("ADS_3_ParkFcnMode",0.0);
  402. set_EPS3_signal("ADS_3_ADSParkHealthSts",0.0);
  403. for(i=0;i<10;i++)
  404. {
  405. set_EPS1_signal("ADS_1_SteerPilotAgEna",0.0);
  406. SendEPS1();
  407. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  408. }
  409. // for(i=0;i<10;i++)
  410. // {
  411. // set_EPS3_signal("ADS_3_SteerParkAgEna",1.0);
  412. // set_EPS3_signal("ADS_3_SteerParkAgReq",0.0);
  413. // set_EPS3_signal("ADS_3_SteerParkAgVld",0.0);
  414. // SendEPS3();
  415. // std::this_thread::sleep_for(std::chrono::milliseconds(10));
  416. // }
  417. for(i=0;i<3000;i++)
  418. {
  419. set_EPS1_signal("ADS_1_SteerPilotAgEna",2.0);
  420. set_EPS1_signal("ADS_1_SteerAgReq",fwheelang);
  421. set_EPS1_signal("ADS_1_SteerAgVld",1.0);
  422. SendEPS1();
  423. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  424. }
  425. for(i=0;i<10;i++)
  426. {
  427. set_EPS1_signal("ADS_1_SteerPilotAgEna",0.0);
  428. SendEPS1();
  429. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  430. }
  431. }
  432. void sendthread()
  433. {
  434. initial();
  435. iv::brain::decition xdecition;
  436. UnAcitvate();
  437. // UnAcitvate();
  438. int nstate = 0; //0 Un 1 Activate
  439. // Activate();
  440. while(gbSendRun)
  441. {
  442. if(gnDecitionNum <= 0)
  443. {
  444. if(nstate == 1)
  445. {
  446. UnAcitvate();
  447. nstate = 0;
  448. }
  449. xdecition.CopyFrom(gdecition_def);
  450. }
  451. else
  452. {
  453. if(nstate == 0)
  454. {
  455. Activate();
  456. nstate = 1;
  457. }
  458. gMutex.lock();
  459. xdecition.CopyFrom(gdecition);
  460. gMutex.unlock();
  461. gnDecitionNum--;
  462. }
  463. #ifdef TORQUEBRAKETEST
  464. if(gnothavetb < 10)
  465. {
  466. iv::controller::torquebrake xtb;
  467. gMutextb.lock();
  468. xtb.CopyFrom(gtb);
  469. gMutextb.unlock();
  470. if(xtb.enable())
  471. {
  472. xdecition.set_torque(xtb.torque());
  473. xdecition.set_brake(xtb.brake());
  474. std::cout<<" use xtb. torque: "<<xtb.torque()<<" brake: "<<xtb.brake()<<std::endl;
  475. // gcontroller->control_torque(xtb.torque());
  476. // gcontroller->control_brake(xtb.brake());
  477. // qDebug("use tb value torque is %f brake is %f",xtb.torque(),xtb.brake());
  478. }
  479. else
  480. {
  481. // qDebug("torquebrake not enable.");
  482. }
  483. gnothavetb++;
  484. }
  485. #endif
  486. executeDecition(xdecition);
  487. if(gbChassisEPS == false) ExecSend();
  488. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  489. }
  490. UnAcitvate();
  491. }
  492. #ifdef Q_OS_LINUX
  493. void sig_int(int signo)
  494. {
  495. gbSendRun = false;
  496. gpsendthread->join();
  497. iv::modulecomm::Unregister(gpacansend);
  498. iv::modulecomm::Unregister(gpachassis);
  499. iv::modulecomm::Unregister(gpadecition);
  500. std::cout<<" controller exit."<<std::endl;
  501. exit(0);
  502. }
  503. #endif
  504. // void processStream(std::istream& stream) {
  505. // std::string line;
  506. // while (std::getline(stream, line)) {
  507. // std::cout << "Read line: " << line << std::endl;
  508. // }
  509. // }
  510. void LoadXML(std::string strxmlpath){
  511. iv::xmlparam::Xmlparam xp(strxmlpath);
  512. gbUseOutDBC = xp.GetParam("UseOutDBC",false);
  513. gstrdbcpath = xp.GetParam("dbcpath","./ADCC_CH.dbc");
  514. }
  515. #include <QFile>
  516. #include <fstream>
  517. int main(int argc, char *argv[])
  518. {
  519. std::istringstream iss("First line.\nSecond line.\n");
  520. // // 将 iss 传递给 processStream,这是合法的
  521. // processStream(iss);
  522. RegisterIVBackTrace();
  523. showversion("controller_changan_shenlan");
  524. QCoreApplication a(argc, argv);
  525. QString strpath = QCoreApplication::applicationDirPath();
  526. if(argc < 2)
  527. strpath = strpath + "/controller_chery_sterra_es.xml";
  528. else
  529. strpath = argv[1];
  530. std::cout<<strpath.toStdString()<<std::endl;
  531. LoadXML(strpath.toStdString());
  532. if(gbUseOutDBC == false)
  533. {
  534. QFile xFile;
  535. xFile.setFileName(":/ADCC_CH.dbc");
  536. if(xFile.open(QIODevice::ReadOnly))
  537. {
  538. std::cout<<" open qrc dbc file success. "<<std::endl;
  539. QTextStream in(&xFile);
  540. QString content = in.readAll(); // 读取文件全部内容到QString
  541. xFile.close();
  542. // 将QString转换为std::string,然后传递给std::istringstream
  543. std::istringstream iss(content.toStdString());
  544. gpsterraes = new sterraes(std::string(":/ADCC_CH.dbc"),iss);
  545. }
  546. else
  547. std::cout<<" open qrc dbc file fail. "<<std::endl;
  548. }
  549. else
  550. {
  551. gpsterraes = new sterraes(gstrdbcpath);
  552. }
  553. // gdecition_def.set_accelerator(-0.5);
  554. gdecition_def.set_brake(0);
  555. gdecition_def.set_rightlamp(false);
  556. gdecition_def.set_leftlamp(false);
  557. gdecition_def.set_wheelangle(0);
  558. gdecition_def.set_angle_mode(0);
  559. gdecition_def.set_angle_active(0);
  560. gdecition_def.set_acc_active(0);
  561. // gdecition_def.set_brake_active(1);
  562. gdecition_def.set_brake_type(0);
  563. gdecition_def.set_auto_mode(0);
  564. // gdecition_def.set_angle_mode(0);
  565. // gdecition_def.set_angle_active(0);
  566. // gdecition_def.set_acc_active(0);
  567. // gdecition_def.set_brake_active(0);
  568. // gdecition_def.set_brake_type(0);
  569. // gdecition_def.set_auto_mode(0);
  570. // gTime.start();
  571. iv::xmlparam::Xmlparam xp(strpath.toStdString());
  572. gstrmemcansend = xp.GetParam("cansend","cansend0");
  573. gstrmemdecition = xp.GetParam("dection","deciton");
  574. gstrmemchassis = xp.GetParam("chassismsgname","chassis");
  575. gpacansend = iv::modulecomm::RegisterSend(gstrmemcansend.data(),10000,1);
  576. gpadecition = iv::modulecomm::RegisterRecv(gstrmemdecition.data(),ListenDeciton);
  577. gpachassis = iv::modulecomm::RegisterRecv(gstrmemchassis.data(),UpdateChassis);
  578. #ifdef TORQUEBRAKETEST
  579. EnableTorqueBrakeTest();
  580. #endif
  581. // testes();
  582. // return 0;
  583. std::thread xthread(sendthread);
  584. gpsendthread = &xthread;
  585. #ifdef Q_OS_LINUX
  586. signal(SIGINT, sig_int);
  587. signal(SIGTERM,sig_int);
  588. #endif
  589. return a.exec();
  590. }