device_tof3d.cpp 22 KB

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