device_tof3d.cpp 33 KB

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