Laser.cpp 9.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399
  1. #include "Laser.h"
  2. #include "../tool/MeasureTopicPublisher.h"
  3. CBinaryData::CBinaryData()
  4. :m_buf(0)
  5. ,m_length(0)
  6. {
  7. }
  8. CBinaryData::CBinaryData(const char* buf, int len, DATA_type type)
  9. :m_buf(0),m_length(0)
  10. {
  11. if (len > 0)
  12. {
  13. m_buf = (char*)malloc(len);
  14. memcpy(m_buf, buf, len);
  15. m_length = len;
  16. }
  17. }
  18. CBinaryData::CBinaryData(const CBinaryData& data)
  19. :m_buf(0),m_length(0)
  20. {
  21. if (m_buf)
  22. {
  23. free(m_buf);
  24. m_buf = 0;
  25. m_length = 0;
  26. }
  27. if (data.Length() > 0)
  28. {
  29. m_buf = (char*)malloc(data.Length());
  30. memcpy(m_buf, data.Data(), data.Length());
  31. m_length = data.Length();
  32. }
  33. }
  34. CBinaryData::~CBinaryData()
  35. {
  36. if (m_buf && m_length)
  37. {
  38. free(m_buf);
  39. m_length = 0;
  40. }
  41. }
  42. char* CBinaryData::Data()const {
  43. return m_buf;
  44. }
  45. int CBinaryData::Length()const {
  46. return m_length;
  47. }
  48. CBinaryData& CBinaryData::operator=(const CBinaryData& data)
  49. {
  50. if (m_buf)
  51. {
  52. free(m_buf);
  53. m_buf = 0;
  54. m_length = 0;
  55. }
  56. if (data.Length() > 0)
  57. {
  58. m_buf = (char*)malloc(data.Length());
  59. memcpy(m_buf, data.Data(), data.Length());
  60. m_length = data.Length();
  61. }
  62. return *this;
  63. }
  64. bool CBinaryData::operator==(const char* str)
  65. {
  66. int length = strlen(str);
  67. return (strncmp((const char*)m_buf, str, length) == 0);
  68. }
  69. const char* CBinaryData::operator+(int n)
  70. {
  71. if (n < m_length)
  72. return m_buf + n;
  73. else
  74. return NULL;
  75. }
  76. CBinaryData& CBinaryData::operator+(CBinaryData& data)
  77. {
  78. if (data.Length() > 0)
  79. {
  80. int length = m_length + data.Length();
  81. char* buf = (char*)malloc(length);
  82. memcpy(buf, m_buf, m_length);
  83. memcpy(buf + m_length, data.Data(), data.Length());
  84. free(m_buf);
  85. m_buf = buf;
  86. m_length = length;
  87. }
  88. return *this;
  89. }
  90. char& CBinaryData::operator[](int n)
  91. {
  92. if (n >= 0 && n < m_length)
  93. return m_buf[n];
  94. }
  95. //////////////
  96. Laser_base::Laser_base(int id, Laser_proto::laser_parameter laser_param)
  97. :m_ThreadRcv(0)
  98. ,m_ThreadPro(0)
  99. ,m_ThreadPub(0)
  100. ,m_id(id)
  101. ,m_points_count(0)
  102. ,m_statu(eLaser_disconnect)
  103. ,m_dMatrix(0)
  104. , m_point_callback_fnc(0)
  105. , m_point_callback_pointer(0)
  106. ,m_laser_param(laser_param)
  107. ,m_bSave_file(false)
  108. ,m_bscan_start(false)
  109. {
  110. mp_laser_task = NULL;
  111. }
  112. Laser_base::~Laser_base()
  113. {
  114. if (m_dMatrix)
  115. {
  116. free(m_dMatrix);
  117. m_dMatrix = 0;
  118. }
  119. }
  120. Error_manager Laser_base::check_error()
  121. {
  122. return SUCCESS;
  123. }
  124. bool Laser_base::Start()
  125. {
  126. m_bscan_start=true;
  127. m_statu = eLaser_busy;
  128. m_bStart_capture.Notify(true);
  129. m_points_count=0;
  130. return true;
  131. }
  132. bool Laser_base::Stop()
  133. {
  134. m_bscan_start=false;
  135. m_bStart_capture.Notify(false);
  136. m_binary_log_tool.close();
  137. m_pts_log_tool.close();
  138. m_statu=eLaser_ready;
  139. //在停止雷达时,将雷达任务状态改为 TASK_OVER 已结束
  140. if(mp_laser_task !=NULL)
  141. {
  142. mp_laser_task->set_task_statu(TASK_OVER);
  143. /*if(mp_laser_task->get_statu() == TASK_WORKING)
  144. {
  145. }*/
  146. }
  147. return true;
  148. }
  149. void Laser_base::SetMetrix(double* data)
  150. {
  151. if (m_dMatrix == 0)
  152. {
  153. m_dMatrix = (double*)malloc(12 * sizeof(double));
  154. }
  155. memcpy(m_dMatrix, data, 12 * sizeof(double));
  156. }
  157. void Laser_base::SetPointCallBack(PointCallBack fnc, void* pointer)
  158. {
  159. m_point_callback_fnc = fnc;
  160. m_point_callback_pointer = pointer;
  161. }
  162. bool Laser_base::Connect()
  163. {
  164. m_bThreadRcvRun.Notify(true);
  165. if(m_ThreadRcv==0)
  166. m_ThreadRcv = new std::thread(&Laser_base::thread_recv, this);
  167. m_ThreadRcv->detach();
  168. m_bThreadProRun.Notify(true);
  169. if(m_ThreadPro==0)
  170. m_ThreadPro = new std::thread(&Laser_base::thread_toXYZ, this);
  171. m_ThreadPro->detach();
  172. if(m_ThreadPub==0)
  173. m_ThreadPub = new std::thread(threadPublish, this);
  174. m_ThreadPub->detach();
  175. return true;
  176. }
  177. void Laser_base::Disconnect()
  178. {
  179. if (m_ThreadRcv)
  180. {
  181. delete m_ThreadRcv;
  182. m_ThreadRcv = 0;
  183. }
  184. if (m_ThreadPub)
  185. {
  186. delete m_ThreadPub;
  187. m_ThreadPub = 0;
  188. }
  189. if (m_ThreadPro)
  190. {
  191. delete m_ThreadPro;
  192. m_ThreadPro = NULL;
  193. }
  194. m_statu = eLaser_disconnect;
  195. }
  196. //对外的接口函数,负责接受并处理任务单,
  197. //input:laser_task 雷达任务单,必须是子类,并且任务正确。(传引用)
  198. Error_manager Laser_base::execute_task(Task_Base* p_laser_task)
  199. {
  200. return SUCCESS;
  201. }
  202. void Laser_base::SetSaveDir(std::string strDir,bool bSaveFile)
  203. {
  204. m_bSave_file = bSaveFile;
  205. m_pts_log_tool.close();
  206. m_binary_log_tool.close();
  207. if (bSaveFile == false)
  208. return;
  209. m_pts_save_path = strDir;
  210. char pts_file[255] = { 0 };
  211. sprintf(pts_file, "%s/pts%d.txt", strDir.c_str(), m_id+1);
  212. m_pts_log_tool.open(pts_file);
  213. char bin_file[255] = { 0 };
  214. sprintf(bin_file, "%s/laser%d.data", strDir.c_str(), m_id+1);
  215. m_binary_log_tool.open(bin_file,true);
  216. }
  217. void Laser_base::thread_recv()
  218. {
  219. while (m_bThreadRcvRun.WaitFor(1))
  220. {
  221. if (m_bStart_capture.WaitFor(1) == false)
  222. continue;
  223. CBinaryData* data=new CBinaryData();
  224. if (this->RecvData(*data))
  225. {
  226. m_queue_laser_data.push(data);
  227. }
  228. else
  229. {
  230. delete data;
  231. data=0;
  232. }
  233. }
  234. }
  235. CPoint3D Laser_base::transfor(CPoint3D point)
  236. {
  237. if (m_dMatrix)
  238. {
  239. CPoint3D result;
  240. double x = point.x;
  241. double y = point.y;
  242. double z = point.z;
  243. result.x = x * m_dMatrix[0] + y*m_dMatrix[1] + z*m_dMatrix[2] + m_dMatrix[3];
  244. result.y = x * m_dMatrix[4] + y*m_dMatrix[5] + z*m_dMatrix[6] + m_dMatrix[7];
  245. result.z = x * m_dMatrix[8] + y*m_dMatrix[9] + z*m_dMatrix[10] + m_dMatrix[11];
  246. return result;
  247. }
  248. else
  249. {
  250. return point;
  251. }
  252. }
  253. void Laser_base::thread_toXYZ()
  254. {
  255. while (m_bThreadProRun.WaitFor(1))
  256. {
  257. if (m_bStart_capture.WaitFor(1) == false)
  258. {
  259. m_queue_laser_data.clear();
  260. continue;
  261. }
  262. CBinaryData* pData=NULL;
  263. bool bPop = m_queue_laser_data.try_pop(pData);
  264. DATA_type type = eUnknow;
  265. if (bPop || m_last_data.Length() != 0)
  266. {
  267. std::vector<CPoint3D> cloud;
  268. if (bPop)
  269. {
  270. if (pData == NULL)
  271. continue;
  272. m_binary_log_tool.write(pData->Data(), pData->Length());
  273. type= this->Data2PointXYZ(pData, cloud);
  274. }
  275. else
  276. {
  277. type = this->Data2PointXYZ(NULL, cloud);
  278. }
  279. if (type == eUnknow)
  280. {
  281. delete pData;
  282. continue;
  283. }
  284. if (type == eData || type == eStart || type == eStop)
  285. {
  286. for (int i = 0; i < cloud.size(); ++i)
  287. {
  288. CPoint3D point = transfor(cloud[i]);
  289. if(m_bSave_file) {
  290. char buf[64] = {0};
  291. sprintf(buf, "%f %f %f\n", point.x, point.y, point.z);
  292. m_pts_log_tool.write(buf, strlen(buf));
  293. }
  294. //此时cloud为雷达采集数据的结果,转换后的三维点云。
  295. //将每个点存入任务单里面的点云容器。
  296. if(mp_laser_task!=NULL)
  297. {
  298. Error_manager code=mp_laser_task->push_point(pcl::PointXYZ(point.x,point.y,point.z));
  299. }
  300. }
  301. m_points_count+=cloud.size();
  302. if (type == eStop)
  303. {
  304. if(m_bSave_file) {
  305. m_pts_log_tool.close();
  306. m_binary_log_tool.close();
  307. }
  308. m_statu = eLaser_ready;
  309. //在停止雷达时,将雷达任务状态改为 TASK_OVER 已结束
  310. if(mp_laser_task !=NULL)
  311. {
  312. if(mp_laser_task->get_statu() == TASK_WORKING)
  313. {
  314. mp_laser_task->set_task_statu(TASK_OVER);
  315. }
  316. }
  317. }
  318. }
  319. else if (type == eReady)
  320. {
  321. if(m_bSave_file) {
  322. m_pts_log_tool.close();
  323. m_binary_log_tool.close();
  324. }
  325. m_statu = eLaser_ready;
  326. }
  327. delete pData;
  328. }
  329. }
  330. }
  331. #include "unistd.h"
  332. void Laser_base::threadPublish(Laser_base *laser)
  333. {
  334. if(laser==0) return ;
  335. while(laser->m_bThreadRcvRun.WaitFor(1))
  336. {
  337. laser->PublishMsg();
  338. usleep(1000*300);
  339. }
  340. }
  341. void Laser_base::PublishMsg()
  342. {
  343. laser_message::laserMsg msg;
  344. laser_message::laserStatus status;
  345. if(GetStatu()==eLaser_ready) status=laser_message::eLaserConnected;
  346. else if(GetStatu()==eLaser_disconnect) status=laser_message::eLaserDisconnected;
  347. else if(GetStatu()==eLaser_busy) status=laser_message::eLaserBusy;
  348. else status=laser_message::eLaserUnknown;
  349. msg.set_id(m_id);
  350. msg.set_laser_status(status);
  351. msg.set_queue_data_count(m_queue_laser_data.size());
  352. msg.set_cloud_count(m_points_count);
  353. MeasureTopicPublisher::GetInstance()->Publish(msg.SerializeAsString());
  354. }