device_tof3d.cpp 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582
  1. #include "device_tof3d.h"
  2. Error_manager DeviceTof3D::Init(const google::protobuf::RepeatedPtrField<tof3dVzenseEtc> &tof_devices) {
  3. LOG(INFO) << "---------- Init DeviceTof3D ----------";
  4. if (tof_devices.size() < DeviceAzimuth::DEVICE_AZIMUTH_MAX) {
  5. return {TOF3D_VZENSE_DEVICE_INIT_FAILED, MAJOR_ERROR, "device numbers is not enough: %d < %d",
  6. tof_devices.size(), DeviceAzimuth::DEVICE_AZIMUTH_MAX};
  7. }
  8. // 使能tof3d相机SDK
  9. auto t_vz_status = VZ_Initialize();
  10. if (t_vz_status != VzReturnStatus::VzRetOK && t_vz_status != VzReturnStatus::VzRetReInitialized) {
  11. return {TOF3D_VZENSE_DEVICE_INIT_FAILED, MAJOR_ERROR, "VzInitialize failed status: %d", t_vz_status};
  12. }
  13. // 注册相机列表
  14. m_devices_list.resize(DeviceAzimuth::DEVICE_AZIMUTH_MAX);
  15. for (auto &device: tof_devices) {
  16. // 校验方位
  17. if (device.azimuth() >= DeviceAzimuth::DEVICE_AZIMUTH_MAX) {
  18. return {ERROR, NORMAL, "azimuth should smaller than %d.", DeviceAzimuth::DEVICE_AZIMUTH_MAX};
  19. }
  20. // 校验方位配置是否出现重复
  21. if (m_devices_list[device.azimuth()].etc == nullptr) {
  22. m_devices_list[device.azimuth()].etc = &device;
  23. } else {
  24. return {ERROR, NORMAL, "device %s id %d is already have the same id device: %s.",
  25. device.ip().c_str(), device.azimuth(), m_devices_list[device.azimuth()].etc->ip().c_str()};
  26. }
  27. }
  28. // 检索相机
  29. if (SearchDevice() != SUCCESS) {
  30. return {ERROR, NORMAL, "search devices failed, please recheck the internet."};
  31. }
  32. // 配置相机列表配置
  33. for (auto &device: m_devices_list) {
  34. if (device.etc->enable_device() && device.handle == nullptr) {
  35. ConnectDevice(device.etc->azimuth());
  36. m_devices_status[device.etc->azimuth()] = 0;
  37. setTof3dParams(device.handle, device.etc->bip());
  38. device.handle_mutex = &all_device_mutex;
  39. device.condit = new Thread_condition();
  40. device.t = new std::thread(&DeviceTof3D::run, this, device.etc->azimuth());
  41. }
  42. }
  43. // 配置自动重连功能
  44. VZ_SetHotPlugStatusCallback(DeviceTof3D::HotPlugStateCallback, this);
  45. // 使能相机列表设备
  46. for (auto &device: m_devices_list) {
  47. if (device.etc->enable_device()) {
  48. device.condit->notify_all(true);
  49. }
  50. }
  51. return {SUCCESS, NORMAL, "VzInitialize success."};
  52. }
  53. Error_manager DeviceTof3D::updateTrans(const DeviceAzimuth &azimuth, const CoordinateTransformation3D &trans) {
  54. rotation_mutex.lock();
  55. rotation_matrix3[azimuth] =
  56. Eigen::AngleAxisf(trans.yaw() * M_PI / 180.f, Eigen::Vector3f::UnitZ()) *
  57. Eigen::AngleAxisf(trans.pitch() * M_PI / 180.f, Eigen::Vector3f::UnitY()) *
  58. Eigen::AngleAxisf(trans.roll() * M_PI / 180.f, Eigen::Vector3f::UnitX());
  59. move[azimuth] << trans.x(), trans.y(), trans.z();
  60. rotation_mutex.unlock();
  61. return {};
  62. }
  63. cv::Mat DeviceTof3D::getDeviceIrMat() {
  64. cv::Mat merge_mat = cv::Mat::zeros(480 * 2, 640 * 2, CV_8UC1);
  65. for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
  66. if (!m_device_mat[device_index].timeout()) {
  67. auto t_device_mat = m_device_mat[device_index]();
  68. // 拼接图像
  69. cv::Mat merge_mat_lf = merge_mat(cv::Rect(0, 0, 640, 480));
  70. t_device_mat.irMat.copyTo(
  71. merge_mat(cv::Rect(
  72. (device_index & 0x1) * t_device_mat.irMat.cols,
  73. ((device_index & 0x2) >> 1) * t_device_mat.irMat.rows,
  74. t_device_mat.irMat.cols,
  75. t_device_mat.irMat.rows)));
  76. } else {
  77. DLOG(WARNING) << device_index << " not get data.";
  78. }
  79. }
  80. return merge_mat;
  81. }
  82. cv::Mat DeviceTof3D::getDevicePointsMat(const DeviceAzimuth &azimuth) {
  83. if (azimuth < DeviceAzimuth::DEVICE_AZIMUTH_MAX && !m_device_mat[azimuth].timeout()) {
  84. return m_device_mat[azimuth]().pointMat;
  85. }
  86. return {};
  87. }
  88. DeviceTof3D::DeviceTof3DSaveInfo DeviceTof3D::getDeviceSaveInfo(const DeviceAzimuth &azimuth) {
  89. return azimuth < DeviceAzimuth::DEVICE_AZIMUTH_MAX ? m_device_mat[azimuth]() : DeviceTof3DSaveInfo{};
  90. }
  91. Error_manager DeviceTof3D::getDeviceStatus() {
  92. for (auto &statu: m_devices_status) {
  93. if (statu() != 0) {
  94. return {FAILED, NORMAL};
  95. }
  96. }
  97. return {};
  98. }
  99. Error_manager DeviceTof3D::SearchDevice(const double &time) {
  100. uint32_t deviceCount = 0;
  101. auto t = std::chrono::steady_clock::now();
  102. std::chrono::duration<double> cost = std::chrono::steady_clock::now() - t;
  103. while (cost.count() < time) {
  104. auto t_vz_status = VZ_GetDeviceCount(&deviceCount);
  105. cost = std::chrono::steady_clock::now() - t;
  106. if (t_vz_status != VzReturnStatus::VzRetOK) {
  107. LOG(INFO) << "VzGetDeviceCount failed! make sure the DCAM is connected";
  108. std::this_thread::sleep_for(std::chrono::seconds(1));
  109. continue;
  110. }
  111. LOG(INFO) << "Found device count: " << deviceCount;
  112. std::this_thread::sleep_for(std::chrono::seconds(1));
  113. // 校验是否含有全部设备
  114. if (isAllDevicesFound(deviceCount)) {
  115. return {SUCCESS, NORMAL};
  116. }
  117. }
  118. return {ERROR, NORMAL, "Can't find all devices in config file."};
  119. }
  120. bool DeviceTof3D::isAllDevicesFound(uint32_t deviceCount) {
  121. // if (deviceCount < DeviceAzimuth::DEVICE_AZIMUTH_MAX) {
  122. // return false;
  123. // }
  124. auto *pDeviceListInfo = new VzDeviceInfo[4];
  125. VZ_GetDeviceInfoList(deviceCount, pDeviceListInfo);
  126. for (auto &device: m_devices_list) {
  127. for (int search_index = 0; search_index < deviceCount; search_index++) {
  128. device.status.found = device.etc->ip() == pDeviceListInfo[search_index].ip;
  129. if (device.status.found) {
  130. break;
  131. }
  132. }
  133. }
  134. for (auto &device: m_devices_list) {
  135. if (device.etc->enable_device() && !device.status.found) {
  136. return false;
  137. }
  138. }
  139. return true;
  140. }
  141. Error_manager DeviceTof3D::setTof3dParams(VzDeviceHandle handle, const Tof3dVzenseBuiltInParams &params) {
  142. if (handle == nullptr) {
  143. LOG(WARNING) << "handle is nullptr!!!";
  144. return {ERROR, CRITICAL_ERROR, "%s handle is nullptr!!!"}; //TODO
  145. }
  146. auto t_vz_status = VZ_SetWorkMode(handle, (VzWorkMode) params.work_mode());
  147. if (t_vz_status != VzReturnStatus::VzRetOK) {
  148. LOG(WARNING) << " VZ_SetWorkMode failed status:" << t_vz_status;
  149. return {}; //TODO
  150. }
  151. t_vz_status = VZ_SetIRGMMGain(handle, params.irgmmgain());
  152. if (t_vz_status != VzReturnStatus::VzRetOK) {
  153. LOG(WARNING) << " VZ_SetIRGMMGain failed status:" << t_vz_status;
  154. return {}; //TODO
  155. }
  156. t_vz_status = VZ_SetFrameRate(handle, params.frame_rate());
  157. if (t_vz_status != VzReturnStatus::VzRetOK) {
  158. LOG(WARNING) << " VZ_SetFrameRate failed status:" << t_vz_status;
  159. return {}; //TODO
  160. }
  161. VzExposureTimeParams exposure_param;
  162. exposure_param.mode = (VzExposureControlMode) params.enable_manual_exposure_time();
  163. exposure_param.exposureTime = params.exposure_time();
  164. t_vz_status = VZ_SetExposureTime(handle, VzToFSensor, exposure_param);
  165. if (t_vz_status != VzReturnStatus::VzRetOK) {
  166. LOG(WARNING) << " VZ_SetExposureTime failed status:" << t_vz_status;
  167. return {}; //TODO
  168. }
  169. t_vz_status = VZ_SetFillHoleFilterEnabled(handle, params.enable_filter_fill_hole());
  170. if (t_vz_status != VzReturnStatus::VzRetOK) {
  171. LOG(WARNING) << " VZ_SetFillHoleFilterEnabled failed status:" << t_vz_status;
  172. return {}; //TODO
  173. }
  174. t_vz_status = VZ_SetSpatialFilterEnabled(handle, params.enable_filter_spatial());
  175. if (t_vz_status != VzReturnStatus::VzRetOK) {
  176. LOG(WARNING) << " VZ_SetSpatialFilterEnabled failed status:" << t_vz_status;
  177. return {}; //TODO
  178. }
  179. VzFlyingPixelFilterParams fly;
  180. fly.enable = params.enable_flying_pixel_filter();
  181. fly.threshold = params.flying_pixel_filter_value();
  182. t_vz_status = VZ_SetFlyingPixelFilterParams(handle, fly);
  183. if (t_vz_status != VzReturnStatus::VzRetOK) {
  184. LOG(WARNING) << " VZ_SetFlyingPixelFilterParams failed status:" << t_vz_status;
  185. return {}; //TODO
  186. }
  187. VzConfidenceFilterParams confidence;
  188. confidence.enable = params.enable_confidence_filter();
  189. confidence.threshold = params.confidence_filter_value();
  190. t_vz_status = VZ_SetConfidenceFilterParams(handle, confidence);
  191. if (t_vz_status != VzReturnStatus::VzRetOK) {
  192. LOG(WARNING) << " VZ_SetConfidenceFilterParams failed status:" << t_vz_status;
  193. return {}; //TODO
  194. }
  195. VzTimeFilterParams time_filter;
  196. time_filter.enable = params.enable_time_filter();
  197. time_filter.threshold = params.time_filter_value();
  198. t_vz_status = VZ_SetTimeFilterParams(handle, time_filter);
  199. if (t_vz_status != VzReturnStatus::VzRetOK) {
  200. LOG(WARNING) << " VZ_SetTimeFilterParams failed status:" << t_vz_status;
  201. return {}; //TODO
  202. }
  203. return Error_manager();
  204. }
  205. Error_manager DeviceTof3D::getTof3dParams(VzDeviceHandle handle, Tof3dVzenseBuiltInParams &params) {
  206. if (handle == nullptr) {
  207. LOG(WARNING) << "handle is nullptr!!!";
  208. return {ERROR, CRITICAL_ERROR, "%s handle is nullptr!!!"}; //TODO
  209. }
  210. // 获取参数
  211. VzWorkMode mode;
  212. auto t_vz_status = VZ_GetWorkMode(handle, &mode);
  213. if (t_vz_status != VzReturnStatus::VzRetOK) {
  214. LOG(WARNING) << " VZ_GetWorkMode failed status:" << t_vz_status;
  215. return {}; //TODO
  216. }
  217. params.set_work_mode(mode);
  218. uint8_t irgmmgain;
  219. t_vz_status = VZ_GetIRGMMGain(handle, &irgmmgain);
  220. if (t_vz_status != VzReturnStatus::VzRetOK) {
  221. LOG(WARNING) << " VZ_GetIRGMMGain failed status:" << t_vz_status;
  222. return {}; //TODO
  223. }
  224. params.set_irgmmgain(irgmmgain);
  225. int frame_rate;
  226. t_vz_status = VZ_GetFrameRate(handle, &frame_rate);
  227. if (t_vz_status != VzReturnStatus::VzRetOK) {
  228. LOG(WARNING) << " VZ_GetFrameRate failed status:" << t_vz_status;
  229. return {}; //TODO
  230. }
  231. params.set_frame_rate(frame_rate);
  232. VzExposureTimeParams exposure_param = {VzExposureControlMode_Manual, 0};
  233. t_vz_status = VZ_GetProperty(handle, "Py_ToFExposureTimeMax", &exposure_param,
  234. sizeof(exposure_param));
  235. if (t_vz_status != VzReturnStatus::VzRetOK) {
  236. LOG(WARNING) << " VZ_GetExposureTime failed status:" << t_vz_status;
  237. return {}; //TODO
  238. }
  239. params.set_enable_manual_exposure_time(exposure_param.mode);
  240. params.set_exposure_time(exposure_param.exposureTime);
  241. bool boolret;
  242. t_vz_status = VZ_GetFillHoleFilterEnabled(handle, &boolret);
  243. if (t_vz_status != VzReturnStatus::VzRetOK) {
  244. LOG(WARNING) << " VZ_GetFillHoleFilterEnabled failed status:" << t_vz_status;
  245. return {}; //TODO
  246. }
  247. params.set_enable_filter_fill_hole(boolret);
  248. t_vz_status = VZ_GetSpatialFilterEnabled(handle, &boolret);
  249. if (t_vz_status != VzReturnStatus::VzRetOK) {
  250. LOG(WARNING) << " VZ_GetSpatialFilterEnabled failed status:" << t_vz_status;
  251. return {}; //TODO
  252. }
  253. params.set_enable_filter_spatial(boolret);
  254. VzFlyingPixelFilterParams fly;
  255. t_vz_status = VZ_GetFlyingPixelFilterParams(handle, &fly);
  256. if (t_vz_status != VzReturnStatus::VzRetOK) {
  257. LOG(WARNING) << " VZ_GetFlyingPixelFilterParams failed status:" << t_vz_status;
  258. return {}; //TODO
  259. }
  260. params.set_enable_flying_pixel_filter(fly.enable);
  261. params.set_flying_pixel_filter_value(fly.threshold);
  262. VzConfidenceFilterParams confidence;
  263. t_vz_status = VZ_GetConfidenceFilterParams(handle, &confidence);
  264. if (t_vz_status != VzReturnStatus::VzRetOK) {
  265. LOG(WARNING) << " VZ_GetConfidenceFilterParams failed status:" << t_vz_status;
  266. return {}; //TODO
  267. }
  268. params.set_enable_confidence_filter(confidence.enable);
  269. params.set_confidence_filter_value(confidence.threshold);
  270. VzTimeFilterParams time_filter;
  271. t_vz_status = VZ_GetTimeFilterParams(handle, &time_filter);
  272. if (t_vz_status != VzReturnStatus::VzRetOK) {
  273. LOG(WARNING) << " VZ_GetTimeFilterParams failed status:" << t_vz_status;
  274. return {}; //TODO
  275. }
  276. params.set_enable_time_filter(time_filter.enable);
  277. params.set_time_filter_value(time_filter.threshold);
  278. return Error_manager();
  279. }
  280. Error_manager DeviceTof3D::ConnectDevice(const DeviceAzimuth &azimuth) {
  281. auto &device = m_devices_list[azimuth];
  282. auto t_vz_status = VZ_OpenDeviceByIP(device.etc->ip().c_str(), &device.handle);
  283. if (t_vz_status != VzReturnStatus::VzRetOK) {
  284. device.status.connected = false;
  285. LOG(WARNING) << "OpenDevice " << device.etc->ip() << " failed status:" << t_vz_status;
  286. return {ERROR, NORMAL};
  287. } else {
  288. device.status.connected = true;
  289. LOG(INFO) << "OpenDevice " << device.etc->ip() << " success status:" << t_vz_status;
  290. }
  291. t_vz_status = VZ_StartStream(device.handle);
  292. if (t_vz_status != VzReturnStatus::VzRetOK) {
  293. LOG(WARNING) << "VZ_StartStream " << device.etc->ip() << " failed status:" << t_vz_status;
  294. return {ERROR, NORMAL};
  295. } else {
  296. LOG(INFO) << "VZ_StartStream " << device.etc->ip() << " success status:" << t_vz_status;
  297. }
  298. return {};
  299. }
  300. Error_manager DeviceTof3D::DisConnectDevice(VzDeviceHandle handle) {
  301. if (handle == nullptr) {
  302. return {ERROR, CRITICAL_ERROR};
  303. }
  304. auto t_vz_status = VZ_StopStream(handle);
  305. if (t_vz_status != VzReturnStatus::VzRetOK) {
  306. LOG(WARNING) << "VZ_StopStream failed status:" << t_vz_status;
  307. } else {
  308. LOG(INFO) << "VZ_StopStream success status:" << t_vz_status;
  309. }
  310. t_vz_status = VZ_CloseDevice(&handle);
  311. if (t_vz_status != VzReturnStatus::VzRetOK) {
  312. LOG(WARNING) << "VZ_CloseDevice failed status:" << t_vz_status;
  313. } else {
  314. LOG(INFO) << "VZ_CloseDevice success status:" << t_vz_status;
  315. }
  316. return {};
  317. }
  318. Error_manager DeviceTof3D::getDepthAndIrPicture(VzDeviceHandle handle, VzFrame &depthFrame, VzFrame &irFrame) {
  319. if (handle == nullptr) {
  320. return {ERROR, CRITICAL_ERROR};
  321. }
  322. Error_manager ret;
  323. VzFrameReady frameReady = {0};
  324. auto t_vz_status = VZ_GetFrameReady(handle, 200, &frameReady);
  325. if (t_vz_status != VzRetOK) {
  326. DLOG(WARNING) << "Device VZ_GetFrameReady failed status:" << t_vz_status;
  327. return {FAILED, MINOR_ERROR, "Device VZ_GetFrameReady failed status: %d.", t_vz_status}; //TODO
  328. }
  329. if (1 == frameReady.depth) {
  330. t_vz_status = VZ_GetFrame(handle, VzDepthFrame, &depthFrame);
  331. if (t_vz_status == VzRetOK && depthFrame.pFrameData != nullptr) {
  332. // LOG(INFO) << ip << " frameIndex :" << depthFrame.frameIndex;
  333. } else {
  334. LOG(INFO) << "Device VZ_GetFrame VzIrFrame failed status: " << t_vz_status;
  335. return {FAILED, MINOR_ERROR, "Device VZ_GetFrame VzIrFrame failed status: %d.", t_vz_status};
  336. }
  337. } else {
  338. return {FAILED, MINOR_ERROR, "Device VZ_GetFrameReady depth not ready: %d.", frameReady.depth};
  339. }
  340. if (1 == frameReady.ir) {
  341. t_vz_status = VZ_GetFrame(handle, VzIRFrame, &irFrame);
  342. if (t_vz_status == VzRetOK && irFrame.pFrameData != nullptr) {
  343. // LOG(INFO) << ip << " frameIndex :" << irFrame.frameIndex;
  344. } else {
  345. LOG(INFO) << "VZ_GetFrame VzIrFrame status:" << t_vz_status;
  346. return {FAILED, MINOR_ERROR, "Device VZ_GetFrame VzIrFrame failed status: %d.", t_vz_status};
  347. }
  348. } else {
  349. return {FAILED, NORMAL, "Device VZ_GetFrameReady ir not ready."};
  350. }
  351. return ret;
  352. }
  353. Error_manager DeviceTof3D::DepthFrame2Mat(VzFrame &frame, cv::Mat &mat) {
  354. if (frame.frameType != VzDepthFrame) {
  355. return {};
  356. }
  357. if (mat.type() != CV_16UC1) {
  358. LOG(INFO) << "Mat type " << mat.type() << " not is " << CV_16UC1;
  359. return {};
  360. }
  361. if (mat.rows != 480 || mat.cols != 640) {
  362. LOG(INFO) << "Mat size (" << mat.rows << ", " << mat.cols << ") not is (480, 640)";
  363. return {};
  364. }
  365. memcpy(mat.data, frame.pFrameData, frame.dataLen);
  366. mat.convertTo(mat, CV_8U, 255.0 / 7495);
  367. applyColorMap(mat, mat, cv::COLORMAP_RAINBOW);
  368. return {};
  369. }
  370. Error_manager DeviceTof3D::IrFrame2Mat(VzFrame &frame, cv::Mat &mat) {
  371. if (frame.frameType != VzIRFrame) {
  372. return {};
  373. }
  374. if (mat.type() != CV_8UC1) {
  375. LOG(INFO) << "Mat type " << mat.type() << " not is " << CV_8UC1;
  376. return {};
  377. }
  378. if (mat.rows != 480 || mat.cols != 640) {
  379. LOG(INFO) << "Mat size (" << mat.rows << ", " << mat.cols << ") not is (480, 640)";
  380. return {};
  381. }
  382. memcpy(mat.data, frame.pFrameData, frame.dataLen);
  383. return {};
  384. }
  385. Error_manager DeviceTof3D::Frame2Mat(VzFrame &frame, cv::Mat &mat) {
  386. switch (frame.frameType) {
  387. case VzDepthFrame:
  388. return DepthFrame2Mat(frame, mat);
  389. case VzIRFrame:
  390. return IrFrame2Mat(frame, mat);
  391. default:
  392. break;
  393. }
  394. return {};
  395. }
  396. void DeviceTof3D::HotPlugStateCallback(const VzDeviceInfo *pInfo, int status, void *contex) {
  397. LOG(WARNING) << "ip " << pInfo->ip << " " << (status == 0 ? "add" : "remove");
  398. if (contex == nullptr) {
  399. LOG(WARNING) << contex << " contex is nullptr.";
  400. return;
  401. }
  402. DeviceTof3D *pDeviceTof3D = (DeviceTof3D *) contex;
  403. for (int device_index = 0; device_index < pDeviceTof3D->m_devices_list.size(); device_index++) {
  404. // LOG(INFO) << device_index << " " << &pDeviceTof3D->m_devices_list[device_index] << " " << pDeviceTof3D->m_devices_list[device_index].etc->ip();
  405. pDeviceTof3D->m_devices_list[device_index].handle_mutex->lock();
  406. if (pDeviceTof3D->m_devices_list[device_index].etc->ip() == pInfo->ip) {
  407. if (status == 0) {
  408. LOG(WARNING) << pInfo->ip << " VZ_OpenDevice "
  409. << VZ_OpenDeviceByUri(pInfo->uri, &pDeviceTof3D->m_devices_list[device_index].handle);
  410. LOG(WARNING) << pInfo->ip << " VZ_StartStream "
  411. << VZ_StartStream(pDeviceTof3D->m_devices_list[device_index].handle);
  412. } else {
  413. LOG(WARNING) << pInfo->ip << " VZ_StopStream "
  414. << VZ_StopStream(pDeviceTof3D->m_devices_list[device_index].handle);
  415. LOG(WARNING) << pInfo->ip << " VZ_CloseDevice "
  416. << VZ_CloseDevice(&pDeviceTof3D->m_devices_list[device_index].handle);
  417. }
  418. pDeviceTof3D->m_devices_status[device_index] = status;
  419. }
  420. pDeviceTof3D->m_devices_list[device_index].handle_mutex->unlock();
  421. }
  422. }
  423. void DeviceTof3D::run(const DeviceAzimuth &azimuth) {
  424. auto &device = m_devices_list[azimuth];
  425. cv::Mat t_ir_img;
  426. cv::Mat t_point_img;
  427. VzFrame depthFrame = {0};
  428. VzFrame irFrame = {0};
  429. VzVector3f *worldV = new VzVector3f[480 * 640];
  430. auto t_start_time = std::chrono::steady_clock::now();
  431. std::chrono::duration<double> cost = std::chrono::steady_clock::now() - t_start_time;
  432. LOG(INFO) << device.etc->ip() << ": " << azimuth << " in thread " << std::this_thread::get_id();
  433. updateTrans(azimuth, device.etc->trans());
  434. while (device.condit->is_alive()) {
  435. device.condit->wait();
  436. cost = std::chrono::steady_clock::now() - t_start_time;
  437. std::this_thread::sleep_for(std::chrono::milliseconds(100 - std::min<int>(99, cost.count() * 1000)));
  438. t_start_time = std::chrono::steady_clock::now();
  439. if (device.condit->is_alive()) {
  440. Error_manager ret;
  441. DeviceTof3DSaveInfo depthInfo;
  442. Error_manager vz_ret = {FAILED, NORMAL};
  443. device.handle_mutex->lock();
  444. if (device.handle) {
  445. vz_ret = getDepthAndIrPicture(device.handle, depthFrame, irFrame);
  446. if (vz_ret == SUCCESS) {
  447. VZ_ConvertDepthFrameToPointCloudVector(device.handle, &depthFrame, worldV);
  448. } else {
  449. ret.compare_and_merge_up(
  450. {FAILED, MINOR_ERROR, "Device %s VZ_GetFrame failed.", device.etc->ip().c_str()});
  451. }
  452. }
  453. device.handle_mutex->unlock();
  454. if (vz_ret == SUCCESS) {
  455. // 灰度图转换
  456. Frame2Mat(irFrame, depthInfo.irMat);
  457. // 点云转换
  458. for (int cols = 0; cols < depthInfo.pointMat.cols - 0; cols++) {
  459. for (int rows = 0; rows < depthInfo.pointMat.rows - 0; rows++) {
  460. int i = rows * depthInfo.pointMat.cols + cols;
  461. if (sqrt(worldV[i].x * worldV[i].x + worldV[i].y * worldV[i].y + worldV[i].z * worldV[i].z) *
  462. 0.001f > 5) {
  463. continue;
  464. }
  465. Eigen::Vector3f trans;
  466. trans << worldV[i].x * 0.001f, worldV[i].y * 0.001f, worldV[i].z * 0.001f;
  467. trans = rotation_matrix3[azimuth] * trans + move[azimuth];
  468. if (trans(2) < 0.03 || fabs(trans(0)) > 1.5 || fabs(trans(1)) > 2.7 || trans(2) > 1) {
  469. continue;
  470. }
  471. depthInfo.pointMat.at<cv::Vec4f>(rows, cols)[0] = trans(0);
  472. depthInfo.pointMat.at<cv::Vec4f>(rows, cols)[1] = trans(1);
  473. depthInfo.pointMat.at<cv::Vec4f>(rows, cols)[2] = trans(2);
  474. }
  475. }
  476. // 将图片和点云存储起来
  477. t_ir_img = depthInfo.irMat.clone();
  478. t_point_img = depthInfo.pointMat.clone();
  479. TransitData::get_instance_pointer()->setImage(t_ir_img, azimuth);
  480. TransitData::get_instance_pointer()->setImageCL(t_point_img, azimuth);
  481. m_device_mat[azimuth] = depthInfo;
  482. }
  483. } else {
  484. LOG_EVERY_N(WARNING, 1000) << device.etc->ip() << " device handle is null.";
  485. }
  486. }
  487. LOG(INFO) << device.etc->ip() << " thread end " << std::this_thread::get_id();
  488. }
  489. void DeviceTof3D::stop() {
  490. for (auto &device: m_devices_list) {
  491. DisConnectDevice(device.handle);
  492. device.condit->kill_all();
  493. device.t->join();
  494. delete device.t;
  495. delete device.condit;
  496. device.t = nullptr;
  497. device.t = nullptr;
  498. }
  499. }