device_tof3d.cpp 33 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857
  1. #include "device_tof3d.h"
  2. Error_manager DeviceTof3D::Init(const VzEtcMap &tp_tof3d, bool search) {
  3. LOG(INFO) << "Init DeviceTof3D.";
  4. m_vz_status = VZ_Initialize();
  5. if (m_vz_status != VzReturnStatus::VzRetOK && m_vz_status != VzReturnStatus::VzRetReInitialized) {
  6. return {TOF3D_VZENSE_DEVICE_INIT_FAILED, MAJOR_ERROR, "VzInitialize failed status: %d", m_vz_status};
  7. }
  8. #ifdef ENABLE_TENSORRT_DETECT
  9. detector = new TensorrtWheelDetector(ETC_PATH PROJECT_NAME "/model.engine", ETC_PATH PROJECT_NAME "/class.txt");
  10. #else
  11. detector = new TensorrtWheelDetector(ETC_PATH PROJECT_NAME "/model.onnx", ETC_PATH PROJECT_NAME "/class.txt");
  12. #endif
  13. loadEtc(tp_tof3d);
  14. if (search) {
  15. SearchDevice(5);
  16. }
  17. cv::namedWindow("ret", cv::WINDOW_AUTOSIZE);
  18. ConnectAllEtcDevices();
  19. VZ_SetHotPlugStatusCallback(DeviceTof3D::HotPlugStateCallback, &mp_device_info);
  20. //启动 线程。
  21. for (auto &info: mp_device_info) {
  22. if (!info.second->etc.enable_device()) {
  23. continue;
  24. }
  25. setTof3dParams(info.second->etc.ip());
  26. getTof3dParams(info.second->etc.ip());
  27. mp_thread_info.insert(std::pair<std::string, ThreadInfo>(
  28. info.first, ThreadInfo(new std::thread(&DeviceTof3D::receiveFrameThread, this, info.first),
  29. new Thread_condition()
  30. )
  31. ));
  32. }
  33. for (auto &t: mp_thread_info) {
  34. t.second.condit->notify_all(true);
  35. }
  36. detect_thread.t = new std::thread(&DeviceTof3D::detectThread, this);
  37. detect_thread.condit = new Thread_condition();
  38. detect_thread.condit->notify_all(true);
  39. return {TOF3D_VZENSE_DEVICE_INIT_SUCCESS, NORMAL, "VzInitialize success."};
  40. }
  41. Error_manager DeviceTof3D::SearchDevice(const double &time) {
  42. uint32_t deviceCount = 0;
  43. auto t = std::chrono::steady_clock::now();
  44. std::chrono::duration<double> cost = std::chrono::steady_clock::now() - t;
  45. while (cost.count() < time) {
  46. m_vz_status = VZ_GetDeviceCount(&deviceCount);
  47. cost = std::chrono::steady_clock::now() - t;
  48. if (m_vz_status != VzReturnStatus::VzRetOK) {
  49. LOG(INFO) << "VzGetDeviceCount failed! make sure the DCAM is connected";
  50. std::this_thread::sleep_for(std::chrono::seconds(1));
  51. continue;
  52. }
  53. std::this_thread::sleep_for(std::chrono::seconds(1));
  54. LOG(INFO) << "Found device count: " << deviceCount;
  55. }
  56. VzDeviceInfo *pDeviceListInfo = new VzDeviceInfo[deviceCount];
  57. m_vz_status = VZ_GetDeviceInfoList(deviceCount, pDeviceListInfo);
  58. if (m_vz_status != VzReturnStatus::VzRetOK) {
  59. LOG(INFO) << "GetDeviceListInfo failed status:" << m_vz_status;
  60. return {}; //TODO
  61. } else {
  62. for (int i = 0; i < deviceCount; i++) {
  63. auto iter = mp_device_info.find(pDeviceListInfo[i].ip);
  64. if (iter == mp_device_info.end()) {
  65. mp_device_info.insert(
  66. std::pair<std::string, tof3dVzenseInfo *>(pDeviceListInfo[i].ip, new tof3dVzenseInfo()));
  67. iter = mp_device_info.find(pDeviceListInfo[i].ip);
  68. }
  69. iter->second->info = pDeviceListInfo[i];
  70. LOG(INFO) << "Found device: " << pDeviceListInfo[i].ip;
  71. }
  72. }
  73. return {};
  74. }
  75. Error_manager DeviceTof3D::ConnectDevice(const std::string &ip, bool open_stream) {
  76. auto iter = mp_device_info.find(ip);
  77. if (iter == mp_device_info.end()) {
  78. LOG(WARNING) << "Can\'t find " << ip << " in mp_device_info";
  79. return {}; //TODO
  80. }
  81. m_vz_status = VZ_OpenDeviceByIP(iter->second->info.ip, &iter->second->handle);
  82. if (m_vz_status != VzReturnStatus::VzRetOK) {
  83. iter->second->is_connect = false;
  84. LOG(WARNING) << "OpenDevice " << ip << " failed status:" << m_vz_status;
  85. return {}; //TODO
  86. } else {
  87. iter->second->is_connect = true;
  88. LOG(INFO) << "OpenDevice " << ip << " success status:" << m_vz_status;
  89. }
  90. if (open_stream) {
  91. m_vz_status = VZ_StartStream(iter->second->handle);
  92. if (m_vz_status != VzReturnStatus::VzRetOK) {
  93. iter->second->is_start_stream = false;
  94. LOG(WARNING) << "VZ_StartStream " << ip << " failed status:" << m_vz_status;
  95. return {};
  96. } else {
  97. iter->second->is_start_stream = true;
  98. LOG(INFO) << "VZ_StartStream " << ip << " success status:" << m_vz_status;
  99. }
  100. }
  101. return {};
  102. }
  103. Error_manager DeviceTof3D::ConnectAllEtcDevices(bool open_stream) {
  104. for (auto &device: mp_device_info) {
  105. if (device.second->etc.enable_device()) {
  106. ConnectDevice(device.first, open_stream);
  107. }
  108. }
  109. return {};
  110. }
  111. Error_manager DeviceTof3D::ConnectAllDevices(bool open_stream) {
  112. for (auto &device: mp_device_info) {
  113. ConnectDevice(device.first, open_stream);
  114. }
  115. return {};
  116. }
  117. Error_manager DeviceTof3D::DisConnectDevice(const std::string &ip) {
  118. auto iter = mp_device_info.find(ip);
  119. if (iter == mp_device_info.end()) {
  120. return {}; //TODO
  121. }
  122. m_vz_status = VZ_StopStream(iter->second->handle);
  123. if (m_vz_status != VzReturnStatus::VzRetOK) {
  124. iter->second->is_start_stream = true;
  125. LOG(WARNING) << "VZ_StopStream failed status:" << m_vz_status;
  126. } else {
  127. iter->second->is_start_stream = false;
  128. LOG(INFO) << "VZ_StopStream success status:" << m_vz_status;
  129. }
  130. m_vz_status = VZ_CloseDevice(&iter->second->handle);
  131. if (m_vz_status != VzReturnStatus::VzRetOK) {
  132. iter->second->is_connect = true;
  133. LOG(WARNING) << "VZ_CloseDevice failed status:" << m_vz_status;
  134. } else {
  135. iter->second->is_connect = false;
  136. LOG(INFO) << "VZ_CloseDevice success status:" << m_vz_status;
  137. }
  138. return {};
  139. }
  140. Error_manager DeviceTof3D::DisConnectAllEtcDevices() {
  141. for (auto &device: mp_device_info) {
  142. if (device.second->etc.enable_device()) {
  143. DisConnectDevice(device.first);
  144. }
  145. }
  146. return {};
  147. }
  148. Error_manager DeviceTof3D::DisConnectAllDevices() {
  149. for (auto &device: mp_device_info) {
  150. DisConnectDevice(device.first);
  151. }
  152. return {};
  153. }
  154. Error_manager DeviceTof3D::getDepthFrame(const std::string &ip, VzFrame &depthFrame) {
  155. auto iter = mp_device_info.find(ip);
  156. if (iter == mp_device_info.end()) {
  157. return {FAILED, NORMAL, "Device %s not in list, can\'t get depth frame.", ip.c_str()}; //TODO
  158. }
  159. if (iter->second->handle == nullptr || !iter->second->is_connect) {
  160. if (ConnectDevice(ip, true) != SUCCESS) {
  161. return {FAILED, NORMAL, "Open device %s failed, stop get depth frame.", ip.c_str()};
  162. }
  163. }
  164. VzFrameReady frameReady = {0};
  165. m_vz_status = VZ_GetFrameReady(iter->second->handle, iter->second->etc.bip().exposure_time(), &frameReady);
  166. if (m_vz_status != VzRetOK) {
  167. LOG(WARNING) << ip << " VZ_GetFrameReady failed status:" << m_vz_status;
  168. return {FAILED, MINOR_ERROR, "%s VZ_GetFrameReady failed status %d!", ip.c_str(), m_vz_status}; //TODO
  169. }
  170. if (1 == frameReady.depth) {
  171. m_vz_status = VZ_GetFrame(iter->second->handle, VzDepthFrame, &depthFrame);
  172. if (m_vz_status == VzRetOK && depthFrame.pFrameData != nullptr) {
  173. // LOG(INFO) << ip << " VZ_GetFrame VzDepthFrame success:" << m_vz_status;
  174. } else {
  175. LOG(INFO) << ip << " VZ_GetFrame VzDepthFrame failed:" << m_vz_status;
  176. }
  177. }
  178. return {};
  179. }
  180. Error_manager DeviceTof3D::getIrFrame(const std::string &ip, VzFrame &irFrame) {
  181. auto iter = mp_device_info.find(ip);
  182. if (iter == mp_device_info.end()) {
  183. return {FAILED, NORMAL, "Device %s not in list, can\'t get ir frame.", ip.c_str()}; //TODO
  184. }
  185. if (iter->second->handle == nullptr || !iter->second->is_connect) {
  186. if (ConnectDevice(ip, true) != SUCCESS) {
  187. return {FAILED, NORMAL, "Open device %s failed, stop get ir frame.", ip.c_str()};
  188. }
  189. }
  190. VzFrameReady frameReady = {0};
  191. m_vz_status = VZ_GetFrameReady(iter->second->handle, 100, &frameReady);
  192. if (m_vz_status != VzRetOK) {
  193. LOG(WARNING) << ip << " VZ_GetFrameReady failed status:" << m_vz_status;
  194. return {}; //TODO
  195. }
  196. if (1 == frameReady.ir) {
  197. m_vz_status = VZ_GetFrame(iter->second->handle, VzIRFrame, &irFrame);
  198. if (m_vz_status == VzRetOK && irFrame.pFrameData != nullptr) {
  199. LOG(INFO) << ip << "VZ_GetFrame VzIrFrame success:" << m_vz_status;
  200. } else {
  201. LOG(INFO) << ip << "VZ_GetFrame VzIrFrame failed:" << m_vz_status;
  202. }
  203. }
  204. return {};
  205. }
  206. Error_manager DeviceTof3D::getDepthAndIrPicture(const std::string &ip, VzFrame &depthFrame, VzFrame &irFrame) {
  207. auto iter = mp_device_info.find(ip);
  208. if (iter == mp_device_info.end()) {
  209. return {FAILED, NORMAL, "Device %s not in list, can\'t get depth and ir frame.", ip.c_str()}; //TODO
  210. }
  211. if (iter->second->handle == nullptr || !iter->second->is_connect) {
  212. if (ConnectDevice(ip, true) != SUCCESS) {
  213. return {FAILED, NORMAL, "Open device %s failed, stop get depth and ir frame.", ip.c_str()};
  214. }
  215. }
  216. Error_manager ret;
  217. VzFrameReady frameReady = {0};
  218. m_vz_status = VZ_GetFrameReady(iter->second->handle, 100, &frameReady);
  219. if (m_vz_status != VzRetOK) {
  220. LOG(WARNING) << ip << " VZ_GetFrameReady failed status:" << m_vz_status;
  221. ret.compare_and_merge_up({FAILED, MINOR_ERROR, "Device %s VZ_GetFrameReady failed status: %d.", ip.c_str(),
  222. m_vz_status}); //TODO
  223. return ret;
  224. }
  225. //Get depth frame, depth frame only output in following data mode
  226. if (1 == frameReady.depth) {
  227. m_vz_status = VZ_GetFrame(iter->second->handle, VzDepthFrame, &depthFrame);
  228. if (m_vz_status == VzRetOK && depthFrame.pFrameData != nullptr) {
  229. LOG(INFO) << ip << " frameIndex :" << depthFrame.frameIndex;
  230. } else {
  231. ret.compare_and_merge_up(
  232. {FAILED, MINOR_ERROR, "Device %s VZ_GetFrame VzIrFrame failed status: %d.", ip.c_str(),
  233. m_vz_status}); //TODO
  234. LOG(INFO) << ip << "VZ_GetFrame VzIrFrame status:" << m_vz_status;
  235. }
  236. } else {
  237. ret.compare_and_merge_up(
  238. {FAILED, MINOR_ERROR, "Device %s VZ_GetFrameReady depth not ready: %d.", ip.c_str(), frameReady.depth});
  239. }
  240. if (1 == frameReady.ir) {
  241. m_vz_status = VZ_GetFrame(iter->second->handle, VzIRFrame, &irFrame);
  242. if (m_vz_status == VzRetOK && irFrame.pFrameData != nullptr) {
  243. LOG(INFO) << ip << " frameIndex :" << irFrame.frameIndex;
  244. } else {
  245. ret.compare_and_merge_up(
  246. {FAILED, MINOR_ERROR, "Device %s VZ_GetFrame VzIrFrame failed status: %d.", ip.c_str(),
  247. m_vz_status}); //TODO
  248. LOG(INFO) << ip << "VZ_GetFrame VzIrFrame status:" << m_vz_status;
  249. }
  250. } else {
  251. ret.compare_and_merge_up(
  252. {FAILED, NORMAL, "Device %s VZ_GetFrameReady ir not ready: %d.", ip.c_str(), frameReady.depth});
  253. }
  254. return ret;
  255. }
  256. Error_manager DeviceTof3D::getDepthPointCloud(const std::string &ip, pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud) {
  257. auto iter = mp_device_info.find(ip);
  258. if (iter == mp_device_info.end()) {
  259. return {FAILED, NORMAL, "Device %s not in list, can\'t get point cloud.", ip.c_str()}; //TODO
  260. }
  261. if (iter->second->handle == nullptr || !iter->second->is_connect) {
  262. if (ConnectDevice(ip, true) != SUCCESS) {
  263. return {FAILED, NORMAL, "Open device %s failed, stop get point cloud.", ip.c_str()};
  264. }
  265. }
  266. VzFrameReady frameReady = {0};
  267. m_vz_status = VZ_GetFrameReady(iter->second->handle, 100, &frameReady);
  268. if (m_vz_status != VzRetOK) {
  269. LOG(WARNING) << ip << " VZ_GetFrameReady failed status:" << m_vz_status;
  270. return {}; //TODO
  271. }
  272. //Get depth frame, depth frame only output in following data mode
  273. if (1 == frameReady.depth) {
  274. VzFrame depthFrame = {0};
  275. m_vz_status = VZ_GetFrame(iter->second->handle, VzDepthFrame, &depthFrame);
  276. if (m_vz_status == VzRetOK && depthFrame.pFrameData != nullptr) {
  277. LOG(INFO) << ip << " frameIndex :" << depthFrame.frameIndex;
  278. VzFrame &srcFrame = depthFrame;
  279. const int len = srcFrame.width * srcFrame.height;
  280. VzVector3f *worldV = new VzVector3f[len];
  281. m_vz_status = VZ_ConvertDepthFrameToPointCloudVector(iter->second->handle, &srcFrame,
  282. worldV);
  283. if (m_vz_status == VzRetOK) {
  284. cloud->clear();
  285. for (int i = 0; i < len; i++) {
  286. if (worldV[i].x == 0 && worldV[i].y == 0 && worldV[i].z == 0) {
  287. continue;
  288. }
  289. cloud->points.emplace_back(worldV[i].x, worldV[i].y, worldV[i].z);
  290. }
  291. delete[] worldV;
  292. worldV = nullptr;
  293. LOG(INFO) << "Save point cloud successful to cloud: " << cloud->size();
  294. }
  295. } else {
  296. LOG(INFO) << ip << "VZ_GetFrame VzIrFrame status:" << m_vz_status;
  297. }
  298. }
  299. return {};
  300. }
  301. Error_manager DeviceTof3D::DepthFrame2PointCloud(const std::string &ip, VzFrame &depthFrame,
  302. pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud) {
  303. // if (depthFrame.frameType != VzDepthFrame) {
  304. // return {};
  305. // }
  306. //
  307. // auto handle_iter = mp_devices_handle.find(ip);
  308. // if (handle_iter == mp_devices_handle.end()) {
  309. // return {}; //TODO
  310. // }
  311. //
  312. // cloud->clear();
  313. // if (handle_iter->second) {
  314. //
  315. // VzFrame &srcFrame = depthFrame;
  316. // const int len = srcFrame.width * srcFrame.height;
  317. // VzVector3f *worldV = new VzVector3f[len];
  318. //
  319. // VZ_ConvertDepthFrameToPointCloudVector(handle_iter->second, &depthFrame, worldV);
  320. //
  321. // for (int i = 0; i < len; i++) {
  322. // cloud->points.emplace_back(worldV[i].x, worldV[i].y, worldV[i].z);
  323. // }
  324. // delete[] worldV;
  325. // worldV = nullptr;
  326. // LOG(INFO) << "Save point cloud successful to cloud: " << cloud->size();
  327. // WriteTxtCloud(ETC_PATH"Tof3d/data/cloud.txt", cloud);
  328. // }
  329. return {};
  330. }
  331. Error_manager DeviceTof3D::Frame2Mat(VzFrame &frame, cv::Mat &mat) {
  332. switch (frame.frameType) {
  333. case VzDepthFrame:
  334. return DepthFrame2Mat(frame, mat);
  335. case VzIRFrame:
  336. return IrFrame2Mat(frame, mat);
  337. default:
  338. break;
  339. }
  340. return {};
  341. }
  342. Error_manager DeviceTof3D::DepthFrame2Mat(VzFrame &frame, cv::Mat &mat) {
  343. if (frame.frameType != VzDepthFrame) {
  344. return {};
  345. }
  346. if (mat.type() != CV_16UC1) {
  347. LOG(INFO) << "Mat type " << mat.type() << " not is " << CV_16UC1;
  348. return {};
  349. }
  350. if (mat.rows != 480 || mat.cols != 640) {
  351. LOG(INFO) << "Mat size (" << mat.rows << ", " << mat.cols << ") not is (480, 640)";
  352. return {};
  353. }
  354. memcpy(mat.data, frame.pFrameData, frame.dataLen);
  355. mat.convertTo(mat, CV_8U, 255.0 / 7495);
  356. applyColorMap(mat, mat, cv::COLORMAP_RAINBOW);
  357. return {};
  358. }
  359. Error_manager DeviceTof3D::IrFrame2Mat(VzFrame &frame, cv::Mat &mat) {
  360. if (frame.frameType != VzIRFrame) {
  361. return {};
  362. }
  363. if (mat.type() != CV_8UC1) {
  364. LOG(INFO) << "Mat type " << mat.type() << " not is " << CV_8UC1;
  365. return {};
  366. }
  367. if (mat.rows != 480 || mat.cols != 640) {
  368. LOG(INFO) << "Mat size (" << mat.rows << ", " << mat.cols << ") not is (480, 640)";
  369. return {};
  370. }
  371. memcpy(mat.data, frame.pFrameData, frame.dataLen);
  372. return {};
  373. }
  374. #include <sys/stat.h>
  375. void DeviceTof3D::receiveFrameThread(const std::string &ip) {
  376. LOG(INFO) << ip << " in thread " << std::this_thread::get_id();
  377. auto iter = mp_device_info.find(ip);
  378. auto t_iter = mp_thread_info.find(ip);
  379. pcl::PointCloud<pcl::PointXYZ>::Ptr t_car_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  380. pcl::PointCloud<pcl::PointXYZ>::Ptr t_wheel_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  381. std::vector<Object> segment_results;
  382. while (t_iter->second.condit->is_alive()) {
  383. t_iter->second.condit->wait();
  384. if (t_iter->second.condit->is_alive()) {
  385. Error_manager ret;
  386. if (iter->second->handle) {
  387. t_car_cloud->clear();
  388. t_wheel_cloud->clear();
  389. VzFrame depthFrame = {0};
  390. cv::Mat depthMat(480, 640, CV_16UC1);
  391. if (getDepthFrame(ip, depthFrame) == SUCCESS) {
  392. segment_results.clear();
  393. if (Frame2Mat(depthFrame, depthMat) == SUCCESS) {
  394. detector->detect(depthMat, segment_results);
  395. // cv::imshow("ret", depthMat);
  396. // cv::waitKey(100);
  397. }
  398. std::vector<cv::Point> mat_seg_ret;
  399. for (auto &result: segment_results) {
  400. if (result.prob > 0.5) {
  401. mat_seg_ret = detector->getPointsFromObj(result);
  402. for (auto &pt: mat_seg_ret) {
  403. depthMat.at<uchar>(pt) = 255 - depthMat.at<uchar>(pt);
  404. }
  405. cv::imshow("ret", depthMat);
  406. cv::waitKey(1);
  407. }
  408. }
  409. if (!mat_seg_ret.empty()) {
  410. segFrame2CarAndWheel(depthFrame, mat_seg_ret, t_car_cloud, t_wheel_cloud);
  411. // viewer.removeAllPointClouds(view_port[0]);
  412. // viewer.removeAllPointClouds(view_port[1]);
  413. // viewer.addPointCloud(t_car_cloud, "car_cloud_", view_port[0]);
  414. // viewer.addPointCloud(t_wheel_cloud, "wheel_cloud_", view_port[1]);
  415. // viewer.spinOnce();
  416. }
  417. } else {
  418. ret.compare_and_merge_up({FAILED, MINOR_ERROR, "Device %s VZ_GetFrame failed.", ip.c_str()});
  419. }
  420. } else {
  421. ret.compare_and_merge_up({FAILED, MINOR_ERROR, "Device %s handle is null.", ip.c_str()});
  422. }
  423. if (!ret.get_error_description().empty()) {
  424. LOG(INFO) << ret.get_error_description();
  425. }
  426. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  427. }
  428. }
  429. DisConnectDevice(ip);
  430. LOG(INFO) << ip << " thread end " << std::this_thread::get_id();
  431. }
  432. #include <pcl/visualization/pcl_visualizer.h>
  433. void DeviceTof3D::detectThread() {
  434. LOG(INFO) << "detect thread running in " << std::this_thread::get_id();
  435. int view_port[2];
  436. pcl::visualization::PCLVisualizer viewer("viewer_0");
  437. viewer.createViewPort(0.0, 0.0, 0.5, 1, view_port[0]);
  438. viewer.createViewPort(0.5, 0.0, 1, 1, view_port[1]);
  439. viewer.addText("car_cloud", 10, 10, 20, 0, 1, 0, "car_cloud", view_port[0]);
  440. viewer.addText("wheel_cloud", 10, 10, 20, 0, 1, 0, "wheel_cloud", view_port[1]);
  441. viewer.addCoordinateSystem(1, "car_axis", view_port[0]);
  442. viewer.addCoordinateSystem(1, "wheel_axis", view_port[1]);
  443. pcl::PointCloud<pcl::PointXYZ>::Ptr t_car_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  444. pcl::PointCloud<pcl::PointXYZ>::Ptr t_wheel_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  445. auto t_start_time = std::chrono::steady_clock::now();
  446. std::chrono::duration<double> cost = std::chrono::steady_clock::now() - t_start_time;
  447. while (detect_thread.condit->is_alive()) {
  448. // detect_thread.condit->wait();
  449. t_car_cloud->clear();
  450. t_wheel_cloud->clear();
  451. cost = std::chrono::steady_clock::now() - t_start_time;
  452. std::this_thread::sleep_for(std::chrono::milliseconds((int) MAX(100 - cost.count() * 1000, 1)));
  453. t_start_time = std::chrono::steady_clock::now();
  454. // LOG(INFO) << "last wheel cost time is " << cost.count() * 1000 << " ms";
  455. if (detect_thread.condit->is_alive()) {
  456. // cost = std::chrono::steady_clock::now() - t_start_time;
  457. // LOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
  458. if (!t_car_cloud->empty() && !t_wheel_cloud->empty()) {
  459. CarPoseOptimize(t_car_cloud);
  460. WheelCloudOptimize(t_wheel_cloud);
  461. }
  462. }
  463. }
  464. LOG(INFO) << "detect thread " << std::this_thread::get_id() << " closed.";
  465. }
  466. void DeviceTof3D::HotPlugStateCallback(const VzDeviceInfo *pInfo, int status, void *contex) {
  467. LOG(WARNING) << "uri " << status << " " << pInfo->uri << " " << (status == 0 ? "add" : "remove");
  468. LOG(WARNING) << "alia " << status << " " << pInfo->alias << " " << (status == 0 ? "add" : "remove");
  469. if (contex == nullptr) {
  470. return;
  471. }
  472. tof3dVzenseInfoMap *mp = (tof3dVzenseInfoMap *) contex;
  473. auto iter = mp->find(pInfo->ip);
  474. LOG(INFO) << iter->first;
  475. if (status == 0) {
  476. LOG(WARNING) << "VZ_OpenDevice " << VZ_OpenDeviceByUri(pInfo->uri, &iter->second->handle);
  477. LOG(WARNING) << "VZ_StartStream " << VZ_StartStream(iter->second->handle);
  478. iter->second->is_connect = true;
  479. iter->second->is_start_stream = true;
  480. } else {
  481. LOG(WARNING) << "VZ_StopStream " << VZ_StopStream(iter->second->handle);
  482. LOG(WARNING) << "VZ_CloseDevice " << VZ_CloseDevice(&iter->second->handle);
  483. iter->second->is_connect = false;
  484. iter->second->is_start_stream = false;
  485. }
  486. }
  487. bool DeviceTof3D::drawBox(cv::Mat &mat, cv::Rect &box, cv::Scalar &color, std::string className, float confidence) {
  488. // Detection box
  489. cv::rectangle(mat, box, color, 2);
  490. // Detection box text
  491. std::string classString = className + ' ' + std::to_string(confidence).substr(0, 4);
  492. cv::Size textSize = cv::getTextSize(classString, cv::FONT_HERSHEY_DUPLEX, 1, 2, 0);
  493. cv::Rect textBox(box.x, box.y - 40, textSize.width + 10, textSize.height + 20);
  494. cv::rectangle(mat, textBox, color, cv::FILLED);
  495. cv::putText(mat, classString, cv::Point(box.x + 5, box.y - 10), cv::FONT_HERSHEY_DUPLEX, 1, cv::Scalar(0, 0, 0), 2,
  496. 0);
  497. return true;
  498. }
  499. Error_manager DeviceTof3D::updateTof3dEtc() {
  500. for (auto &info: mp_device_info) {
  501. if (info.second->etc.enable_device()) {
  502. }
  503. }
  504. return Error_manager();
  505. }
  506. Error_manager DeviceTof3D::loadEtc(const DeviceTof3D::VzEtcMap &etc) {
  507. for (auto &iter: etc) {
  508. tof3dVzenseInfo *info = new tof3dVzenseInfo();
  509. info->etc = iter.second;
  510. mp_device_info.insert(std::pair<std::string, tof3dVzenseInfo *>(iter.first, info));
  511. LOG(INFO) << "Get device " << iter.first << " etc: " << iter.second.DebugString();
  512. }
  513. return Error_manager();
  514. }
  515. void DeviceTof3D::stopWorking() {
  516. for (auto &info: mp_device_info) {
  517. auto iter = mp_thread_info.find(info.second->etc.ip());
  518. if (iter != mp_thread_info.end()) {
  519. iter->second.condit->kill_all();
  520. iter->second.t->join();
  521. delete iter->second.t;
  522. iter->second.t = nullptr;
  523. }
  524. }
  525. mp_device_info.clear();
  526. mp_thread_info.clear();
  527. }
  528. Error_manager DeviceTof3D::reInit(const VzEtcMap &etc) {
  529. LOG(INFO) << "================= Reinit Device Tof3D.";
  530. stopWorking();
  531. Error_manager ret = Init(etc, true);
  532. return ret;
  533. }
  534. Error_manager DeviceTof3D::setTof3dParams(const std::string &ip) {
  535. auto iter = mp_device_info.find(ip);
  536. if (iter == mp_device_info.end()) {
  537. LOG(WARNING) << "Can\'t find " << ip << " in mp_device_info";
  538. return {}; //TODO
  539. }
  540. m_vz_status = VZ_SetWorkMode(iter->second->handle, (VzWorkMode) iter->second->etc.bip().work_mode());
  541. if (m_vz_status != VzReturnStatus::VzRetOK) {
  542. LOG(WARNING) << ip << " VZ_SetWorkMode failed status:" << m_vz_status;
  543. return {}; //TODO
  544. }
  545. m_vz_status = VZ_SetIRGMMGain(iter->second->handle, iter->second->etc.bip().irgmmgain());
  546. if (m_vz_status != VzReturnStatus::VzRetOK) {
  547. LOG(WARNING) << ip << " VZ_SetIRGMMGain failed status:" << m_vz_status;
  548. return {}; //TODO
  549. }
  550. m_vz_status = VZ_SetFrameRate(iter->second->handle, iter->second->etc.bip().frame_rate());
  551. if (m_vz_status != VzReturnStatus::VzRetOK) {
  552. LOG(WARNING) << ip << " VZ_SetFrameRate failed status:" << m_vz_status;
  553. return {}; //TODO
  554. }
  555. VzExposureTimeParams exposure_param;
  556. exposure_param.mode = (VzExposureControlMode) iter->second->etc.bip().enable_manual_exposure_time();
  557. exposure_param.exposureTime = iter->second->etc.bip().exposure_time();
  558. m_vz_status = VZ_SetExposureTime(iter->second->handle, VzToFSensor, exposure_param);
  559. if (m_vz_status != VzReturnStatus::VzRetOK) {
  560. LOG(WARNING) << ip << " VZ_SetExposureTime failed status:" << m_vz_status;
  561. return {}; //TODO
  562. }
  563. m_vz_status = VZ_SetFillHoleFilterEnabled(iter->second->handle, iter->second->etc.bip().enable_filter_fill_hole());
  564. if (m_vz_status != VzReturnStatus::VzRetOK) {
  565. LOG(WARNING) << ip << " VZ_SetFillHoleFilterEnabled failed status:" << m_vz_status;
  566. return {}; //TODO
  567. }
  568. m_vz_status = VZ_SetSpatialFilterEnabled(iter->second->handle, iter->second->etc.bip().enable_filter_spatial());
  569. if (m_vz_status != VzReturnStatus::VzRetOK) {
  570. LOG(WARNING) << ip << " VZ_SetSpatialFilterEnabled failed status:" << m_vz_status;
  571. return {}; //TODO
  572. }
  573. VzFlyingPixelFilterParams fly;
  574. fly.enable = iter->second->etc.bip().enable_flying_pixel_filter();
  575. fly.threshold = iter->second->etc.bip().flying_pixel_filter_value();
  576. m_vz_status = VZ_SetFlyingPixelFilterParams(iter->second->handle, fly);
  577. if (m_vz_status != VzReturnStatus::VzRetOK) {
  578. LOG(WARNING) << ip << " VZ_SetFlyingPixelFilterParams failed status:" << m_vz_status;
  579. return {}; //TODO
  580. }
  581. VzConfidenceFilterParams confidence;
  582. confidence.enable = iter->second->etc.bip().enable_confidence_filter();
  583. confidence.threshold = iter->second->etc.bip().confidence_filter_value();
  584. m_vz_status = VZ_SetConfidenceFilterParams(iter->second->handle, confidence);
  585. if (m_vz_status != VzReturnStatus::VzRetOK) {
  586. LOG(WARNING) << ip << " VZ_SetConfidenceFilterParams failed status:" << m_vz_status;
  587. return {}; //TODO
  588. }
  589. VzTimeFilterParams time_filter;
  590. time_filter.enable = iter->second->etc.bip().enable_time_filter();
  591. time_filter.threshold = iter->second->etc.bip().time_filter_value();
  592. m_vz_status = VZ_SetTimeFilterParams(iter->second->handle, time_filter);
  593. if (m_vz_status != VzReturnStatus::VzRetOK) {
  594. LOG(WARNING) << ip << " VZ_SetTimeFilterParams failed status:" << m_vz_status;
  595. return {}; //TODO
  596. }
  597. return Error_manager();
  598. }
  599. Error_manager DeviceTof3D::getTof3dParams(const std::string &ip) {
  600. auto iter = mp_device_info.find(ip);
  601. if (iter == mp_device_info.end()) {
  602. LOG(WARNING) << "Can\'t find " << ip << " in mp_device_info";
  603. return {}; //TODO
  604. }
  605. // 获取参数
  606. VzWorkMode mode;
  607. m_vz_status = VZ_GetWorkMode(iter->second->handle, &mode);
  608. if (m_vz_status != VzReturnStatus::VzRetOK) {
  609. LOG(WARNING) << ip << " VZ_GetWorkMode failed status:" << m_vz_status;
  610. return {}; //TODO
  611. }
  612. iter->second->etc.mutable_bip()->set_work_mode(mode);
  613. uint8_t irgmmgain;
  614. m_vz_status = VZ_GetIRGMMGain(iter->second->handle, &irgmmgain);
  615. if (m_vz_status != VzReturnStatus::VzRetOK) {
  616. LOG(WARNING) << ip << " VZ_GetIRGMMGain failed status:" << m_vz_status;
  617. return {}; //TODO
  618. }
  619. iter->second->etc.mutable_bip()->set_irgmmgain(irgmmgain);
  620. int frame_rate;
  621. m_vz_status = VZ_GetFrameRate(iter->second->handle, &frame_rate);
  622. if (m_vz_status != VzReturnStatus::VzRetOK) {
  623. LOG(WARNING) << ip << " VZ_GetFrameRate failed status:" << m_vz_status;
  624. return {}; //TODO
  625. }
  626. iter->second->etc.mutable_bip()->set_frame_rate(frame_rate);
  627. VzExposureTimeParams exposure_param = {VzExposureControlMode_Manual, 0};
  628. m_vz_status = VZ_GetProperty(iter->second->handle, "Py_ToFExposureTimeMax", &exposure_param,
  629. sizeof(exposure_param));
  630. if (m_vz_status != VzReturnStatus::VzRetOK) {
  631. LOG(WARNING) << ip << " VZ_GetExposureTime failed status:" << m_vz_status;
  632. return {}; //TODO
  633. }
  634. iter->second->etc.mutable_bip()->set_enable_manual_exposure_time(exposure_param.mode);
  635. iter->second->etc.mutable_bip()->set_exposure_time(exposure_param.exposureTime);
  636. bool boolret;
  637. m_vz_status = VZ_GetFillHoleFilterEnabled(iter->second->handle, &boolret);
  638. if (m_vz_status != VzReturnStatus::VzRetOK) {
  639. LOG(WARNING) << ip << " VZ_GetFillHoleFilterEnabled failed status:" << m_vz_status;
  640. return {}; //TODO
  641. }
  642. iter->second->etc.mutable_bip()->set_enable_filter_fill_hole(boolret);
  643. m_vz_status = VZ_GetSpatialFilterEnabled(iter->second->handle, &boolret);
  644. if (m_vz_status != VzReturnStatus::VzRetOK) {
  645. LOG(WARNING) << ip << " VZ_GetSpatialFilterEnabled failed status:" << m_vz_status;
  646. return {}; //TODO
  647. }
  648. iter->second->etc.mutable_bip()->set_enable_filter_spatial(boolret);
  649. VzFlyingPixelFilterParams fly;
  650. m_vz_status = VZ_GetFlyingPixelFilterParams(iter->second->handle, &fly);
  651. if (m_vz_status != VzReturnStatus::VzRetOK) {
  652. LOG(WARNING) << ip << " VZ_GetFlyingPixelFilterParams failed status:" << m_vz_status;
  653. return {}; //TODO
  654. }
  655. iter->second->etc.mutable_bip()->set_enable_flying_pixel_filter(fly.enable);
  656. iter->second->etc.mutable_bip()->set_flying_pixel_filter_value(fly.threshold);
  657. VzConfidenceFilterParams confidence;
  658. m_vz_status = VZ_GetConfidenceFilterParams(iter->second->handle, &confidence);
  659. if (m_vz_status != VzReturnStatus::VzRetOK) {
  660. LOG(WARNING) << ip << " VZ_GetConfidenceFilterParams failed status:" << m_vz_status;
  661. return {}; //TODO
  662. }
  663. iter->second->etc.mutable_bip()->set_enable_confidence_filter(confidence.enable);
  664. iter->second->etc.mutable_bip()->set_confidence_filter_value(confidence.threshold);
  665. VzTimeFilterParams time_filter;
  666. m_vz_status = VZ_GetTimeFilterParams(iter->second->handle, &time_filter);
  667. if (m_vz_status != VzReturnStatus::VzRetOK) {
  668. LOG(WARNING) << ip << " VZ_GetTimeFilterParams failed status:" << m_vz_status;
  669. return {}; //TODO
  670. }
  671. iter->second->etc.mutable_bip()->set_enable_time_filter(time_filter.enable);
  672. iter->second->etc.mutable_bip()->set_time_filter_value(time_filter.threshold);
  673. return Error_manager();
  674. }
  675. Error_manager DeviceTof3D::segFrame2CarAndWheel(VzFrame &depth_frame, std::vector<cv::Point> &wheel_cv_cloud,
  676. pcl::PointCloud<pcl::PointXYZ>::Ptr &car_cloud,
  677. pcl::PointCloud<pcl::PointXYZ>::Ptr &wheel_cloud) {
  678. auto iter = mp_device_info.find("192.168.2.102");
  679. if (iter->second->handle != nullptr) {
  680. VzSensorIntrinsicParameters cameraParam = {};
  681. VZ_GetSensorIntrinsicParameters(iter->second->handle, VzToFSensor, &cameraParam);
  682. const uint16_t *pDepthFrameData = (uint16_t *) depth_frame.pFrameData;
  683. for (auto &pt: wheel_cv_cloud) {
  684. VzDepthVector3 depthPoint = {pt.x, pt.y, pDepthFrameData[pt.y * depth_frame.width + pt.x]};
  685. VzVector3f worldV = {};
  686. VZ_ConvertDepthToPointCloud(iter->second->handle, &depthPoint, &worldV, 1, &cameraParam);
  687. wheel_cloud->emplace_back(worldV.x, worldV.y, worldV.z);
  688. }
  689. LOG(INFO) << wheel_cloud->size();
  690. VzFrame &srcFrame = depth_frame;
  691. const int len = srcFrame.width * srcFrame.height;
  692. VzVector3f *worldV = new VzVector3f[len];
  693. m_vz_status = VZ_ConvertDepthFrameToPointCloudVector(iter->second->handle, &srcFrame,
  694. worldV);
  695. if (m_vz_status == VzRetOK) {
  696. car_cloud->clear();
  697. for (int i = 0; i < len; i++) {
  698. if (worldV[i].x == 0 && worldV[i].y == 0 && worldV[i].z == 0) {
  699. continue;
  700. }
  701. car_cloud->points.emplace_back(worldV[i].x, worldV[i].y, worldV[i].z);
  702. }
  703. delete[] worldV;
  704. worldV = nullptr;
  705. LOG(INFO) << "Save point cloud successful to cloud: " << car_cloud->size();
  706. }
  707. // for (int i = (depth_frame.height - WINDOW_SIZE)/2, offset = i * depth_frame.width; i < (depth_frame.height + WINDOW_SIZE)/2; i++)
  708. // {
  709. // for (int j = (depth_frame.width - WINDOW_SIZE)/2; j < (depth_frame.width + WINDOW_SIZE)/2; j++)
  710. // {
  711. // VzDepthVector3 depthPoint = {j, i, pDepthFrameData[offset + j]};
  712. // VzVector3f worldV = {};
  713. // VZ_ConvertDepthToPointCloud(iter->second->handle, &depthPoint, &worldV, 1, &cameraParam);
  714. // if (0 < worldV.z && worldV.z < 0xFFFF)
  715. // {
  716. // LOG(INFO) << worldV.x << "\t" << worldV.y << "\t" << worldV.z << std::endl;
  717. // }
  718. // }
  719. // offset += depth_frame.width;
  720. // }
  721. }
  722. return Error_manager();
  723. }
  724. Error_manager DeviceTof3D::WheelCloudOptimize(pcl::PointCloud<pcl::PointXYZ>::Ptr &wheel_cloud) {
  725. return Error_manager();
  726. }
  727. Error_manager DeviceTof3D::CarPoseOptimize(pcl::PointCloud<pcl::PointXYZ>::Ptr &car_cloud) {
  728. return Error_manager();
  729. }