can_bus.cpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459
  1. #include "can_bus.h"
  2. #include <thread>
  3. #include "message_queue.h"
  4. #include <math.h>
  5. #define GET_BIT(x, bit) ((x & (1 << bit)) >> bit)
  6. float Canb2f(uint8_t m0, uint8_t m1, uint8_t m2, uint8_t m3)
  7. {
  8. //求符号位
  9. float sig = 1.;
  10. if (m0 >=128.)
  11. sig = -1.;
  12. //求阶码
  13. float jie = 0.;
  14. if (m0 >=128.)
  15. {
  16. jie = m0-128. ;
  17. }
  18. else
  19. {
  20. jie = m0;
  21. }
  22. jie = jie * 2.;
  23. if (m1 >=128.)
  24. jie += 1.;
  25. jie -= 127.;
  26. //求尾码
  27. float tail = 0.;
  28. if (m1 >=128.)
  29. m1 -= 128.;
  30. tail = m3 + (m2 + m1 * 256.) * 256.;
  31. tail = (tail)/8388608; // 8388608 = 2^23
  32. float f = sig * pow(2., jie) * (1+tail);
  33. return f;
  34. }
  35. int hex_to_decimal(const char* hex_str) {
  36. int decimal = 0;
  37. int len = strlen(hex_str);
  38. for (int i = 0; i < len; i++) {
  39. char c = toupper(hex_str[i]);
  40. if (c >= '0' && c <= '9') {
  41. decimal = decimal * 16 + (c - '0');
  42. } else if (c >= 'A' && c <= 'F') {
  43. decimal = decimal * 16 + (c - 'A' + 10);
  44. } else {
  45. return -1; // 输入的字符串含有非十六进制字符
  46. }
  47. }
  48. return decimal;
  49. }
  50. int16_t make_int16(unsigned char h,unsigned char l)
  51. {
  52. int16_t hi=(int16_t)(h&0x00FF);
  53. int16_t low= (int16_t)(l&0x00FF);
  54. return (hi<<8)|low;
  55. }
  56. CCanBusSensor::CCanBusSensor(CMessageQueue* q) :_message(q)
  57. {
  58. _run = false;
  59. for (int32_t i = 0; i < sizeof(Sendframe)/sizeof(can_frame); i++)
  60. memset(&Sendframe[i], 0, sizeof(can_frame));
  61. }
  62. void CCanBusSensor::SetCanBusSensor(SensorCanBus<CCanBusSensor>* can)
  63. {
  64. _canbus = can;
  65. }
  66. void CCanBusSensor::CanSendProc()
  67. {
  68. while (_run)
  69. {
  70. for(int32_t i=0;i<sizeof(Sendframe)/sizeof(can_frame);i++)
  71. {
  72. if(Sendframe[i].can_id != 0)
  73. {
  74. // //接收到的frame
  75. // for (int i = 0; i < Sendframe[i]->can_dlc; i++) {
  76. // printf("%02x ", Sendframe[i]->data[i]);
  77. // }
  78. // printf("\n");
  79. if(Sendframe[i].can_id == 0x184)
  80. {
  81. _message->_dst = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  82. //printf("data delay:%lld\r\n",_message->_dst - _message->_source);
  83. }
  84. _canbus->Write(&Sendframe[i]);
  85. Sendframe[i].can_id = 0;
  86. }
  87. }
  88. std::this_thread::sleep_for(std::chrono::milliseconds(5));
  89. }
  90. }
  91. void CCanBusSensor::Start()
  92. {
  93. _run = true;
  94. _can_thread = std::thread(&CCanBusSensor::CanSendProc, this);
  95. Direction = 0;//方向
  96. Hand_Throttle = 0;//手油门
  97. Foot_Throttle = 0;//脚油门
  98. Brake = 0;//刹车
  99. _message->DataMqtt_SendDate = false;
  100. _message->DataMqtt_curTick = 0;
  101. }
  102. void CCanBusSensor::Run()
  103. {
  104. }
  105. void CCanBusSensor::Stop()
  106. {
  107. if (_run)
  108. {
  109. _run = false;
  110. _can_thread.join();
  111. }
  112. for (int32_t i = 0; i < sizeof(Sendframe)/sizeof(can_frame); i++)
  113. memset(&Sendframe[i], 0, sizeof(can_frame));
  114. Direction = 0;//方向
  115. Hand_Throttle = 0;//手油门
  116. Foot_Throttle = 0;//脚油门
  117. Brake = 0;//刹车
  118. _message->DataMqtt_SendDate = false;
  119. _message->DataMqtt_curTick = 0;
  120. }
  121. //_data
  122. void CCanBusSensor::Notify(struct can_frame *date)
  123. {
  124. //std::cout << std::hex << date->can_id << std::endl;
  125. if(_run)
  126. {
  127. switch (date->can_id)
  128. {
  129. case 0x283:
  130. _data.Main_pump_1_pressure = make_int16(date->data[1],date->data[0]);//主泵1压力
  131. _data.Main_pump_2_pressure = make_int16(date->data[3],date->data[2]);//主泵2压力
  132. break;
  133. case 0x285:
  134. _data.Stick_angle = make_int16(date->data[1],date->data[0]);//斗杆角度
  135. _data.Boom_angle = make_int16(date->data[3],date->data[2]);//动臂角度
  136. break;
  137. case 0x286:
  138. _data.Hydraulic_oil_temperature = make_int16(date->data[1],date->data[0]);//液压油油温
  139. _data.Fuel_level = (int32_t)date->data[6];//燃油油位
  140. break;
  141. case 0x28A:
  142. _data.Travel_speed = make_int16(date->data[1],date->data[0]);//行驶速度
  143. _data.Engine_temperature = make_int16(date->data[3],date->data[2]);//发动机水温
  144. _data.Hand_gear = make_int16(date->data[5],date->data[4]);//水箱水位
  145. _data.Actual_gear = make_int16(date->data[7],date->data[6]);//发动机机油压力
  146. break;
  147. case 0x28B:
  148. _data.Engine_speed = make_int16(date->data[1],date->data[0]);//发动机转速
  149. {
  150. long long tick=std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  151. if(_data.Engine_speed > 700 && _message->bStopedCar && tick-_message->_curStopTick > 500)
  152. _message->bStopedCar = false;
  153. }
  154. _data.engine_fmi = (static_cast<uint16_t>(date->data[3]) << 8 | static_cast<uint16_t>(date->data[2]));
  155. _data.engine_spn = (static_cast<uint16_t>(date->data[5]) << 8 | static_cast<uint16_t>(date->data[4]));
  156. _data.engine_num = (static_cast<uint16_t>(date->data[7]) << 8 | static_cast<uint16_t>(date->data[6]));
  157. break;
  158. case 0x28D:
  159. _data.Gripper_height = Canb2f(date->data[3], date->data[2], date->data[1],
  160. date->data[0]);//抓具高度
  161. _data.amplitude = Canb2f(date->data[7], date->data[6], date->data[5],
  162. date->data[4]);//幅度
  163. break;
  164. case 0x28F:
  165. _data.Idle_protection = (date->data[3] & 0x80) == 0x80 ? 1 : 0;//怠速保护
  166. _data.Front_toggle = (date->data[1] & 0x08) == 0x08 ? 1 : 0;//前轮对中
  167. _data.Back_toggle = (date->data[1] & 0x10) == 0x10 ? 1 : 0;//后轮对中
  168. _data.interlock = (date->data[5] & 0x08) == 0x08 ? 1 : 0;//启动联锁
  169. _data.safety_switch = (date->data[6] & 0x80) == 0x80 ? 1 : 0;//安全开关阀异常
  170. _data.arm_lift_pilot = (date->data[7] & 0x01) == 0x01 ? 1 : 0;//大臂提升先导比例阀异常
  171. _data.arm_lowering_pilot = (date->data[7] & 0x02) == 0x02 ? 1 : 0;//大臂下降先导比例阀异常
  172. _data.lever_lifting_pilot = (date->data[7] & 0x04) == 0x04 ? 1 : 0;//斗杆提升先导比例阀异常
  173. _data.rod_lowering_pilot = (date->data[7] & 0x08) == 0x08 ? 1 : 0;//斗杆下降先导比例阀异常
  174. _data.left_rotary_pilot = (date->data[7] & 0x10) == 0x10 ? 1 : 0;//左回转先导比例阀异常cab_start
  175. _data.right_rotary_pilot = (date->data[7] & 0x20) == 0x20 ? 1 : 0;//右回转先导比例阀异常
  176. _data.grab_open_pilot = (date->data[7] & 0x40) == 0x40 ? 1 : 0;//抓斗开启先导比例阀异常
  177. _data.grab_close_pilot = (date->data[7] & 0x80) == 0x80 ? 1 : 0;//抓斗闭合先导比例阀异常
  178. _data.safety_valves = (date->data[4] & 0x10) == 0x10 ? 1 : 0;//安全开关阀
  179. //增加
  180. memcpy(_data.all_Buff,date->data,date->can_dlc);
  181. break;
  182. case 0x280:
  183. memcpy(_data.Error_Buff,date->data,date->can_dlc);
  184. SendStatusToMSG();;
  185. break;
  186. case 0x384:
  187. // _data.function_code= make_int16(date->data[1],date->data[0]) ;
  188. // _data.main_add = make_int16(date->data[3],date->data[2]);
  189. // _data.sub_add = make_int16(date->data[5],date->data[4]);
  190. // _data.paramter = make_int16(date->data[7],date->data[6]);
  191. _data.function_code = (static_cast<uint16_t>(date->data[0]) << 8 | static_cast<uint16_t>(date->data[1]));
  192. _data.main_add = (static_cast<uint16_t>(date->data[2]) << 8 | static_cast<uint16_t>(date->data[3]));
  193. _data.sub_add = (static_cast<uint16_t>(date->data[4]) << 8 | static_cast<uint16_t>(date->data[5]));
  194. _data.paramter = (static_cast<uint16_t>(date->data[6]) << 8 | static_cast<uint16_t>(date->data[7]));
  195. break;
  196. default:
  197. break;
  198. }
  199. }
  200. }
  201. //sendframe
  202. void CCanBusSensor::OnMessage(cannet_frame* frames, int32_t count)
  203. {
  204. // vehicle_status_t vehicle_status;
  205. for (int32_t i = 0; i < count; i++)
  206. {
  207. cannet_frame& frame = frames[i];
  208. int32_t canid = frame.canid;
  209. //std::cout << std::hex << canid << std::endl;
  210. switch (canid)
  211. {
  212. case 0x181:
  213. Sendframe[0].can_id = 0x181;
  214. Sendframe[0].can_dlc = frame.dlc;
  215. memcpy(Sendframe[0].data, frame.data, frame.dlc);
  216. control_can.accPedalH = make_int16(frame.data[1],frame.data[0]); //手油门
  217. control_can.accPedalF = make_int16(frame.data[3],frame.data[2]); //脚油门
  218. control_can.brakePedal = make_int16(frame.data[5],frame.data[4]); //刹车
  219. control_can.baseLegControl = make_int16(frame.data[7],frame.data[6]); //支腿动作控制
  220. //std::cout << "revice 181" << std::endl;
  221. break;
  222. case 0x182:
  223. Sendframe[1].can_id = 0x182;
  224. Sendframe[1].can_dlc = frame.dlc;
  225. memcpy(Sendframe[1].data, frame.data, frame.dlc);
  226. control_can.taskJoint_1 = make_int16(frame.data[1], frame.data[0]);//第一个作业关节控制
  227. control_can.taskJoint_2 = make_int16(frame.data[7], frame.data[6]);//第2个作业关节控制
  228. control_can.taskJoint_3 = make_int16(frame.data[3], frame.data[2]);//第3个作业关节控制
  229. control_can.toolControl = make_int16(frame.data[5],frame.data[4]); //末端控制工具
  230. //std::cout << "182" << std::endl;
  231. break;
  232. case 0x183:
  233. Sendframe[2].can_id = 0x183;
  234. Sendframe[2].can_dlc = frame.dlc;
  235. memcpy(Sendframe[2].data, frame.data, frame.dlc);
  236. control_can.steeringWheel = make_int16(frame.data[3],frame.data[2]); //方向盘转速
  237. control_can.endJoint = make_int16(frame.data[1],frame.data[0]); //抓具旋转
  238. break;
  239. case 0x184:
  240. Sendframe[3].can_id = 0x184;
  241. Sendframe[3].can_dlc = frame.dlc;
  242. control_can.keyStatus = (frame.data[3] & 0x01 ? 1:0 ) + (frame.data[2] & 0x80 ? 1:0)*2; //钥匙状态 0-熄火 1-上电 2-启动
  243. control_can.parkControl = frame.data[1] & 0x01 ? 1:0 ; //驻车控制 1-1
  244. control_can.travelMode = frame.data[3] & 0x04? 1:0 ; //驾驶模式 3-3
  245. control_can.eStop = frame.data[3] & 0x02 ? 1:0 ; //急停开关 3-2
  246. control_can.directSwitch = frame.data[4] & 0x04 ? 1:0 ; //前后切换 4-3
  247. control_can.gearControl = (frame.data[0] & 0x20 ? 1:0) + (frame.data[0] & 0x40 ? 1:0) * 2 ; //车辆档位控制 1-前进 2-后退
  248. control_can.hazardLight = frame.data[0] & 0x04 ? 1:0 ; //双闪灯0-3
  249. control_can.travelLight = (frame.data[0] & 0x02 ? 1:0) +(frame.data[0] & 0x01 ? 1:0)*2; //行驶灯光 0-全关闭 1-近光 2-远光
  250. control_can.vehicleHorn = frame.data[1] & 0x02 ? 1:0 ; //喇叭1-2
  251. control_can.silencedAlarm = frame.data[2] & 0x40 ? 1:0; //消报警音按钮2-7100000data[2] & 0x20 ? 1:0) *2 ; //2- 4*5 工作灯 0-全关闭 1-前大灯 2工作灯 3 全开
  252. control_can.turnSignal = (frame.data[0] & 0x08 ? 1:0) + (frame.data[0] & 0x10 ? 1:0) * 2 ; //转向灯 0-关 1-近光灯 2-远光灯
  253. control_can.turnMode = (frame.data[3] & 0x08 ? 1:0) + (frame.data[3] & 0x10 ? 1:0) * 2 + (frame.data[3] & 0x20 ? 1:0) * 3 +(frame.data[3] & 0x40 ? 1:0) * 4; //转向模式
  254. control_can.enableHydraulic = frame.data[2] & 0x01 ? 1:0; //液压使能开关
  255. control_can.workLight = (frame.data[2] & 0x20 ? 1:0) + (frame.data[2] & 0x40 ? 1:0)*2 ; //工作灯 0-关 1-前大灯 2-工作灯 3-全开
  256. control_can.bypassSwitch = frame.data[1] & 0x02 ? 1:0 ; //2- 1 旁通开关
  257. control_can.baseLegSwitch =(frame.data[1] & 0x04 ? 1:0)*1 +(frame.data[1] & 0x08 ? 1:0)*2 +(frame.data[1] & 0x10 ? 1:0)*4+(frame.data[1] & 0x20 ? 1:0)*8; //四个支腿选择开关
  258. control_can.cabLift = (frame.data[1] &0x40 ? 1:0) * 1 + (frame.data[1] & 0x80 ? 1:0) * 2; //驾驶室升降 0 无 1-升 2-降
  259. control_can.esCabLift = frame.data[2] & 0x08 ? 1:0; //驾驶室应急下降
  260. control_can.suckerSelect = frame.data[2] & 0x04 ? 1:0; //吸盘选择开关
  261. control_can.errBasOperation = 0; //基本操作故障
  262. control_can.errAccPedal = (frame.data[5] & 0x40 ? 1:0) + (frame.data[5] & 0x80 ? 1:0)*2; //油门信号故障 0-无故障 1-油门旋扭故障 2-脚油门故障 3-都有故障
  263. control_can.errBrakePedal = frame.data[6] & 0x01 ? 1:0; //刹车信号故障
  264. control_can.errSteeringWheel = frame.data[6] & 0x02 ? 1:0 ; //转向故障
  265. control_can.errHandle = (frame.data[5] & 0x01 ? 1:0) + (frame.data[5] & 0x02 ? 1:0)*2 +(frame.data[5] & 0x04 ? 1:0)*4 +( frame.data[5] & 0x08 ? 1:0) *8 +(frame.data[5] & 0x10 ? 1:0)*16 ; //手柄信号故障
  266. control_can.errEndTool = frame.data[5] & 0x20 ?1:0;//末端工具控制故障
  267. control_can.errOther = 0;//其他故障
  268. //模式
  269. model = (frame.data[3] & 0x04) == 0x04 ? 1 : 0;
  270. //切换前后摄像头
  271. _front_view = (frame.data[4] & 0x04) == 0x04 ? false: true;
  272. _message->SwitchCamera(_front_view);
  273. //b_ready = (_msg[3].DATA[4] & 0x10) == 0x10 ? 1 : 0;
  274. if((frame.data[4] & 0x10) == 0x10 ? 1 : 0)//已就绪 抓钢机就绪状态,待无人车入场
  275. {
  276. _message->SendZGJStatus(1);
  277. control_can.coopSignal = 1; //就位
  278. std::cout << "SendZGJStatus" << std::endl;
  279. //_msg[3].DATA[4] &= 0xEF;
  280. }
  281. if((frame.data[4] & 0x20) == 0x20 ? 1 : 0)//已完成 抓钢机抓钢结束,待无人车离场
  282. {
  283. _message->SendZGJStatus(2);
  284. control_can.coopSignal = 0; //结束
  285. //_msg[3].DATA[4] &= 0xD7;
  286. }
  287. if(!_message->btimeStopedCar)
  288. {
  289. memcpy(Sendframe[3].data, frame.data, frame.dlc);
  290. }
  291. else
  292. {
  293. long long tick=std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  294. /*
  295. if(tick-_message->_curStopTick > 500)
  296. {
  297. Emergency();
  298. _message->btimeStopedCar = false;
  299. }
  300. */
  301. if(tick-_message->_curStopTick < 500)
  302. Emergency();
  303. else
  304. _message->btimeStopedCar = false;
  305. }
  306. //_message->_dst = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  307. // printf("data delay:%ld\r\n",_message->_dst - _message->_source);
  308. //std::cout << "revice 184" << std::endl;
  309. // _message -> SendVehicleStatus( vehicle_status);
  310. break;
  311. case 0x185:
  312. Sendframe[4].can_id = 0x185;
  313. Sendframe[4].can_dlc = frame.dlc;
  314. memcpy(Sendframe[4].data, frame.data, frame.dlc);
  315. _message -> SendVehicleStatus( control_can);
  316. break;
  317. }
  318. }
  319. }
  320. void CCanBusSensor::SendStatusToMSG()
  321. {
  322. RemoNet::State req;
  323. req.set_engine_speed(_data.Engine_speed);
  324. req.set_travel_speed(_data.Travel_speed);
  325. req.set_fuel_level(_data.Fuel_level);
  326. req.set_engine_temperature(_data.Engine_temperature);
  327. req.set_hydraulic_oil_temperature(_data.Hydraulic_oil_temperature);
  328. req.set_main_pump_1_pressure(_data.Main_pump_1_pressure);
  329. req.set_main_pump_2_pressure(_data.Main_pump_2_pressure);
  330. req.set_hand_gear(_data.Hand_gear);
  331. req.set_actual_gear(_data.Actual_gear);
  332. req.set_gripper_height(_data.Gripper_height);
  333. req.set_amplitude(_data.amplitude);
  334. req.set_boom_angle(_data.Boom_angle);
  335. req.set_stick_angle(_data.Stick_angle);
  336. req.set_idle_protection(_data.Idle_protection);
  337. req.set_front_toggle(_data.Front_toggle);
  338. req.set_back_toggle(_data.Back_toggle);
  339. req.set_error_buff((char *)_data.Error_Buff,8);
  340. //增加
  341. req.set_function_code(_data.function_code);
  342. req.set_main_add(_data.main_add);
  343. req.set_sub_add(_data.sub_add);
  344. req.set_paramter(_data.paramter);
  345. //增加0x28b
  346. req.set_engine_spn(_data.engine_spn); //发动机实时故障SPN
  347. req.set_engine_fmi(_data.engine_fmi); //发动机实时故障FMI
  348. req.set_engine_num(_data.engine_num); //发动机故障次数
  349. //增加0X28F
  350. req.set_all_buff((char *)_data.all_Buff,8);
  351. MessageHead Head;
  352. CIOBuffer pBuffer;
  353. Head.Command = RemoNet::CC_STATE;
  354. Head.Length = req.ByteSizeLong();
  355. Head.Serialize(pBuffer.Buffer);
  356. auto ptr = pBuffer.Buffer + MessageHead::Size();
  357. req.SerializeToArray(ptr, Head.Length);
  358. pBuffer.Length = MessageHead::Size() + Head.Length;
  359. _message->WritePacket(ChannelType::CHANNEL_CAR, pBuffer);
  360. }
  361. void CCanBusSensor::Emergency()
  362. {
  363. if(model)
  364. {
  365. Sendframe[3].can_id = 0x184;
  366. Sendframe[3].can_dlc = 8;
  367. Sendframe[3].data[3] &= 0xFD;
  368. //_canbus->Write(&Sendframe[3]);
  369. }
  370. }