message_queue.cpp 35 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169
  1. #include <atomic>
  2. #include <string>
  3. #include "../common/comm.h"
  4. #include "api.h"
  5. #include "../common/iobuffer.h"
  6. #include "../common/sensor_socket.h"
  7. #include "../common/peer_connection.h"
  8. #include "VideoRenderer.h"
  9. #include "../thirdparty/jsoncpp/include/json/json.h"
  10. #include "protocol.pb.h"
  11. #include "imu_sensor.h"
  12. #include "Rtk.h"
  13. #include "message_queue.h"
  14. #include <fstream>
  15. #include <iostream>
  16. #include <cstring>
  17. #include "hmacsha256.h"
  18. #include <linux/usbdevice_fs.h>
  19. #include <sys/ioctl.h>
  20. #include <sys/statfs.h>
  21. #include <stdlib.h>
  22. #include <unistd.h>
  23. #include <sys/vfs.h>
  24. #include <dirent.h>
  25. #include <sys/stat.h>
  26. CMessageQueue::CMessageQueue():Head(nullptr),Tail(nullptr)
  27. {
  28. _peerId=-1;
  29. btimeStopedCar = false;
  30. File_fd = NULL;
  31. _Version = 1;
  32. }
  33. CMessageQueue::~CMessageQueue()
  34. {
  35. }
  36. void renableUSB(const char* file)
  37. {
  38. printf("Resetting USB device %s\n", file);
  39. int fd = open(file, O_WRONLY);
  40. if (fd < 0) {
  41. char text[256];
  42. perror(text);
  43. printf("Error opening output file %s", text);
  44. return;
  45. }
  46. int rc = ioctl(fd, USBDEVFS_RESET, 0);
  47. if (rc < 0) {
  48. perror("Error in ioctl");
  49. return;
  50. }
  51. printf("Reset successful\n");
  52. close(fd);
  53. }
  54. void CMessageQueue::Create()
  55. {
  56. Json::Value root;
  57. Json::Reader jsonReader;
  58. std::ifstream ifile("./config.json");
  59. std::string serverip;
  60. int32_t _hostPort;
  61. int32_t _remotePort;
  62. _curTick=0;
  63. bStopedCar=false;
  64. if(jsonReader.parse(ifile,root))
  65. {
  66. std::cout<<"enter config json"<<std::endl;
  67. _serial=root["serial"].asString();
  68. int32_t _Rtkport=root["rtk_port"].asInt();
  69. int32_t _Rtkhost=root["rtk_host"].asInt();
  70. std::string _Rtkip=root["rtk_ip"].asString();
  71. std::cout<<"Rtk ip:"<< _Rtkip <<std::endl;
  72. _Rtk = std::make_unique<SensorSocket<CRtkSensor>>(this, _Rtkip, _Rtkport, _Rtkhost);
  73. //_Rtk->Start();
  74. _Version = root["Version"].asInt();
  75. if(_Version)//AD10
  76. {
  77. std::string can_port_radar = root["can_bus_radar"].asString();
  78. _CanBusRadar = std::make_unique<SensorCanBus<CCanRadarSensor>>(this, can_port_radar);
  79. //_CanBusRadar->Start();
  80. }
  81. else
  82. {
  83. //_RadarIp
  84. int32_t _radarport=root["radar_port"].asInt();
  85. int32_t _radarhost=root["radar_host"].asInt();
  86. std::string _radarip=root["radar_ip"].asString();
  87. std::cout<<"radar ip:"<<_radarip<<std::endl;
  88. _RadarIp = std::make_unique<SensorSocket<CRadarSensor>>(this,_radarip,_radarport,_radarhost);
  89. //_RadarIp->Start();
  90. }
  91. if(_Version)//AD10
  92. {
  93. std::string can_port = root["can_bus_vehicle"].asString();
  94. _CanBusVehicle = std::make_unique<SensorCanBus<CCanBusSensor>>(this, can_port);
  95. //_CanBusVehicle->Start();
  96. }
  97. else
  98. {
  99. _PcanBusVehicle = std::make_unique<SensorPeakCan<CPcanSensor>>(this);
  100. //_PcanBusVehicle->Start();
  101. }
  102. _UdpMinPort=root["udp_min_port"].asInt();
  103. _UdpMaxPort=root["udp_max_port"].asInt();
  104. //20230417
  105. //const char* serverUrl = "tcp://localhost:1883"; //服务器地址
  106. //const char* userName = ""; //用户名
  107. //const char* password = ""; //密码
  108. std::string serverUrl = root["MqttserverUrl"].asString();
  109. std::string userName = root["Esn"].asString();
  110. std::string password = root["EsnPass"].asString();
  111. std::string clientId = ""; //客户端标识符
  112. bool _Hm256 = false;
  113. unsigned char Source[128];
  114. time_t rawtime;
  115. struct tm* info;
  116. char buffer[80];
  117. time(&rawtime);
  118. info = localtime(&rawtime);
  119. uint8_t secret[32] = { 0 };
  120. //如UTC 时间2018/7/24 17:56:20 则应表示为2018072417。
  121. /*sprintf((char*)secret, "%d%.2d%.2d%.2d", info->tm_year + 1900, info->tm_mon + 1, info->tm_mday,
  122. info->tm_hour);*/
  123. sprintf((char*)secret, "%d%.2d%.2d", info->tm_year + 1900, info->tm_mon + 1, info->tm_mday);
  124. memset(Source, 0, 128);
  125. sprintf((char*)Source, "%s_0_0_%s", userName.c_str(), secret);
  126. clientId.clear();
  127. clientId.append((const char*)Source);
  128. if (password.length() && _Hm256)
  129. {
  130. uint8_t outdata[128] = { 0 };
  131. uint8_t md[SHA256_DIGESTLEN] = { 0 };
  132. int len1 = strlen((char*)secret);
  133. int len2 = strlen((char*)password.c_str());
  134. HMAC_SHA256_CTX hmac;
  135. hmac_sha256_init(&hmac, secret, len1);
  136. hmac_sha256_update(&hmac, (const uint8_t*)password.c_str(), len2);
  137. hmac_sha256_final(&hmac, md);
  138. memcpy(outdata, md, SHA256_DIGESTLEN);
  139. password.clear();
  140. password.append((const char*)outdata);
  141. }
  142. _Mqtt_ZR = std::make_unique<SensorMQTT<CMqttSensor>>(this, serverUrl, userName, password, clientId);
  143. std::string DataServerUrl = root["DataServerUrl"].asString();
  144. std::string DatauserName = root["DataEsn"].asString();
  145. std::string Datapassword = root["DataEsnPass"].asString();
  146. std::string DataclientId = root["DataClientId"].asString();
  147. _Mqtt_SE = std::make_unique<SensorMQTT<CDataMqttSensor>>(this, DataServerUrl, DatauserName, Datapassword, DataclientId);
  148. //_Mqtt_SE->Start();
  149. //std::string _usb_1 = root["usb_3"].asString();
  150. //renableUSB("/dev/bus/usb/002/002");
  151. //renableUSB("/dev/bus/usb/001/003");
  152. //renableUSB(_usb_2.c_str());
  153. //renableUSB(_usb_1.c_str());
  154. serverip=root["ip"].asString();
  155. _hostPort=root["TcpHostPort"].asInt();
  156. _remotePort=root["TcpRemotePort"].asInt();
  157. _name=root["name"].asString();
  158. const Json::Value arrayObj=root["camerainfo"];
  159. int32_t count=arrayObj.size();
  160. for(int32_t i=0;i<count;i++)
  161. {
  162. LocalCameraInfo info;
  163. const Json::Value& value=arrayObj[i];
  164. info.index=value["index"].asInt();
  165. info.label=value["label"].asString();
  166. _cameraArray.push_back(info);
  167. }
  168. for(int i=0;i<_cameraArray.size();i++)
  169. {
  170. _peerArray.push_back({nullptr});
  171. }
  172. }
  173. else{
  174. std::string error=jsonReader.getFormattedErrorMessages();
  175. std::cout<<error<<std::endl;
  176. }
  177. _client=std::make_unique<SocketClient>(this);
  178. _client->Start(serverip.c_str(),_remotePort,_hostPort);
  179. //20230412
  180. //_Mqtt_ZR = std::make_unique<CMqtt>(this);
  181. //_Mqtt_ZR->start();
  182. //_can=std::make_unique<SocketCan>(this);
  183. //_can->Start(_canip,_canport,_hostport);
  184. std::this_thread::yield();
  185. // OnNotifyReq(0);
  186. }
  187. /*
  188. void CMessageQueue::WriteCanMessage(std::unordered_map<int32_t, cannet_frame>& node,bool islidar)
  189. {
  190. if(!bDataChannelCreated) return;
  191. // std::lock_guard<std::mutex> l(_canLock);
  192. RemoNet::CCCanMesage Req;
  193. Req.set_islidar(islidar);
  194. for(auto& p:node)
  195. {
  196. int32_t lidar=p.second.canid;
  197. auto m=Req.add_message();
  198. m->set_head(p.second.dlc);
  199. m->set_canid(lidar);
  200. m->set_data(p.second.data,8);
  201. }
  202. MessageHead Head;
  203. CIOBuffer pBuffer;
  204. Head.Command = RemoNet::CC_CAN;
  205. Head.Length = Req.ByteSizeLong();
  206. Head.Serialize(pBuffer.Buffer);
  207. auto ptr = pBuffer.Buffer + MessageHead::Size();
  208. Req.SerializeToArray(ptr, Head.Length);
  209. pBuffer.Length = MessageHead::Size() + Head.Length;
  210. _peerArray[0]->SendData(&pBuffer);
  211. }
  212. bool CMessageQueue::IsCarId(int32_t value)
  213. {
  214. return std::find(_carArray.begin(),_carArray.end(),value)!=_carArray.end();
  215. }
  216. */
  217. void CMessageQueue::EnQueue(CIOBuffer* pBuffer)
  218. {
  219. bool bNullBuffer=false;
  220. std::unique_lock <std::mutex> lck(_lock);
  221. if(Head==nullptr)
  222. {
  223. Head=Tail=pBuffer;
  224. bNullBuffer=true;
  225. }
  226. else{
  227. Tail->NextBuf=pBuffer;
  228. Tail=Tail->NextBuf;
  229. }
  230. pBuffer->NextBuf=nullptr;
  231. if(bNullBuffer)
  232. {
  233. //_cv.notify_one();
  234. //20231023
  235. _cv.notify_all();
  236. }
  237. }
  238. void CMessageQueue::Process()
  239. {
  240. CIOBuffer * ptr=nullptr;
  241. {
  242. std::unique_lock <std::mutex> lck(_lock);
  243. /*
  244. while(Head==nullptr)
  245. {
  246. _cv.wait(lck);
  247. }
  248. */
  249. while(Head==nullptr&&_cv.wait_for(lck,std::chrono::seconds(1))==std::cv_status::timeout)
  250. {
  251. CheckSignal();
  252. //std::cout<<".";
  253. //std::cout.flush();
  254. }
  255. }
  256. while(Head!=nullptr)
  257. {
  258. ptr=Head;
  259. Head=Head->NextBuf;
  260. if(ptr!=nullptr)
  261. {
  262. Message* message=reinterpret_cast<Message *>(ptr->Buffer);
  263. switch (message->cmd)
  264. {
  265. case MessageType::ReqVideo:
  266. OnNotifyReq((int32_t)message->param_l);
  267. break;
  268. case MessageType::RepVideo:
  269. OnNotifyRep((int32_t)message->param_l);
  270. break;
  271. case MessageType::Connected:
  272. OnNotifyConnected((bool)message->param_l);
  273. break;
  274. case MessageType::Leave:
  275. OnNotifyLeave();
  276. break;
  277. case MessageType::AsyncMessage:
  278. OnNotifyMessage();
  279. break;
  280. case MessageType::StopSensor:
  281. OnNotifyStopSensor();
  282. break;
  283. case MessageType::Ping:
  284. OnNotifyPing(message->param_l);
  285. break;
  286. }
  287. ptr->Release();
  288. }
  289. }
  290. }
  291. void CMessageQueue::SetTick(long long tick)
  292. {
  293. _curTick=tick;
  294. }
  295. void CMessageQueue::OnNotifyConnected(bool bRet)
  296. {
  297. if(bRet)
  298. {
  299. _client->WriteAddRobot(_serial,_name,static_cast<int32_t>(EgoType::Car));
  300. _updatethread.start(_client.get());
  301. //cs->Analog(0,0,0,0,0);
  302. }
  303. else
  304. {
  305. if(_peerId!=-1)
  306. {
  307. OnVideoLeave(_peerId,EgoType::User);
  308. _peerId=-1;
  309. }
  310. _updatethread.stop();
  311. }
  312. }
  313. int day_diffient(int year_start, int month_start, int day_start,char *Dst)
  314. {
  315. //2024-03-11
  316. int year_end = strtol(Dst,NULL,10);
  317. char Temp = '-',*p = NULL,*p1 = NULL;
  318. p = strchr(Dst,Temp);
  319. int month_end = strtol(p + 1,NULL,10);
  320. p1 = strchr(p + 1,Temp);
  321. int day_end = strtol(p1 + 1,NULL,10);
  322. int y2, m2, d2;
  323. int y1, m1, d1;
  324. m1 = (month_start + 9) % 12;
  325. y1 = year_start - m1/10;
  326. d1 = 365*y1 + y1/4 - y1/100 + y1/400 + (m1*306 + 5)/10 + (day_start - 1);
  327. m2 = (month_end + 9) % 12;
  328. y2 = year_end - m2/10;
  329. d2 = 365*y2 + y2/4 - y2/100 + y2/400 + (m2*306 + 5)/10 + (day_end - 1);
  330. return (d1 - d2);
  331. }
  332. void delete_days(const char *path)
  333. {
  334. DIR *dir;
  335. struct dirent *entry;
  336. struct stat statbuf;
  337. time_t rawtime;
  338. struct tm* info;
  339. time(&rawtime);
  340. info = localtime(&rawtime);
  341. uint8_t secret[64] = { 0 };
  342. sprintf((char*)secret, "%d-%.2d-%.2d.log", info->tm_year + 1900, info->tm_mon + 1, info->tm_mday);
  343. printf("%s\r\n",secret);
  344. dir = opendir(path);
  345. if (dir == NULL)
  346. {
  347. printf("无法打开目录\n");
  348. return;
  349. }
  350. while ((entry = readdir(dir)) != NULL)
  351. {
  352. if(entry->d_name[0]=='.')
  353. continue;
  354. //printf("%s\n",entry->d_name);
  355. if(day_diffient(info->tm_year + 1900, info->tm_mon + 1, info->tm_mday,entry->d_name) > 15)
  356. {
  357. char Dst[128];
  358. memset(Dst,0,128);
  359. sprintf(Dst,"rm -rf /home/nvidia/20240226ZGJ-PORT/EgoZJ/EgoSystem/build/log/%s",entry->d_name);
  360. system(Dst);
  361. }
  362. }
  363. closedir(dir);
  364. }
  365. void CMessageQueue::SerichFile(char *filename)
  366. {
  367. DIR *directory_pointer;
  368. struct dirent *entry;
  369. int exist = 0;
  370. char Dst[128];
  371. memset(Dst,0,128);
  372. sprintf(Dst,"/home/nvidia/20240226ZGJ-PORT/EgoZJ/EgoSystem/build/log/%s",filename);
  373. if((directory_pointer=opendir("/home/nvidia/20240226ZGJ-PORT/EgoZJ/EgoSystem/build/log/")) == NULL)
  374. printf("Error open\n");
  375. else
  376. {
  377. while((entry=readdir(directory_pointer)) != NULL)
  378. {
  379. if(entry->d_name[0]=='.') continue;
  380. printf("%s\n",entry->d_name);
  381. if(!strcmp(entry->d_name,filename))
  382. {
  383. File_fd = fopen(Dst, "a");
  384. exist = 1;
  385. break;
  386. }
  387. }
  388. }
  389. if(!exist)
  390. File_fd = fopen(Dst, "w+");
  391. closedir(directory_pointer);
  392. }
  393. void CMessageQueue::OnNotifyReq(int32_t index)
  394. {
  395. // std::cout<<__FUNCTION__<<","<<__LINE__<<std::endl;
  396. if(_peerId==-1) return;
  397. if(index==0)
  398. {
  399. mrsWebrtcCreateFactory(true);
  400. _curTick=0;
  401. bStopedCar=false;
  402. _Rtk->Start();
  403. if(_Version)//AD10
  404. {
  405. _CanBusVehicle->Start();
  406. _CanBusRadar->Start();
  407. }
  408. else
  409. {
  410. _PcanBusVehicle->Start();
  411. _RadarIp->Start();
  412. }
  413. _Mqtt_ZR->Start();
  414. _Mqtt_SE->Start();
  415. File_fd = NULL;
  416. struct statfs diskInfo;
  417. statfs("/dev/mmcblk0p1", &diskInfo);
  418. unsigned long long freeDisk = diskInfo.f_bfree * diskInfo.f_bsize;
  419. time_t rawtime;
  420. struct tm* info;
  421. time(&rawtime);
  422. info = localtime(&rawtime);
  423. uint8_t secret[64] = { 0 };
  424. sprintf((char*)secret, "%d-%.2d-%.2d.log", info->tm_year + 1900, info->tm_mon + 1, info->tm_mday);
  425. if((freeDisk >> 30) < 15)
  426. {
  427. system("rm -rf /home/nvidia/20240226ZGJ-PORT/EgoZJ/EgoSystem/build/log");
  428. system("mkdir /home/nvidia/20240226ZGJ-PORT/EgoZJ/EgoSystem/build/log/");
  429. }
  430. else
  431. delete_days("/home/nvidia/20240226ZGJ-PORT/EgoZJ/EgoSystem/build/log");
  432. SerichFile((char *)secret);
  433. }
  434. _peerArray[index]=std::make_unique<CPeerConnection>(static_cast<ChannelType>(index),_client.get());
  435. _client->WriteVideoRep(_peerId, RemoNet::VideoDesc::OK, index);
  436. }
  437. void CMessageQueue::OnNotifyRep(int32_t index)
  438. {
  439. _peerArray[index]=std::make_unique<CPeerConnection>(static_cast<ChannelType>(index), _client.get());
  440. InitPeerConnection(_peerId,index);
  441. _peerArray[index]->CreateOffer();
  442. }
  443. void CMessageQueue::InitPeerConnection(int32_t peer,int32_t index)
  444. {
  445. _peerArray[index]->Initialize(peer,index,_UdpMinPort,_UdpMaxPort);
  446. _peerArray[index]->AddDataChannel(true, false);
  447. _peerArray[index]->AddLocalVideoTrack(static_cast<RenderPosition>(index),_cameraArray[index].index);
  448. if(index==RenderPosition::BACK)
  449. {
  450. void * front=_peerArray[RenderPosition::FRONT]->GetCurrentCtx();
  451. while(front==nullptr)
  452. {
  453. std::cout<<"front==nullptr"<<std::endl;
  454. std::this_thread::sleep_for(std::chrono::microseconds(50));
  455. front=_peerArray[RenderPosition::FRONT]->GetCurrentCtx();
  456. }
  457. void * back=_peerArray[RenderPosition::BACK]->GetCurrentCtx();
  458. while (back==nullptr)
  459. {
  460. std::cout<<"back==nullptr"<<std::endl;
  461. std::this_thread::sleep_for(std::chrono::microseconds(50));
  462. back=_peerArray[RenderPosition::BACK]->GetCurrentCtx();
  463. }
  464. _peerArray[RenderPosition::FRONT]->SetOtherCtx(back);
  465. _peerArray[RenderPosition::BACK]->SetOtherCtx(front);
  466. }
  467. /*
  468. if((index+1)==RenderPosition::ALL)
  469. {
  470. void * front=_peerArray[RenderPosition::FRONT]->GetCurrentCtx();
  471. while(front==nullptr)
  472. {
  473. std::cout<<"front==nullptr"<<std::endl;
  474. std::this_thread::sleep_for(std::chrono::microseconds(50));
  475. front=_peerArray[RenderPosition::FRONT]->GetCurrentCtx();
  476. }
  477. void * back=_peerArray[RenderPosition::BACK]->GetCurrentCtx();
  478. while (back==nullptr)
  479. {
  480. std::cout<<"back==nullptr"<<std::endl;
  481. std::this_thread::sleep_for(std::chrono::microseconds(50));
  482. back=_peerArray[RenderPosition::BACK]->GetCurrentCtx();
  483. }
  484. _peerArray[RenderPosition::FRONT]->SetOtherCtx(back);
  485. _peerArray[RenderPosition::BACK]->SetOtherCtx(front);
  486. void * left=_peerArray[RenderPosition::LEFT]->GetCurrentCtx();
  487. while(left==nullptr)
  488. {
  489. std::cout<<"left==nullptr"<<std::endl;
  490. std::this_thread::sleep_for(std::chrono::microseconds(50));
  491. front=_peerArray[RenderPosition::LEFT]->GetCurrentCtx();
  492. }
  493. void * right=_peerArray[RenderPosition::RIGHT]->GetCurrentCtx();
  494. while (right==nullptr)
  495. {
  496. std::cout<<"right==nullptr"<<std::endl;
  497. std::this_thread::sleep_for(std::chrono::microseconds(50));
  498. back=_peerArray[RenderPosition::RIGHT]->GetCurrentCtx();
  499. }
  500. _peerArray[RenderPosition::LEFT]->SetOtherCtx(right);
  501. _peerArray[RenderPosition::RIGHT]->SetOtherCtx(left);
  502. }
  503. */
  504. /*
  505. if((index+1)==RenderPosition::ALL)
  506. {
  507. void * front=_peerArray[RenderPosition::FRONT]->GetCurrentCtx();
  508. void * back=_peerArray[RenderPosition::BACK]->GetCurrentCtx();
  509. void * left=_peerArray[RenderPosition::LEFT]->GetCurrentCtx();
  510. void * right=_peerArray[RenderPosition::RIGHT]->GetCurrentCtx();
  511. void * dash=_peerArray[RenderPosition::DASHBOARD]->GetCurrentCtx();
  512. _peerArray[RenderPosition::FRONT]->SetOtherCtx(back);
  513. _peerArray[RenderPosition::BACK]->SetOtherCtx(front);
  514. _peerArray[RenderPosition::LEFT]->SetOtherCtx(left);
  515. _peerArray[RenderPosition::RIGHT]->SetOtherCtx(right);
  516. _peerArray[RenderPosition::DASHBOARD]->SetOtherCtx(dash);
  517. }
  518. */
  519. if(index==RenderPosition::FRONT)
  520. _peerArray[index]->AddLocalAudioTrack();
  521. }
  522. void CMessageQueue::OnAdd(bool bRet)
  523. {
  524. }
  525. void CMessageQueue::OnConnected(bool bRet)
  526. {
  527. CIOBuffer * pBuffer=CIOBuffer::Alloc();
  528. Message* message=reinterpret_cast<Message *>(pBuffer->Buffer);
  529. message->cmd=MessageType::Connected;
  530. message->param_l=bRet;
  531. EnQueue(pBuffer);
  532. }
  533. void CMessageQueue::OnVideoLeave(int32_t peer,EgoType type)
  534. {
  535. {
  536. CIOBuffer * pBuffer=CIOBuffer::Alloc();
  537. Message* message=reinterpret_cast<Message *>(pBuffer->Buffer);
  538. message->cmd=MessageType::StopSensor;
  539. EnQueue(pBuffer);
  540. }
  541. {
  542. CIOBuffer * pBuffer=CIOBuffer::Alloc();
  543. Message* message=reinterpret_cast<Message *>(pBuffer->Buffer);
  544. message->cmd=MessageType::Leave;
  545. EnQueue(pBuffer);
  546. }
  547. }
  548. #ifdef WIN32
  549. void CMessageQueue::OnVideoRep(int32_t index,RemoNet::VideoDesc desc)
  550. {
  551. if (desc == RemoNet::VideoDesc::OK)
  552. {
  553. assert(_peerId!=-1);
  554. CIOBuffer * pBuffer=CIOBuffer::Alloc();
  555. Message* message=reinterpret_cast<Message *>(pBuffer->Buffer);
  556. message->cmd=MessageType::ReqVideo;
  557. message->param_l=index;
  558. EnQueue(pBuffer);
  559. }
  560. }
  561. #else
  562. void CMessageQueue::OnVideoReq(int32_t video,int32_t peer)
  563. {
  564. // std::cout<<__FUNCTION__<<","<<__LINE__<<std::endl;
  565. _peerId=peer;
  566. CIOBuffer * pBuffer=CIOBuffer::Alloc();
  567. Message* message=reinterpret_cast<Message *>(pBuffer->Buffer);
  568. message->cmd=MessageType::ReqVideo;
  569. message->param_l=video;
  570. EnQueue(pBuffer);
  571. }
  572. #endif
  573. void CMessageQueue::OnNotifyLeave()
  574. {
  575. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  576. for (size_t i = 0; i < _peerArray.size(); i++)
  577. {
  578. if(_peerArray[i]!=nullptr)
  579. {
  580. _peerArray[i]->Close();
  581. _peerArray[i].reset();
  582. }
  583. /* code */
  584. }
  585. _peerId=-1;
  586. }
  587. void CMessageQueue::OnNotifyStopSensor()
  588. {
  589. _curTick=0;
  590. if(_Version)//AD10
  591. {
  592. std::cout<<"_CanBusVehicle Stop"<<std::endl;
  593. _CanBusVehicle->Stop();
  594. std::cout<<"_CanBusRadar Stop"<<std::endl;
  595. _CanBusRadar->Stop();
  596. }
  597. else
  598. {
  599. std::cout<<"_PcanBusVehicle Stop"<<std::endl;
  600. _PcanBusVehicle->Stop();
  601. std::cout<<"_RadarIp Stop"<<std::endl;
  602. _RadarIp->Stop();
  603. }
  604. std::cout << "RTK Stop" << std::endl;
  605. _Rtk->Stop();
  606. std::cout<<"mqtt Stop"<<std::endl;
  607. _Mqtt_ZR->Stop();
  608. std::cout<<"data mqtt Stop"<<std::endl;
  609. _Mqtt_SE->Stop();
  610. if(!File_fd)
  611. {
  612. fclose(File_fd);
  613. File_fd = NULL;
  614. }
  615. RemoNet::StopAck Rep;
  616. CIOBuffer Buffer;
  617. MessageHead Head;
  618. Head.Command = RemoNet::CC_StopACK;
  619. Head.Length = Rep.ByteSizeLong();
  620. Head.Serialize(Buffer.Buffer);
  621. auto ptr = Buffer.Buffer + MessageHead::Size();
  622. Rep.SerializeToArray(ptr, Head.Length);
  623. Buffer.Length = Head.Length + MessageHead::Size();
  624. _peerArray[RenderPosition::FRONT]->SendData(Buffer);
  625. }
  626. void CMessageQueue::OnVideoOffer(int32_t index,const char* type, const char* sdp)
  627. {
  628. // std::cout<<__FUNCTION__<<","<<__LINE__<<std::endl;
  629. InitPeerConnection(_peerId,index);
  630. _peerArray[index]->SetRemoteDescription(type,sdp);
  631. _peerArray[index]->CreateAnswer();
  632. }
  633. void CMessageQueue::OnVideoAnswer(int32_t index, const char* type, const char* sdp)
  634. {
  635. // std::cout<<__FUNCTION__<<","<<__LINE__<<std::endl;
  636. _peerArray[index]->SetRemoteDescription(type,sdp);
  637. }
  638. void CMessageQueue::OnVideoCandidate(int32_t index,const char* candidate,
  639. int32_t sdp_mline_index,
  640. const char* sdp_mid)
  641. {
  642. _peerArray[index]->AddIceCandidate(candidate,sdp_mline_index,sdp_mid);
  643. }
  644. /*
  645. void CMessageQueue::SwitchCamera(bool front)
  646. {
  647. _peerArray[RenderPosition::FRONT_BACK]->SwitchCapture(front);
  648. }
  649. */
  650. //关注
  651. void CMessageQueue::OnMessageFrameNotify(ChannelType type,int16_t cmd,int16_t length,const void * data)
  652. {
  653. // std::cout<<"cmd:" <<std::hex<<cmd<<std::endl;
  654. if(cmd==RemoNet::CC_Text)
  655. {
  656. RemoNet::TestTextReq Req;
  657. Req.ParseFromArray(data,length);
  658. std::cout<<Req.text()<<std::endl;
  659. CIOBuffer * pBuffer=CIOBuffer::Alloc();
  660. Message* message=reinterpret_cast<Message *>(pBuffer->Buffer);
  661. message->cmd=MessageType::AsyncMessage;
  662. EnQueue(pBuffer);
  663. }
  664. else if(cmd==RemoNet::CC_Switch)
  665. {
  666. RemoNet::CCSwitch Req;
  667. Req.ParseFromArray(data,length);
  668. bool front=Req.front();
  669. _peerArray[RenderPosition::FRONT]->SwitchCapture(front);
  670. }
  671. else if(cmd==RemoNet::CC_Ping)
  672. {
  673. RemoNet::CCPing Req;
  674. Req.ParseFromArray(data,length);
  675. CIOBuffer * pBuffer=CIOBuffer::Alloc();
  676. Message* message=reinterpret_cast<Message *>(pBuffer->Buffer);
  677. message->cmd=MessageType::Ping;
  678. message->param_l=Req.tick();
  679. EnQueue(pBuffer);
  680. }
  681. else if(cmd==RemoNet::CC_SensorStop)
  682. {
  683. CIOBuffer * pBuffer=CIOBuffer::Alloc();
  684. Message* message=reinterpret_cast<Message *>(pBuffer->Buffer);
  685. message->cmd=MessageType::StopSensor;
  686. EnQueue(pBuffer);
  687. }
  688. else if (cmd == RemoNet::CC_CANMSG)
  689. {
  690. _source = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  691. _curTick = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  692. RemoNet::CCCanMsg Req;
  693. Req.ParseFromArray(data, length);
  694. cannet_frame* frames = (cannet_frame*)alloca(sizeof(cannet_frame) * Req.frams_size());
  695. for (int32_t i = 0; i < Req.frams_size(); i++)
  696. {
  697. auto& frame = Req.frams(i);
  698. frames[i].canid = frame.canid();
  699. frames[i].dlc = frame.dlc();
  700. memcpy(frames[i].data, frame.data().data(), frame.dlc());
  701. }
  702. //_robot->Get()->OnMessage(frames, Req.frams_size());
  703. if(_Version)//AD10
  704. _CanBusVehicle->Get()->OnMessage(frames, Req.frams_size());
  705. else
  706. _PcanBusVehicle->Get()->OnMessage(frames, Req.frams_size());
  707. }
  708. }
  709. void CMessageQueue::StopCar()
  710. {
  711. std::cout<<"Stop Car"<<std::endl;
  712. if(_Version)//AD10
  713. _CanBusVehicle->Get()->Emergency();
  714. else
  715. _PcanBusVehicle->Get()->Emergency();
  716. }
  717. void CMessageQueue::OnNotifyMessage()
  718. {
  719. RemoNet::TestTextReq Req;
  720. Req.set_text("ewqewqewqe");
  721. CIOBuffer Buffer;
  722. MessageHead Head;
  723. Head.Command = RemoNet::CC_Text;
  724. Head.Length = Req.ByteSizeLong();
  725. Head.Serialize(Buffer.Buffer);
  726. auto ptr = Buffer.Buffer + MessageHead::Size();
  727. Req.SerializeToArray(ptr, Head.Length);
  728. Buffer.Length = Head.Length + MessageHead::Size();
  729. _peerArray[RenderPosition::FRONT]->SendData(Buffer);
  730. }
  731. void CMessageQueue::OnNotifyPing(int64_t value)
  732. {
  733. RemoNet::CCPing Rep;
  734. Rep.set_tick(value);
  735. CIOBuffer Buffer;
  736. MessageHead Head;
  737. Head.Command = RemoNet::CC_Ping;
  738. Head.Length = Rep.ByteSizeLong();
  739. Head.Serialize(Buffer.Buffer);
  740. auto ptr = Buffer.Buffer + MessageHead::Size();
  741. Rep.SerializeToArray(ptr, Head.Length);
  742. Buffer.Length = Head.Length + MessageHead::Size();
  743. //std::cout << "ping" << std::endl;
  744. if( _peerArray[RenderPosition::FRONT]!=nullptr && _peerArray[RenderPosition::FRONT]->bReadyChannel)
  745. _peerArray[RenderPosition::FRONT]->SendData(Buffer);
  746. }
  747. /*
  748. void CMessageQueue::StartCar()
  749. {
  750. _can->SetStartWrite(true);
  751. }
  752. */
  753. void CMessageQueue::CheckSignal()
  754. {
  755. if(!bStopedCar)
  756. {
  757. long long tick=std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  758. if(_curTick!=0&&tick-_curTick > 3)
  759. {
  760. StopCar();
  761. bStopedCar=true;
  762. std::cout<<"_curTick!=0&&tick-_curTick > 3" << std::endl;
  763. _curStopTick = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  764. btimeStopedCar = true;
  765. _curTick = 0;
  766. }
  767. }
  768. }
  769. void CMessageQueue::WriteIMUData(ImuData* data)
  770. {
  771. MessageHead Head;
  772. CIOBuffer Buffer;
  773. RemoNet::IMuMessage Req;
  774. Req.set_rx(data->ry);
  775. Req.set_ry(data->rx);
  776. // Req.set_rz(data->rz);
  777. Head.Command=RemoNet::CC_IMU;
  778. Head.Length=Req.ByteSizeLong();
  779. Head.Serialize(Buffer.Buffer);
  780. auto ptr = Buffer.Buffer + MessageHead::Size();
  781. Req.SerializeToArray(ptr, Head.Length);
  782. Buffer.Length = Head.Length + MessageHead::Size();
  783. if( _peerArray[ChannelType::CHANNEL_IMU]!=nullptr)
  784. _peerArray[ChannelType::CHANNEL_IMU]->SendData(Buffer);
  785. }
  786. void CMessageQueue::WritePacket(ChannelType type, CIOBuffer & pBuffer)
  787. {
  788. if( _peerArray[type]!=nullptr)
  789. _peerArray[type]->SendData(pBuffer);
  790. }
  791. void CMessageQueue::WriteRadarData(RadarData& data)
  792. {
  793. MessageHead Head;
  794. CIOBuffer Buffer;
  795. RemoNet::CCRadarMessage Req;
  796. Req.set_radar0(data.r0);
  797. Req.set_radar1(data.r1);
  798. Req.set_radar2(data.r2);
  799. Req.set_radar3(data.r3);
  800. Req.set_radar4(data.r4);
  801. Req.set_radar5(data.r5);
  802. Req.set_radar6(data.r6);
  803. Req.set_radar7(data.r7);
  804. //Head.Command=RemoNet::CC_IMU;
  805. Head.Command = RemoNet::CC_Radar;
  806. Head.Length=Req.ByteSizeLong();
  807. Head.Serialize(Buffer.Buffer);
  808. auto ptr = Buffer.Buffer + MessageHead::Size();
  809. Req.SerializeToArray(ptr, Head.Length);
  810. Buffer.Length = Head.Length + MessageHead::Size();
  811. if( _peerArray[ChannelType::CHANNEL_RADAR]!=nullptr)
  812. _peerArray[ChannelType::CHANNEL_RADAR]->SendData(Buffer);
  813. }
  814. void CMessageQueue::WriteRobotStatus(int32_t ,int32_t )
  815. {
  816. }
  817. #ifdef LIDAR_SENSOR
  818. void CMessageQueue::WriteLidarPoint(const PointCloudMsg<PointXYZI>& msg,ChannelType side)
  819. {
  820. RemoNet::LidarPoint pt;
  821. pt.set_is_left(side==ChannelType::CHANNEL_LEFT_LIDAR);
  822. pt.set_frame_id(msg.frame_id);
  823. pt.set_height(msg.height);
  824. pt.set_width(msg.width);
  825. pt.set_is_dense(msg.is_dense);
  826. pt.set_seq(msg.seq);
  827. pt.set_timestamp(msg.timestamp);
  828. for(int i=0;i<msg.point_cloud_ptr->size();i++)
  829. {
  830. pt.add_data((*msg.point_cloud_ptr)[i].x);
  831. pt.add_data((*msg.point_cloud_ptr)[i].y);
  832. pt.add_data((*msg.point_cloud_ptr)[i].z);
  833. pt.add_data((*msg.point_cloud_ptr)[i].intensity);
  834. }
  835. MessageHead Head;
  836. CIOBuffer Buffer;
  837. Head.Command=RemoNet::CC_LIDARDATA;
  838. Head.Length=pt.ByteSizeLong();
  839. Head.Serialize(Buffer.Buffer);
  840. auto ptr = Buffer.Buffer + MessageHead::Size();
  841. pt.SerializeToArray(ptr, Head.Length);
  842. Buffer.Length = Head.Length + MessageHead::Size();
  843. if( _peerArray[side]!=nullptr)
  844. _peerArray[side]->SendData(&Buffer);
  845. }
  846. #endif
  847. void CMessageQueue::SwitchCamera(bool front)
  848. {
  849. _peerArray[RenderPosition::FRONT]->SwitchCapture(front);
  850. _peerArray[RenderPosition::BACK]->SwitchCapture(front);
  851. }
  852. void CMessageQueue::SendZGJStatus(int status)
  853. {
  854. _Rtk->Get()->Send_ZGJ_status(status);
  855. }
  856. // void CMessageQueue::SendVehicleStatus(int16_t Direction,int16_t Hand_Throttle,int16_t Foot_Throttle,int16_t Brake)
  857. // {
  858. // //CDataMqttSensor::sendMessage()
  859. // if (CDataMqttSensor::_run)
  860. // {
  861. // time_t rawtime;
  862. // struct tm* info;
  863. // time(&rawtime);
  864. // info = localtime(&rawtime);
  865. // char secret[64] = { 0 };
  866. // sprintf((char*)secret, "%d-%.2d-%.2d %.2d:%.2d:%.2d", info->tm_year + 1900, info->tm_mon + 1, info->tm_mday,info->tm_hour,info->tm_min,info->tm_sec);
  867. // printf("%s\r\n",secret);
  868. // char WriteLocalDat[128];
  869. // memset(WriteLocalDat,0,128);
  870. // sprintf(WriteLocalDat, "%d-%.2d-%.2d %.2d:%.2d:%.2d 方向值:%d 手油门值:%d 脚油门值:%d 刹车值:%d\n", info->tm_year + 1900, info->tm_mon + 1, info->tm_mday,info->tm_hour,info->tm_min,info->tm_sec,
  871. // Direction,Hand_Throttle,Foot_Throttle,Brake);
  872. // fwrite(WriteLocalDat, strlen(WriteLocalDat) , 1, File_fd);
  873. // Json::Value root;
  874. // Json::Value Source;
  875. // Json::FastWriter writer;
  876. // std::string SendTime;
  877. // Source["1"] = SendTime.assign(secret,strlen(secret));//发送时间
  878. // Source["2"] = Direction;//方向值
  879. // Source["3"] = Hand_Throttle;//手油门值
  880. // Source["4"] = Foot_Throttle;//脚油门值
  881. // Source["5"] = Brake;//刹车值
  882. // Json::StyledWriter sw;
  883. // //std::cout << sw.write(Source) << std::endl << std::endl;
  884. // if (!DataMqtt_SendDate)
  885. // {
  886. // DataMqtt_curTick = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  887. // DataMqtt_SendDate = true;
  888. // }
  889. // else
  890. // {
  891. // long long tick = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  892. // if (DataMqtt_curTick != 0 && tick - DataMqtt_curTick > 10000)
  893. // {
  894. // if (CDataMqttSensor::_run && (CDataMqttSensor::m_mqttClient != NULL))
  895. // CDataMqttSensor::sendMessage((char*)sw.write(Source).c_str(), 0, (char*)"bg/log");
  896. // DataMqtt_SendDate = false;
  897. // }
  898. // }
  899. // }
  900. // }
  901. void CMessageQueue::SendVehicleStatus(vehicle_status can_status)
  902. {
  903. //CDataMqttSensor::sendMessage()
  904. if (CDataMqttSensor::_run)
  905. {
  906. time_t rawtime;
  907. struct tm* info;
  908. time(&rawtime);
  909. info = localtime(&rawtime);
  910. char secret[64] = { 0 };
  911. sprintf((char*)secret, "%d-%.2d-%.2d %.2d:%.2d:%.2d", info->tm_year + 1900, info->tm_mon + 1, info->tm_mday,info->tm_hour,info->tm_min,info->tm_sec);
  912. printf("%s\r\n",secret);
  913. // char WriteLocalDat[128];
  914. // memset(WriteLocalDat,0,128);
  915. // sprintf(WriteLocalDat, "%d-%.2d-%.2d %.2d:%.2d:%.2d 方向值:%d 手油门值:%d 脚油门值:%d 刹车值:%d\n", info->tm_year + 1900, info->tm_mon + 1, info->tm_mday,info->tm_hour,info->tm_min,info->tm_sec,
  916. // Direction,Hand_Throttle,Foot_Throttle,Brake);
  917. // fwrite(WriteLocalDat, strlen(WriteLocalDat) , 1, File_fd);
  918. Json::Value root;
  919. Json::Value Source;
  920. Json::FastWriter writer;
  921. std::string SendTime;
  922. // Source["1"] = SendTime.assign(secret,strlen(secret));//发送时间
  923. // Source["2"] = Direction;//方向值
  924. // Source["3"] = Hand_Throttle;//手油门值
  925. // Source["4"] = Foot_Throttle;//脚油门值
  926. // Source["5"] = Brake;//刹车值
  927. Source["1"] = can_status.fire_status;//启动/熄火
  928. Source["2"] = can_status.remote_forward;//远程控制前进
  929. Source["3"] = can_status.remote_backward;//远程控制后退
  930. Source["4"] = can_status.Brake;//刹车
  931. Source["5"] = can_status.Park;//驻车
  932. Source["6"] = can_status.Outrigger_status;//支腿
  933. Source["7"] = can_status.Turn_angle;//转弯角度
  934. Source["8"] = can_status.Left_turn;//左旋 左手柄 左信号
  935. Source["9"] = can_status.Right_turn;//右旋 左手柄 右信号
  936. Source["10"] = can_status.Raised;//小臂抬起 左手柄 向后
  937. Source["11"] = can_status.Decrease;//小臂下降 左手柄 向前
  938. Source["12"] = can_status.Stretch;//大臂伸起 右手柄 向后
  939. Source["13"] = can_status.Bulls_decline;//大臂下降 右手柄 向前
  940. Source["14"] = can_status.Material;//吸盘吸料
  941. Source["15"] = can_status.Discharge;//吸盘放料
  942. Source["16"] = can_status.zhua;//抓斗抓料
  943. Source["17"] = can_status.fang;//抓斗放料
  944. Source["18"] = can_status.Shell_rotation_left;//贝壳斗旋转 shun
  945. Source["19"] = can_status.Shell_rotation_right;//贝壳斗旋转 ni
  946. Source["19"] = can_status.Cabin;//驾驶室升
  947. Source["20"] = can_status.Cab;//驾驶室降
  948. Source["21"] = can_status.Working_signal;//作业灯开/关
  949. Source["22"] = can_status.Turn_left_signal;//左转向 开/关
  950. Source["23"] = can_status.Turn_right_signal;//右转向 开/关
  951. Source["24"] = can_status.Warning_Light;//警示灯 开/关 ?
  952. Source["25"] = can_status.Trumpet;//喇叭
  953. Source["26"] = can_status.Security_lock;//安全锁 开/关
  954. Source["27"] = can_status.Urget_stop;//急停
  955. Source["28"] = can_status.Vehicle_id;//车辆id
  956. Source["29"] = SendTime.assign(secret,strlen(secret));;//发送时间
  957. Json::StyledWriter sw;
  958. //std::cout << sw.write(Source) << std::endl << std::endl;
  959. if (!DataMqtt_SendDate)
  960. {
  961. DataMqtt_curTick = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  962. DataMqtt_SendDate = true;
  963. }
  964. else
  965. {
  966. long long tick = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  967. if (DataMqtt_curTick != 0 && tick - DataMqtt_curTick > 10000)
  968. {
  969. if (CDataMqttSensor::_run && (CDataMqttSensor::m_mqttClient != NULL))
  970. CDataMqttSensor::sendMessage((char*)sw.write(Source).c_str(), 0, (char*)"bg/log");
  971. DataMqtt_SendDate = false;
  972. }
  973. }
  974. }
  975. }