main.cpp 21 KB

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