KinectHelpers.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package VisionX::ArmarXObjects::KinectV2PointCloudProvider
19  * @author Christoph Pohl (christoph dot pohl at kit dot edu)
20  * @date 2019
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
25 
26 #ifndef VISIONX_KINECTHELPERS_H
27 #define VISIONX_KINECTHELPERS_H
28 
29 #include <Eigen/Geometry>
30 
31 #include <pcl/point_cloud.h>
32 #include <pcl/point_types.h>
33 
34 #include <opencv2/opencv.hpp>
35 
37 
38 #include <libfreenect2/libfreenect2.hpp>
39 
40 template <typename PointT>
42 {
43 public:
44  KinectToPCLHelper(const libfreenect2::Freenect2Device::IrCameraParams& depth_p, bool mirror) :
45  mirror_(mirror), qnan_(std::numeric_limits<float>::quiet_NaN())
46  {
47  const int w = 512;
48  const int h = 424;
49  float* pm1 = colmap.data();
50  float* pm2 = rowmap.data();
51  for (int i = 0; i < w; i++)
52  {
53  *pm1++ = (i - depth_p.cx + 0.5) / depth_p.fx;
54  }
55  for (int i = 0; i < h; i++)
56  {
57  *pm2++ = (i - depth_p.cy + 0.5) / depth_p.fy;
58  }
59  }
60 
61  typename pcl::PointCloud<PointT>::Ptr
62  calculatePointCloud(libfreenect2::Frame& undistorted,
63  libfreenect2::Frame& registered,
64  typename pcl::PointCloud<PointT>::Ptr cloud)
65  {
66  const std::size_t w = undistorted.width;
67  const std::size_t h = undistorted.height;
68  cloud->resize(w * h);
69  cv::Mat tmp_itD0(undistorted.height, undistorted.width, CV_32FC1, undistorted.data);
70  cv::Mat tmp_itRGB0(registered.height, registered.width, CV_8UC4, registered.data);
71 
72  if (mirror_)
73  {
74 
75  cv::flip(tmp_itD0, tmp_itD0, 1);
76  cv::flip(tmp_itRGB0, tmp_itRGB0, 1);
77  }
78 
79  const float* itD0 = (float*)tmp_itD0.ptr();
80  const char* itRGB0 = (char*)tmp_itRGB0.ptr();
81 
82  PointT* itP = &cloud->points[0];
83  bool is_dense = true;
84 
85  for (std::size_t y = 0; y < h; ++y)
86  {
87 
88  const unsigned int offset = y * w;
89  const float* itD = itD0 + offset;
90  const char* itRGB = itRGB0 + offset * 4;
91  const float dy = rowmap(y);
93  // bool label = pcl::traits::has_label<PointT>::value;
94  // bool normal = pcl::traits::has_normal<PointT>::value;
95  for (std::size_t x = 0; x < w; ++x, ++itP, ++itD, itRGB += 4)
96  {
97  const float depth_value = *itD / 1000.0;
98  // auto rgb = tmp_itRGB0.at<cv::Vec4b>(y, x);
99 
100  if (!std::isnan(depth_value) && (std::abs(depth_value) >= 0.0001))
101  {
102 
103  const float rx = colmap(x) * depth_value;
104  const float ry = dy * depth_value;
105  itP->z = depth_value;
106  itP->x = rx;
107  itP->y = ry;
108 
109  if (color)
110  {
111  itP->b = itRGB[0];
112  itP->g = itRGB[1];
113  itP->r = itRGB[2];
114  }
115  }
116  else
117  {
118  itP->z = qnan_;
119  itP->x = qnan_;
120  itP->y = qnan_;
121  is_dense = false;
122  }
123  }
124  }
125  cloud->is_dense = is_dense;
126  return cloud;
127  };
128 
129 private:
132  bool mirror_;
133  float qnan_;
134 };
135 
137 {
138  explicit KinectToIVTHelper(bool mirror) : mirror_(mirror){};
139 
140  void
141  calculateImages(libfreenect2::Frame& undistorted,
142  libfreenect2::Frame& registered,
143  CByteImage** rgbImages)
144  {
145  cv::Mat tmp_itD0(undistorted.height, undistorted.width, CV_32FC1, undistorted.data);
146  cv::Mat tmp_itRGB0(registered.height, registered.width, CV_8UC4, registered.data);
147  calculateImages(tmp_itD0, tmp_itRGB0, rgbImages);
148  }
149 
150  void
151  calculateImages(cv::Mat& undistorted, cv::Mat& registered, CByteImage** rgbImages)
152  {
153  if (mirror_)
154  {
155  cv::flip(undistorted, undistorted, 1);
156  cv::flip(registered, registered, 1);
157  }
158  for (int j = 0; j < undistorted.rows; j++)
159  {
160  int index = 3 * (j * undistorted.cols);
161  for (int i = 0; i < undistorted.cols; i++)
162  {
163  float value = undistorted.at<float>(j, i);
164 
166  rgbImages[1]->pixels[index + 0],
167  rgbImages[1]->pixels[index + 1],
168  rgbImages[1]->pixels[index + 2],
169  false);
170 
171  auto v = registered.at<cv::Vec4b>(j, i);
172  for (int k = 0; k < 3; k++)
173  {
174  rgbImages[0]->pixels[index + k] = v[2 - k];
175  }
176  index += 3;
177  }
178  }
179  }
180 
181 private:
182  bool mirror_;
183 };
184 
185 #endif //VISIONX_KINECTHELPERS_H
KinectToIVTHelper::calculateImages
void calculateImages(cv::Mat &undistorted, cv::Mat &registered, CByteImage **rgbImages)
Definition: KinectHelpers.h:151
index
uint8_t index
Definition: EtherCATFrame.h:59
KinectToPCLHelper::calculatePointCloud
pcl::PointCloud< PointT >::Ptr calculatePointCloud(libfreenect2::Frame &undistorted, libfreenect2::Frame &registered, typename pcl::PointCloud< PointT >::Ptr cloud)
Definition: KinectHelpers.h:62
KinectToIVTHelper::calculateImages
void calculateImages(libfreenect2::Frame &undistorted, libfreenect2::Frame &registered, CByteImage **rgbImages)
Definition: KinectHelpers.h:141
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:855
armarx::abs
std::vector< T > abs(const std::vector< T > &v)
Definition: VectorHelpers.h:281
visionx::tools::depthValueToRGB
void depthValueToRGB(unsigned int depthInMM, unsigned char &r, unsigned char &g, unsigned char &b, bool noiseResistant=false)
Definition: ImageUtil.h:183
KinectToIVTHelper::KinectToIVTHelper
KinectToIVTHelper(bool mirror)
Definition: KinectHelpers.h:138
armarx::PointT
pcl::PointXYZRGBL PointT
Definition: Common.h:30
armarx::ctrlutil::v
double v(double t, double v0, double a0, double j)
Definition: CtrlUtil.h:39
float
#define float
Definition: 16_Level.h:22
std
Definition: Application.h:66
KinectToIVTHelper
Definition: KinectHelpers.h:136
KinectToPCLHelper
Definition: KinectHelpers.h:41
ImageUtil.h
Eigen::Matrix< float, 512, 1 >
httplib::Error
Error
Definition: httplib.h:1131
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
KinectToPCLHelper::KinectToPCLHelper
KinectToPCLHelper(const libfreenect2::Freenect2Device::IrCameraParams &depth_p, bool mirror)
Definition: KinectHelpers.h:44