rs-kinfu.cpp
Go to the documentation of this file.
1 
2 #include <opencv2/imgproc.hpp>
3 #include <opencv2/rgbd/kinfu.hpp>
4 
5 #include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
6 #include <example.hpp> // Include short list of convenience functions for rendering
7 
8 #include <thread>
9 #include <queue>
10 #include <atomic>
11 #include <fstream>
12 
13 using namespace cv;
14 using namespace cv::kinfu;
15 
16 static float max_dist = 2.5;
17 static float min_dist = 0;
18 
19 
20 // Assigns an RGB value for each point in the pointcloud, based on the depth value
21 void colorize_pointcloud(const Mat points, Mat& color)
22 {
23  // Define a vector of 3 Mat arrays which will hold the channles of points
24  std::vector<Mat> channels(points.channels());
25  split(points, channels);
26  // Get the depth channel which we'll use to colorize the pointcloud
27  color = channels[2];
28 
29  // Convert the depth matrix to unsigned char values
30  float min = min_dist;
31  float max = max_dist;
32  color.convertTo(color, CV_8UC1, 255 / (max - min), -255 * min / (max - min));
33  // Get an rgb value for each point
34  applyColorMap(color, color, COLORMAP_JET);
35 }
36 
37 // Handles all the OpenGL calls needed to display the point cloud
38 void draw_kinfu_pointcloud(glfw_state& app_state, Mat points, Mat normals)
39 {
40  // Define new matrix which will later hold the coloring of the pointcloud
41  Mat color;
42  colorize_pointcloud(points, color);
43 
44  // OpenGL commands that prep screen for the pointcloud
47 
48  glClearColor(153.f / 255, 153.f / 255, 153.f / 255, 1);
50 
52  glPushMatrix();
53  gluPerspective(65, 1.3, 0.01f, 10.0f);
54 
56  glPushMatrix();
57  gluLookAt(0, 0, 0, 0, 0, 1, 0, -1, 0);
58 
59  glTranslatef(0, 0, 1 + app_state.offset_y*0.05f);
60  glRotated(app_state.pitch-20, 1, 0, 0);
61  glRotated(app_state.yaw+5, 0, 1, 0);
62  glTranslatef(0, 0, -0.5f);
63 
69  // this segment actually prints the pointcloud
70  for (int i = 0; i < points.rows; i++)
71  {
72  // Get point coordinates from 'points' matrix
73  float x = points.at<float>(i, 0);
74  float y = points.at<float>(i, 1);
75  float z = points.at<float>(i, 2);
76 
77  // Get point coordinates from 'normals' matrix
78  float nx = normals.at<float>(i, 0);
79  float ny = normals.at<float>(i, 1);
80  float nz = normals.at<float>(i, 2);
81 
82  // Get the r, g, b values for the current point
83  uchar r = color.at<uchar>(i, 0);
84  uchar g = color.at<uchar>(i, 1);
85  uchar b = color.at<uchar>(i, 2);
86 
87  // Register color and coordinates of the current point
88  glColor3ub(r, g, b);
89  glNormal3f(nx, ny, nz);
90  glVertex3f(x, y, z);
91  }
92  // OpenGL cleanup
93  glEnd();
94  glPopMatrix();
96  glPopMatrix();
97  glPopAttrib();
98 }
99 
100 
101 void export_to_ply(Mat points, Mat normals)
102 {
103  // First generate a filename
104  const size_t buffer_size = 50;
105  char fname[buffer_size];
106  time_t t = time(0); // get time now
107  struct tm * now = localtime(&t);
108  strftime(fname, buffer_size, "%m%d%y %H%M%S.ply", now);
109  std::cout << "exporting to" << fname << std::endl;
110 
111  // Get rgb values for points
112  Mat color;
113  colorize_pointcloud(points, color);
114 
115  // Write the ply file
116  std::ofstream out(fname);
117  out << "ply\n";
118  out << "format binary_little_endian 1.0\n";
119  out << "comment pointcloud saved from Realsense Viewer\n";
120  out << "element vertex " << points.rows << "\n";
121  out << "property float" << sizeof(float) * 8 << " x\n";
122  out << "property float" << sizeof(float) * 8 << " y\n";
123  out << "property float" << sizeof(float) * 8 << " z\n";
124 
125  out << "property float" << sizeof(float) * 8 << " nx\n";
126  out << "property float" << sizeof(float) * 8 << " ny\n";
127  out << "property float" << sizeof(float) * 8 << " nz\n";
128 
129  out << "property uchar red\n";
130  out << "property uchar green\n";
131  out << "property uchar blue\n";
132  out << "end_header\n";
133  out.close();
134 
135  out.open(fname, std::ios_base::app | std::ios_base::binary);
136  for (int i = 0; i < points.rows; i++)
137  {
138  // write vertices
139  out.write(reinterpret_cast<const char*>(&(points.at<float>(i, 0))), sizeof(float));
140  out.write(reinterpret_cast<const char*>(&(points.at<float>(i, 1))), sizeof(float));
141  out.write(reinterpret_cast<const char*>(&(points.at<float>(i, 2))), sizeof(float));
142 
143  // write normals
144  out.write(reinterpret_cast<const char*>(&(normals.at<float>(i, 0))), sizeof(float));
145  out.write(reinterpret_cast<const char*>(&(normals.at<float>(i, 1))), sizeof(float));
146  out.write(reinterpret_cast<const char*>(&(normals.at<float>(i, 2))), sizeof(float));
147 
148  // write colors
149  out.write(reinterpret_cast<const char*>(&(color.at<uchar>(i, 0))), sizeof(uint8_t));
150  out.write(reinterpret_cast<const char*>(&(color.at<uchar>(i, 1))), sizeof(uint8_t));
151  out.write(reinterpret_cast<const char*>(&(color.at<uchar>(i, 2))), sizeof(uint8_t));
152  }
153 }
154 
155 
156 // Thread-safe queue for OpenCV's Mat objects
158 {
159 public:
160  void push(Mat& item)
161  {
162  std::lock_guard<std::mutex> lock(_mtx);
163  queue.push(item);
164  }
165  int try_get_next_item(Mat& item)
166  {
167  std::lock_guard<std::mutex> lock(_mtx);
168  if (queue.empty())
169  return false;
170  item = std::move(queue.front());
171  queue.pop();
172  return true;
173  }
174 private:
175  std::queue<Mat> queue;
176  std::mutex _mtx;
177 };
178 
179 
180 int main(int argc, char **argv)
181 {
182  // Declare KinFu and params pointers
183  Ptr<KinFu> kf;
184  Ptr<Params> params = Params::defaultParams();
185 
186  // Create a pipeline and configure it
189  float depth_scale;
191  auto profile = p.start(cfg);
192  auto dev = profile.get_device();
193  auto stream_depth = profile.get_stream(RS2_STREAM_DEPTH);
194 
195  // Get a new frame from the camera
197  auto d = data.get_depth_frame();
198 
199  for (rs2::sensor& sensor : dev.query_sensors())
200  {
202  {
203  // Set some presets for better results
205  // Depth scale is needed for the kinfu set-up
206  depth_scale = dpt.get_depth_scale();
207  break;
208  }
209  }
210 
211  // Declare post-processing filters for better results
212  auto decimation = rs2::decimation_filter();
213  auto spatial = rs2::spatial_filter();
214  auto temporal = rs2::temporal_filter();
215 
216  auto clipping_dist = max_dist / depth_scale; // convert clipping_dist to raw depth units
217 
218  // Use decimation once to get the final size of the frame
219  d = decimation.process(d);
220  auto w = d.get_width();
221  auto h = d.get_height();
222  Size size = Size(w, h);
223 
224  auto intrin = stream_depth.as<rs2::video_stream_profile>().get_intrinsics();
225 
226  // Configure kinfu's parameters
227  params->frameSize = size;
228  params->intr = Matx33f(intrin.fx, 0, intrin.ppx,
229  0, intrin.fy, intrin.ppy,
230  0, 0, 1);
231  params->depthFactor = 1 / depth_scale;
232 
233  // Initialize KinFu object
234  kf = KinFu::create(params);
235 
236  bool after_reset = false;
237  mat_queue points_queue;
238  mat_queue normals_queue;
239 
240  window app(1280, 720, "RealSense KinectFusion Example");
241  glfw_state app_state;
242  register_glfw_callbacks(app, app_state);
243 
244  std::atomic_bool stopped(false);
245 
246  // This thread runs KinFu algorithm and calculates the pointcloud by fusing depth data from subsequent depth frames
247  std::thread calc_cloud_thread([&]() {
248  Mat _points;
249  Mat _normals;
250  try {
251  while (!stopped)
252  {
253  rs2::frameset data = p.wait_for_frames(); // Wait for next set of frames from the camera
254 
255  auto d = data.get_depth_frame();
256  // Use post processing to improve results
257  d = decimation.process(d);
258  d = spatial.process(d);
259  d = temporal.process(d);
260 
261  // Set depth values higher than clipping_dist to 0, to avoid unnecessary noise in the pointcloud
262  uint16_t* p_depth_frame = reinterpret_cast<uint16_t*>(const_cast<void*>(d.get_data()));
263 #pragma omp parallel for schedule(dynamic) //Using OpenMP to try to parallelise the loop
264  for (int y = 0; y < h; y++)
265  {
266  auto depth_pixel_index = y * w;
267  for (int x = 0; x < w; x++, ++depth_pixel_index)
268  {
269  // Check if the depth value of the current pixel is greater than the threshold
270  if (p_depth_frame[depth_pixel_index] > clipping_dist)
271  {
272  p_depth_frame[depth_pixel_index] = 0;
273  }
274  }
275  }
276 
277  // Define matrices on the GPU for KinFu's use
278  UMat points;
279  UMat normals;
280  // Copy frame from CPU to GPU
281  Mat f(h, w, CV_16UC1, (void*)d.get_data());
282  UMat frame(h, w, CV_16UC1);
283  f.copyTo(frame);
284  f.release();
285 
286  // Run KinFu on the new frame(on GPU)
287  if (!kf->update(frame))
288  {
289  kf->reset(); // If the algorithm failed, reset current state
290  // Save the pointcloud obtained before failure
291  export_to_ply(_points, _normals);
292 
293  // To avoid calculating pointcloud before new frames were processed, set 'after_reset' to 'true'
294  after_reset = true;
295  points.release();
296  normals.release();
297  std::cout << "reset" << std::endl;
298  }
299 
300  // Get current pointcloud
301  if (!after_reset)
302  {
303  kf->getCloud(points, normals);
304  }
305 
306  if (!points.empty() && !normals.empty())
307  {
308  // copy points from GPU to CPU for rendering
309  points.copyTo(_points);
310  points.release();
311  normals.copyTo(_normals);
312  normals.release();
313  // Push to queue for rendering
314  points_queue.push(_points);
315  normals_queue.push(_normals);
316  }
317  after_reset = false;
318  }
319  }
320  catch (const std::exception& e) // Save pointcloud in case an error occurs (for example, camera disconnects)
321  {
322  export_to_ply(_points, _normals);
323  }
324  });
325 
326  // Main thread handles rendering of the pointcloud
327  Mat points;
328  Mat normals;
329  while (app)
330  {
331  // Get the current state of the pointcloud
332  points_queue.try_get_next_item(points);
333  normals_queue.try_get_next_item(normals);
334  if (!points.empty() && !normals.empty()) // points or normals might not be ready on first iterations
335  draw_kinfu_pointcloud(app_state, points, normals);
336  }
337  stopped = true;
338  calc_cloud_thread.join();
339 
340  // Save the pointcloud upon closing the app
341  export_to_ply(points, normals);
342 
343  return 0;
344 }
static const textual_icon lock
Definition: model-views.h:218
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
void push(Mat &item)
Definition: rs-kinfu.cpp:160
GLboolean GLboolean GLboolean b
GLboolean GLboolean g
GLint y
void colorize_pointcloud(const Mat points, Mat &color)
Definition: rs-kinfu.cpp:21
void export_to_ply(Mat points, Mat normals)
Definition: rs-kinfu.cpp:101
#define glBegin
GLfloat GLfloat p
Definition: glext.h:12687
std::vector< uint32_t > split(const std::string &s, char delim)
double yaw
Definition: example.hpp:875
#define glPopMatrix
GLuint color
#define GL_PROJECTION
#define glPushAttrib
static float max_dist
Definition: rs-kinfu.cpp:16
double pitch
Definition: example.hpp:876
rs2_intrinsics intrin
unsigned short uint16_t
Definition: stdint.h:79
GLdouble GLdouble GLdouble w
d
Definition: rmse.py:171
void draw_kinfu_pointcloud(glfw_state &app_state, Mat points, Mat normals)
Definition: rs-kinfu.cpp:38
#define glLoadIdentity
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
GLdouble GLdouble z
unsigned char uint8_t
Definition: stdint.h:78
#define glVertex3f
e
Definition: rmse.py:177
#define glEnable
int main(int argc, char **argv)
Definition: rs-kinfu.cpp:180
depth_frame get_depth_frame() const
Definition: rs_frame.hpp:1006
GLdouble t
#define GL_LIGHTING
GLdouble f
static float min_dist
Definition: rs-kinfu.cpp:17
#define glColor3ub
GLsizeiptr size
std::ostream & cout()
GLdouble GLdouble r
#define GL_COLOR_MATERIAL
GLdouble x
#define glPushMatrix
int try_get_next_item(Mat &item)
Definition: rs-kinfu.cpp:165
GLbyte ny
#define glClear
float offset_y
Definition: example.hpp:881
#define glTranslatef
#define glNormal3f
#define glEnd
GLenum const GLfloat * params
GLbyte nx
Definition: glext.h:6424
#define GL_LIGHT0
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
#define GL_DEPTH_BUFFER_BIT
#define GL_MODELVIEW
fname
Definition: rmse.py:13
int min(int a, int b)
Definition: lz4s.c:73
const GLuint GLenum const void * binary
Definition: glext.h:1882
#define glPopAttrib
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
#define glClearColor
int i
#define glRotated
std::array< float, 3 > color
Definition: model-views.h:449
GLbyte GLbyte nz
pipeline_profile start()
std::queue< Mat > queue
Definition: rs-kinfu.cpp:175
#define GL_ALL_ATTRIB_BITS
void register_glfw_callbacks(window &app, glfw_state &app_state)
Definition: example.hpp:1037
std::mutex _mtx
Definition: rs-kinfu.cpp:176
#define GL_POINTS
#define glMatrixMode
Definition: parser.hpp:150
GLdouble GLdouble GLint GLint const GLdouble * points
#define GL_DEPTH_TEST


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:40