main.cpp 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717
  1. #include <QCoreApplication>
  2. #include <QTime>
  3. #include <QMutex>
  4. #include "control/control_status.h"
  5. #include "control/controller.h"
  6. #include "xmlparam.h"
  7. #include "modulecomm.h"
  8. #include "ivbacktrace.h"
  9. #include "ivversion.h"
  10. #include "canmsg.pb.h"
  11. #include "decition.pb.h"
  12. #include "chassis.pb.h"
  13. #include "torquebrake.h"
  14. #include <thread>
  15. #ifdef Q_OS_LINUX
  16. #include <signal.h>
  17. #endif
  18. static void * gpacansend;
  19. static void * gpadecition;
  20. static void * gpachassis;
  21. static std::string gstrmemdecition;
  22. static std::string gstrmemcansend;
  23. static std::string gstrmemchassis;
  24. static bool gbSendRun = true;
  25. static bool gbChassisEPS = false;
  26. static iv::brain::decition gdecition_def;
  27. static iv::brain::decition gdecition;
  28. static QTime gTime;
  29. static int gnLastSendTime = 0;
  30. static int gnLastRecvDecTime = -1000;
  31. static int gnDecitionNum = 0; //when is zero,send default;
  32. const int gnDecitionNumMax = 100;
  33. static int gnIndex = 0;
  34. static bool gbHaveVehSpd = false;
  35. static double gfVehSpd = 0.0;
  36. static bool gbHaveWheelAngle = false;
  37. static double gfWheelAngle = 0.0;
  38. static double gfWheelSpeedLim = 300; //300 degrees per second
  39. static boost::shared_ptr<iv::control::Controller> gcontroller; //实际车辆控制器
  40. static QMutex gMutex;
  41. static std::thread * gpsendthread = NULL;
  42. // signal: @ACC_LatAngReq //更改CANid
  43. #define ECU_1C4_ACC_LatAngReq_CovFactor (0.1)
  44. // conversion value to CAN signal
  45. #define ECU_1C4_ACC_LatAngReq_toS(x) ((int16_t)((x) / 0.1 + 7200))
  46. // signal: @ACC_MotorTorqueMaxLimitRequest
  47. #define ECU_1C4_ACC_MotorTorqueMaxLimitRequest_CovFactor (0.02)
  48. // conversion value to CAN signal
  49. #define ECU_1C4_ACC_MotorTorqueMaxLimitRequest_toS(x) ((int16_t)((x) / 0.02 + 1024))
  50. // signal: @ACC_MotorTorqueMinLimitRequest
  51. #define ECU_1C4_ACC_MotorTorqueMinLimitRequest_CovFactor (0.02)
  52. // conversion value to CAN signal
  53. #define ECU_1C4_ACC_MotorTorqueMinLimitRequest_toS(x) ((int16_t)((x) / 0.02 + 1024))
  54. typedef struct
  55. {
  56. int16_t ACC_LatAngReq;
  57. //uint8_t ADS_Reqmode; //20221102, 新车没有此信号
  58. int16_t ACC_MotorTorqueMaxLimitRequest;
  59. uint8_t ACC_LatAngReqActive;
  60. int16_t ACC_MotorTorqueMinLimitRequest;
  61. //uint8_t ACC_ADCReqType; //20221102, 新车没有此信号
  62. } ECU_1C4_t;
  63. // signal: @ACC_AccTrqReq
  64. #define ECU_24E_ACC_AccTrqReq_CovFactor (1)
  65. // conversion value to CAN signal
  66. #define ECU_24E_ACC_AccTrqReq_toS(x) ((int16_t)((x) + 16384))
  67. // signal: @ACC_ACCTargetAcceleration
  68. #define ECU_24E_ACC_ACCTargetAcceleration_CovFactor (0.05)
  69. // conversion value to CAN signal
  70. #define ECU_24E_ACC_ACCTargetAcceleration_toS(x) ((int16_t)((x) / 0.05 + 100))
  71. // signal: @ACC_AEBTargetDeceleration
  72. #define ECU_24E_ACC_AEBTargetDeceleration_CovFactor (0.0005)
  73. // conversion value to CAN signal
  74. #define ECU_24E_ACC_AEBTargetDeceleration_toS(x) ((int32_t)((x) / 0.0005 + 32000))
  75. static int gnState = 0; //0 not act 1 act
  76. typedef struct
  77. {
  78. int16_t ACC_AccTrqReq;
  79. uint8_t ACC_AccTrqReqActive;
  80. int16_t ACC_ACCTargetAcceleration;
  81. int32_t ACC_AEBTargetDeceleration;
  82. uint8_t ACC_AEBVehilceHoldReq;
  83. uint8_t ADCReqMode;
  84. uint8_t ACC_AEBActive;
  85. uint8_t ACC_Driveoff_Request;
  86. uint8_t ACC_DecToStop;
  87. uint8_t ACC_CDDActive;
  88. uint8_t ACC_ACCMode;
  89. } ECU_24E_t;
  90. typedef struct
  91. {
  92. uint8_t CdcDoor;
  93. uint8_t res1;
  94. uint8_t res2;
  95. uint8_t ADS_UDLCTurnLightReq;
  96. } ECU_25E_t; //zhuanxiangdeng IDgenghuan
  97. unsigned char byte_1C4[64];//byte_144[8];
  98. unsigned char byte_24E[64];
  99. unsigned char byte_25E[32];
  100. ECU_1C4_t _m1C4 = {0,0,0,0};
  101. ECU_24E_t _m24E = {0,0,0,0,0,0,0,0,0,0,0};
  102. ECU_25E_t _m25E = {0,0,0,0};
  103. void ExecSend();
  104. void executeDecition(const iv::brain::decition &decition)
  105. {
  106. static int xieya = 50;
  107. // std::cout<<"acc is "<<decition.torque()<<" ang is "<<decition.wheelangle()<<std::endl;
  108. // std::cout<<"angle_mode is "<<decition.angle_mode()<<" angle_active is "<<decition.angle_active()<<std::endl;
  109. // std::cout<<"brake_type is "<<decition.brake_type()<<" acc_active is "<<decition.acc_active()<<std::endl;
  110. // std::cout<<"brake is "<<decition.brake()<<" brake_active is "<<decition.brake_active()<<std::endl;
  111. // std::cout<<"auto_mode is "<<decition.auto_mode()<<" rightlamp is "<<decition.rightlamp()<<std::endl;
  112. double fWheelAngleReq = decition.wheelangle();
  113. double fsendinter = 0.02;
  114. // if(fabs(fWheelAngleReq - gfWheelAngle)/fsendinter > gfWheelSpeedLim)
  115. // {
  116. // if(fWheelAngleReq > gfWheelAngle)
  117. // {
  118. // fWheelAngleReq = gfWheelAngle + fsendinter * gfWheelSpeedLim;
  119. // }
  120. // else
  121. // {
  122. // fWheelAngleReq = gfWheelAngle - fsendinter * gfWheelSpeedLim;
  123. // }
  124. // }
  125. // std::cout<<" wheel req: "<<decition.wheelangle()<<" real send : "<<fWheelAngleReq<<" real whhel:"<<gfWheelAngle<< std::endl;
  126. _m1C4.ACC_LatAngReq = ECU_1C4_ACC_LatAngReq_toS(fWheelAngleReq);
  127. //_m1C4.ADS_Reqmode = decition.angle_mode(); //20221102,新车没有此信号
  128. _m1C4.ACC_MotorTorqueMaxLimitRequest = ECU_1C4_ACC_MotorTorqueMaxLimitRequest_toS(10);
  129. _m1C4.ACC_LatAngReqActive = decition.angle_active();
  130. _m1C4.ACC_MotorTorqueMinLimitRequest = ECU_1C4_ACC_MotorTorqueMinLimitRequest_toS(-10);
  131. // _m144.ACC_ADCReqType = decition.brake_type();//ADC请求类型(制动时为1,其余情况为0)
  132. if(decition.brake()>(-0.0000001))
  133. {
  134. //_m144.ACC_ADCReqType = 0;//ADC请求类型(制动时为1,其余情况为0)//20221102,新车没有此信号
  135. // _m24B.ADCReqMode = 0;//20221102,新车没有此信号
  136. _m24E.ACC_DecToStop =0;
  137. }
  138. else
  139. {
  140. //_m144.ACC_ADCReqType = 1;//20221102,新车没有此信号
  141. // _m24B.ADCReqMode = 1;//20221102,新车没有此信号
  142. _m24E.ACC_DecToStop =1;
  143. }
  144. // std::cout<<" type: "<<(int)_m144.ACC_ADCReqType<<std::endl;
  145. /*制动过程用的减速度,加速用扭矩*/
  146. _m24E.ACC_AccTrqReq = ECU_24E_ACC_AccTrqReq_toS(decition.torque());
  147. _m24E.ACC_AccTrqReqActive = decition.acc_active();
  148. if(decition.brake()<(-1.5))
  149. {
  150. _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(-1.5);
  151. }
  152. else
  153. _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(decition.brake());
  154. // std::cout<<" brake : "<<decition.brake()<<std::endl;
  155. // std::cout<<"brake acctive. "<<decition.brake_active()<<std::endl;
  156. if(decition.brake()>(-0.0000001))
  157. {
  158. if(xieya > 0)
  159. {
  160. _m24E.ACC_CDDActive = 1;
  161. _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0.5);
  162. _m24E.ACC_AccTrqReq = ECU_24E_ACC_AccTrqReq_toS(0);
  163. _m24E.ACC_Driveoff_Request = 1;
  164. //_m144.ACC_ADCReqType = 1;//20221102,新车没有此信号
  165. //_m24B.ADCReqMode = 1; //20221102,新车没有此信号
  166. _m24E.ACC_DecToStop =1;
  167. xieya--;
  168. std::cout<<" xieya. now veh speed: "<<gfVehSpd<<std::endl;
  169. }
  170. else
  171. {
  172. _m24E.ACC_CDDActive = 0;
  173. _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0);
  174. _m24E.ACC_Driveoff_Request = 0;
  175. }
  176. }
  177. else
  178. {
  179. _m24E.ACC_CDDActive = 1;
  180. _m24E.ACC_Driveoff_Request = 0;
  181. }
  182. // _m24B.ACC_CDDActive = decition.brake_active();
  183. // std::cout<<" req mode: "<<_m144.ADS_Reqmode<<std::endl;
  184. //byte_144[0] = ((_m144.ACC_LatAngReq >> 9) & (0x1FU)) | ((_m144.ADS_Reqmode & (0x07U)) << 5);
  185. // qDebug(" req mode: %d byte: %02X ",_m144.ADS_Reqmode, byte_144[0]);
  186. // byte_144[1] = ((_m144.ACC_LatAngReq >> 1) & (0xFFU));
  187. //byte_144[2] = ((_m144.ACC_LatAngReq & (0x01U)) << 7) | ((_m144.ACC_MotorTorqueMaxLimitRequest >> 5) & (0x3FU)) | ((_m144.ACC_LatAngReqActive & (0x01U)) << 6);
  188. //byte_144[3] = ((_m144.ACC_MotorTorqueMaxLimitRequest & (0x1FU)) << 3) | ((_m144.ACC_MotorTorqueMinLimitRequest >> 8) & (0x07U));
  189. //byte_144[4] = (_m144.ACC_MotorTorqueMinLimitRequest & (0xFFU));
  190. //byte_144[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
  191. byte_1C4[0] = ((_m1C4.ACC_MotorTorqueMaxLimitRequest >> 3) & (0xFFU));
  192. // qDebug(" req mode: %d byte: %02X ",_m144.ADS_Reqmode, byte_144[0]);
  193. byte_1C4[1] = ((_m1C4.ACC_MotorTorqueMaxLimitRequest & (0x07U)) << 5) | ((_m1C4.ACC_MotorTorqueMinLimitRequest >> 6) & (0x1FU));
  194. byte_1C4[2] = ((_m1C4.ACC_MotorTorqueMinLimitRequest & (0x3FU)) << 2) | ((_m1C4.ACC_LatAngReq >> 12) & (0x03U));
  195. byte_1C4[3] = (((_m1C4.ACC_LatAngReq>>4 )& (0xFFU)));
  196. // byte_1C4[4] = (((_m1C4.ACC_LatAngReq<<4) & (0xF0U)))|((_m1C4.ACC_LatAngReqActive&(0x01U))<<3);
  197. byte_1C4[4] = (((_m1C4.ACC_LatAngReq)& (0x0fU))<<4)|((_m1C4.ACC_LatAngReqActive&(0x01U))<<3);
  198. //byte_1C4[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
  199. // _m24B.ACC_AEBTargetDeceleration = 0;
  200. // _m24B.ACC_AEBVehilceHoldReq = 0;
  201. // _m24B.ADCReqMode = 0;
  202. // _m24B.ACC_AEBActive = 0;
  203. // _m24B.ACC_Driveoff_Request = 0;
  204. // _m24B.ACC_DecToStop = 0;
  205. // std::cout<<" brake : "<<decition.brake()<<std::endl;
  206. // std::cout<<"brake acctive. "<<decition.brake_active()<<std::endl;
  207. if(decition.brake()>(-0.0000001))
  208. {
  209. _m24E.ACC_CDDActive = 0;
  210. _m24E.ACC_Driveoff_Request = 1;
  211. if(xieya > 0)
  212. {
  213. _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0.5);
  214. xieya--;
  215. }
  216. else
  217. {
  218. _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0);
  219. }
  220. _m24E.ACC_AccTrqReqActive = 1;
  221. _m24E.ACC_DecToStop = 0;
  222. }
  223. else
  224. {
  225. _m24E.ACC_CDDActive = 1;
  226. _m24E.ACC_Driveoff_Request = 0;
  227. if(gbHaveVehSpd)
  228. {
  229. if(gfVehSpd < 0.01)
  230. {
  231. if(xieya != 50)std::cout<<"need xieya. "<<std::endl;
  232. xieya = 50;
  233. }
  234. }
  235. _m24E.ACC_AccTrqReqActive = 0;
  236. _m24E.ACC_DecToStop = 1;
  237. }
  238. // _m24B.ACC_CDDActive = decition.brake_active();
  239. _m24E.ACC_ACCMode = decition.auto_mode();
  240. if(gnState == 0)
  241. {
  242. _m24E.ACC_CDDActive = 0;
  243. _m24E.ACC_Driveoff_Request = 0;
  244. _m24E.ACC_ACCMode = 0;
  245. _m24E.ACC_ACCTargetAcceleration = 0;
  246. _m24E.ACC_AccTrqReqActive = 0;
  247. _m24E.ACC_DecToStop = 0;
  248. }
  249. // std::cout<<"acc mode: "<<(int)_m24B.ACC_ACCMode<<std::endl;
  250. // byte_24B[0] = ((_m24B.ACC_AccTrqReq >> 7) & (0xFFU));
  251. //byte_24B[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
  252. //byte_24B[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
  253. //byte_24B[3] = ((_m24B.ACC_ACCTargetAcceleration & (0x07U)) << 5) | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
  254. //byte_24B[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
  255. //byte_24B[5] = ((_m24B.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24B.ACC_AEBVehilceHoldReq & (0x01U));
  256. //byte_24B[6] = ((_m24B.ADCReqMode & (0x03U)) << 1) | ((_m24B.ACC_AEBActive & (0x01U)) << 3) | ((_m24B.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24B.ACC_DecToStop & (0x01U)) << 6) | ((_m24B.ACC_CDDActive & (0x01U)) << 7);
  257. //byte_24B[7] = (_m24B.ACC_ACCMode & (0x07U));
  258. byte_24E[0] = ((_m24E.ACC_ACCTargetAcceleration) & (0xFFU));
  259. //byte_24E[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
  260. //byte_24E[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
  261. byte_24E[3] = ((_m24E.ACC_DecToStop & (0x01U)) << 7);// | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
  262. //byte_24E[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
  263. byte_24E[5] = ((_m24E.ACC_CDDActive & (0x01U)) << 4);//((_m24E.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24E.ACC_AEBVehilceHoldReq & (0x01U));
  264. byte_24E[6] = ((_m24E.ACC_Driveoff_Request & (0x01U)) << 7)|((_m24E.ACC_ACCMode & (0x07U))<<4);//((_m24E.ADCReqMode & (0x03U)) << 1) | ((_m24E.ACC_AEBActive & (0x01U)) << 3) | ((_m24E.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24E.ACC_DecToStop & (0x01U)) << 6) | ((_m24E.ACC_CDDActive & (0x01U)) << 7);
  265. byte_24E[8] = ((_m24E.ACC_AEBTargetDeceleration>>8) & (0xFFU));
  266. byte_24E[9] = ((_m24E.ACC_AEBTargetDeceleration) & (0xFFU));
  267. byte_24E[10] = ((_m24E.ACC_AEBActive & (0x01U)) << 7);
  268. byte_24E[11] = ((_m24E.ACC_AccTrqReq>>13 )& (0x03U));
  269. byte_24E[12] = ((_m24E.ACC_AccTrqReq>>5 )& (0xFFU));
  270. //byte_24E[13] = ((_m24E.ACC_AccTrqReq & (0x1FU)<<3))| ((_m24E.ACC_AccTrqReqActive & (0x01U)) << 2);
  271. byte_24E[13] = (((_m24E.ACC_AccTrqReq & (0x1FU))<<3))| ((_m24E.ACC_AccTrqReqActive & (0x01U)) << 2);
  272. if(decition.leftlamp() == true && decition.rightlamp() == false)
  273. _m25E.ADS_UDLCTurnLightReq = 3;
  274. else if(decition.leftlamp() == false && decition.rightlamp() == true)
  275. _m25E.ADS_UDLCTurnLightReq = 4;
  276. else
  277. _m25E.ADS_UDLCTurnLightReq = 0;
  278. byte_25E[3] = ((_m25E.ADS_UDLCTurnLightReq & (0x07U)));
  279. }
  280. void Activate()
  281. {
  282. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  283. iv::brain::decition xdecition;
  284. // for(int j=0;j<100000;j++)
  285. // {
  286. std::cout<<" run "<<std::endl;
  287. for(int i = 0; i < 3; i++){
  288. xdecition.set_wheelangle(0.0);
  289. xdecition.set_angle_mode(0);
  290. xdecition.set_angle_active(0);
  291. xdecition.set_acc_active(0);
  292. xdecition.set_brake_active(0);
  293. // xdecition.set_brake_type(0);
  294. xdecition.set_auto_mode(0);
  295. gnState = 0;
  296. executeDecition(xdecition);
  297. ExecSend();
  298. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  299. }
  300. for(int i = 0; i < 3; i++){
  301. xdecition.set_wheelangle(0.0);
  302. xdecition.set_angle_mode(1);
  303. xdecition.set_angle_active(1);
  304. xdecition.set_acc_active(1);
  305. xdecition.set_brake_active(1);
  306. // xdecition.set_brake_type(1);
  307. xdecition.set_auto_mode(3);
  308. gnState = 1;
  309. executeDecition(xdecition);
  310. ExecSend();
  311. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  312. }
  313. // }
  314. }
  315. void UnAcitvate()
  316. {
  317. iv::brain::decition xdecition;
  318. for(int i = 0; i < 3; i++){
  319. xdecition.set_wheelangle(0);
  320. xdecition.set_angle_mode(1);
  321. xdecition.set_angle_active(1);
  322. xdecition.set_acc_active(1);
  323. xdecition.set_brake_active(1);
  324. // xdecition.set_brake_type(1);
  325. xdecition.set_auto_mode(3);
  326. gnState = 1;
  327. executeDecition(xdecition);
  328. ExecSend();
  329. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  330. }
  331. for(int i = 0; i < 3; i++){
  332. xdecition.set_wheelangle(0);
  333. xdecition.set_angle_mode(0);
  334. xdecition.set_angle_active(0);
  335. xdecition.set_acc_active(0);
  336. xdecition.set_brake_active(0);
  337. // xdecition.set_brake_type(0);
  338. gnState = 0;
  339. xdecition.set_auto_mode(0);
  340. executeDecition(xdecition);
  341. ExecSend();
  342. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  343. }
  344. }
  345. void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
  346. {
  347. (void)index;
  348. (void)dt;
  349. (void)strmemname;
  350. iv::chassis xchassis;
  351. // static int ncount = 0;
  352. if(!xchassis.ParseFromArray(strdata,nSize))
  353. {
  354. std::cout<<"iv::decition::BrainDecition::UpdateChassis ParseFrom Array Error."<<std::endl;
  355. return;
  356. }
  357. if(xchassis.has_epsmode())
  358. {
  359. if(xchassis.epsmode() == 0)
  360. {
  361. gbChassisEPS = true;
  362. }
  363. }
  364. if(xchassis.has_vel())
  365. {
  366. gfVehSpd = xchassis.vel();
  367. gbHaveVehSpd = true;
  368. // std::cout<<" gf Veh speed : "<<gfVehSpd<<std::endl;
  369. }
  370. if(xchassis.has_angle_feedback())
  371. {
  372. gfWheelAngle = xchassis.angle_feedback();
  373. gbHaveWheelAngle = true;
  374. }
  375. }
  376. void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  377. {
  378. (void)index;
  379. (void)dt;
  380. (void)strmemname;
  381. static qint64 oldtime = QDateTime::currentMSecsSinceEpoch();
  382. iv::brain::decition xdecition;
  383. if(!xdecition.ParseFromArray(strdata,nSize))
  384. {
  385. std::cout<<"ListenDecition parse error."<<std::endl;
  386. return;
  387. }
  388. // if(xdecition.gear() != 4)
  389. // {
  390. // qDebug("not D");
  391. // }
  392. xdecition.set_angle_mode(1);
  393. xdecition.set_angle_active(1);
  394. xdecition.set_acc_active(1);
  395. xdecition.set_brake_active(1);
  396. // xdecition.set_brake_type(1);
  397. xdecition.set_auto_mode(3);
  398. // xdecition.set_wheelangle(45.0);
  399. if((oldtime - QDateTime::currentMSecsSinceEpoch())<-100)qDebug("dection time is %lld diff is %lld ",QDateTime::currentMSecsSinceEpoch(),oldtime - QDateTime::currentMSecsSinceEpoch());
  400. oldtime = QDateTime::currentMSecsSinceEpoch();
  401. gMutex.lock();
  402. gdecition.CopyFrom(xdecition);
  403. gMutex.unlock();
  404. gnDecitionNum = gnDecitionNumMax;
  405. gbChassisEPS = false;
  406. }
  407. void ExecSend()
  408. {
  409. static int nCount = 0;
  410. nCount++;
  411. iv::can::canmsg xmsg;
  412. iv::can::canraw xraw;
  413. // unsigned char * strp = (unsigned char *)&(ServiceControlStatus.command10.byte[0]);
  414. // 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]);
  415. xraw.set_id(0x1C4);
  416. xraw.set_data(byte_1C4,32);
  417. xraw.set_bext(false);
  418. xraw.set_bremote(false);
  419. xraw.set_len(32);
  420. iv::can::canraw * pxraw1C4 = xmsg.add_rawmsg();
  421. pxraw1C4->CopyFrom(xraw);
  422. // qDebug(" 0x144: %02X %02X %02X %02X %02X %02X %02X %02X",byte_144[0],byte_144[1],byte_144[2],byte_144[3],
  423. // byte_144[4],byte_144[5],byte_144[6],byte_144[7]);
  424. xmsg.set_channel(0);
  425. xmsg.set_index(gnIndex);
  426. xraw.set_id(0x24E);
  427. xraw.set_data(byte_24E,64);
  428. xraw.set_bext(false);
  429. xraw.set_bremote(false);
  430. xraw.set_len(64);
  431. if(nCount%2 == 1)
  432. {
  433. iv::can::canraw * pxraw24E = xmsg.add_rawmsg();
  434. pxraw24E->CopyFrom(xraw);
  435. }
  436. xmsg.set_channel(0);
  437. xmsg.set_index(gnIndex);
  438. xraw.set_id(0x25E);
  439. xraw.set_data(byte_25E,32);
  440. xraw.set_bext(false);
  441. xraw.set_bremote(false);
  442. xraw.set_len(32);
  443. if(nCount == 10)
  444. {
  445. iv::can::canraw * pxraw25E = xmsg.add_rawmsg();
  446. pxraw25E->CopyFrom(xraw);
  447. nCount = 0;
  448. }
  449. xmsg.set_channel(0);
  450. xmsg.set_index(gnIndex);
  451. gnIndex++;
  452. xmsg.set_mstime(QDateTime::currentMSecsSinceEpoch());
  453. int ndatasize = xmsg.ByteSize();
  454. char * strser = new char[ndatasize];
  455. std::shared_ptr<char> pstrser;
  456. pstrser.reset(strser);
  457. if(xmsg.SerializeToArray(strser,ndatasize))
  458. {
  459. iv::modulecomm::ModuleSendMsg(gpacansend,strser,ndatasize);
  460. }
  461. else
  462. {
  463. std::cout<<"MainWindow::onTimer serialize error."<<std::endl;
  464. }
  465. }
  466. void initial()
  467. {
  468. for (uint8_t i = 0; i < 64; i++) //CAN to canfd
  469. {
  470. byte_1C4[i] = 0;
  471. byte_24E[i] = 0;
  472. //byte_36E[i] = 0;
  473. }
  474. }
  475. void sendthread()
  476. {
  477. initial();
  478. iv::brain::decition xdecition;
  479. UnAcitvate();
  480. // UnAcitvate();
  481. int nstate = 0; //0 Un 1 Activate
  482. // Activate();
  483. while(gbSendRun)
  484. {
  485. if(gnDecitionNum <= 0)
  486. {
  487. if(nstate == 1)
  488. {
  489. UnAcitvate();
  490. nstate = 0;
  491. }
  492. xdecition.CopyFrom(gdecition_def);
  493. }
  494. else
  495. {
  496. if(nstate == 0)
  497. {
  498. Activate();
  499. nstate = 1;
  500. }
  501. gMutex.lock();
  502. xdecition.CopyFrom(gdecition);
  503. gMutex.unlock();
  504. gnDecitionNum--;
  505. }
  506. #ifdef TORQUEBRAKETEST
  507. if(gnothavetb < 10)
  508. {
  509. iv::controller::torquebrake xtb;
  510. gMutextb.lock();
  511. xtb.CopyFrom(gtb);
  512. gMutextb.unlock();
  513. if(xtb.enable())
  514. {
  515. xdecition.set_torque(xtb.torque());
  516. xdecition.set_brake(xtb.brake());
  517. std::cout<<" use xtb. torque: "<<xtb.torque()<<" brake: "<<xtb.brake()<<std::endl;
  518. // gcontroller->control_torque(xtb.torque());
  519. // gcontroller->control_brake(xtb.brake());
  520. // qDebug("use tb value torque is %f brake is %f",xtb.torque(),xtb.brake());
  521. }
  522. else
  523. {
  524. // qDebug("torquebrake not enable.");
  525. }
  526. gnothavetb++;
  527. }
  528. #endif
  529. executeDecition(xdecition);
  530. if(gbChassisEPS == false) ExecSend();
  531. std::this_thread::sleep_for(std::chrono::milliseconds(10));
  532. }
  533. UnAcitvate();
  534. }
  535. #ifdef Q_OS_LINUX
  536. void sig_int(int signo)
  537. {
  538. gbSendRun = false;
  539. gpsendthread->join();
  540. iv::modulecomm::Unregister(gpacansend);
  541. iv::modulecomm::Unregister(gpachassis);
  542. iv::modulecomm::Unregister(gpadecition);
  543. std::cout<<" controller exit."<<std::endl;
  544. exit(0);
  545. }
  546. #endif
  547. int main(int argc, char *argv[])
  548. {
  549. RegisterIVBackTrace();
  550. showversion("controller_changan_shenlan");
  551. QCoreApplication a(argc, argv);
  552. QString strpath = QCoreApplication::applicationDirPath();
  553. if(argc < 2)
  554. strpath = strpath + "/controller_changan_shenlan.xml";
  555. else
  556. strpath = argv[1];
  557. std::cout<<strpath.toStdString()<<std::endl;
  558. // gdecition_def.set_accelerator(-0.5);
  559. gdecition_def.set_brake(0);
  560. gdecition_def.set_rightlamp(false);
  561. gdecition_def.set_leftlamp(false);
  562. gdecition_def.set_wheelangle(0);
  563. gdecition_def.set_angle_mode(0);
  564. gdecition_def.set_angle_active(0);
  565. gdecition_def.set_acc_active(0);
  566. // gdecition_def.set_brake_active(1);
  567. gdecition_def.set_brake_type(0);
  568. gdecition_def.set_auto_mode(0);
  569. // gdecition_def.set_angle_mode(0);
  570. // gdecition_def.set_angle_active(0);
  571. // gdecition_def.set_acc_active(0);
  572. // gdecition_def.set_brake_active(0);
  573. // gdecition_def.set_brake_type(0);
  574. // gdecition_def.set_auto_mode(0);
  575. gTime.start();
  576. gcontroller = boost::shared_ptr<iv::control::Controller>(new iv::control::Controller());
  577. iv::xmlparam::Xmlparam xp(strpath.toStdString());
  578. gstrmemcansend = xp.GetParam("cansend","cansend0");
  579. gstrmemdecition = xp.GetParam("dection","deciton");
  580. gstrmemchassis = xp.GetParam("chassismsgname","chassis");
  581. gpacansend = iv::modulecomm::RegisterSend(gstrmemcansend.data(),10000,1);
  582. gpadecition = iv::modulecomm::RegisterRecv(gstrmemdecition.data(),ListenDeciton);
  583. gpachassis = iv::modulecomm::RegisterRecv(gstrmemchassis.data(),UpdateChassis);
  584. #ifdef TORQUEBRAKETEST
  585. EnableTorqueBrakeTest();
  586. #endif
  587. std::thread xthread(sendthread);
  588. gpsendthread = &xthread;
  589. #ifdef Q_OS_LINUX
  590. signal(SIGINT, sig_int);
  591. signal(SIGTERM,sig_int);
  592. #endif
  593. return a.exec();
  594. }