rs-pcl.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2015-2017 Intel Corporation. All Rights Reserved.
3 
4 #include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
5 #include "../../../examples/example.hpp" // Include short list of convenience functions for rendering
6 
7 #include <pcl/point_types.h>
8 #include <pcl/filters/passthrough.h>
9 
10 // Struct for managing rotation of pointcloud view
11 struct state {
12  state() : yaw(0.0), pitch(0.0), last_x(0.0), last_y(0.0),
13  ml(false), offset_x(0.0f), offset_y(0.0f) {}
14  double yaw, pitch, last_x, last_y; bool ml; float offset_x, offset_y;
15 };
16 
17 using pcl_ptr = pcl::PointCloud<pcl::PointXYZ>::Ptr;
18 
19 // Helper functions
20 void register_glfw_callbacks(window& app, state& app_state);
21 void draw_pointcloud(window& app, state& app_state, const std::vector<pcl_ptr>& points);
22 
24 {
25  pcl_ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
26 
27  auto sp = points.get_profile().as<rs2::video_stream_profile>();
28  cloud->width = sp.width();
29  cloud->height = sp.height();
30  cloud->is_dense = false;
31  cloud->points.resize(points.size());
32  auto ptr = points.get_vertices();
33  for (auto& p : cloud->points)
34  {
35  p.x = ptr->x;
36  p.y = ptr->y;
37  p.z = ptr->z;
38  ptr++;
39  }
40 
41  return cloud;
42 }
43 
44 float3 colors[] { { 0.8f, 0.1f, 0.3f },
45  { 0.1f, 0.9f, 0.5f },
46  };
47 
48 int main(int argc, char * argv[]) try
49 {
50  // Create a simple OpenGL window for rendering:
51  window app(1280, 720, "RealSense PCL Pointcloud Example");
52  // Construct an object to manage view state
53  state app_state;
54  // register callbacks to allow manipulation of the pointcloud
55  register_glfw_callbacks(app, app_state);
56 
57  // Declare pointcloud object, for calculating pointclouds and texture mappings
59  // We want the points object to be persistent so we can display the last cloud when a frame drops
61 
62  // Declare RealSense pipeline, encapsulating the actual device and sensors
64  // Start streaming with default recommended configuration
65  pipe.start();
66 
67  // Wait for the next set of frames from the camera
68  auto frames = pipe.wait_for_frames();
69 
70  auto depth = frames.get_depth_frame();
71 
72  // Generate the pointcloud and texture mappings
73  points = pc.calculate(depth);
74 
75  auto pcl_points = points_to_pcl(points);
76 
77  pcl_ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
78  pcl::PassThrough<pcl::PointXYZ> pass;
79  pass.setInputCloud(pcl_points);
80  pass.setFilterFieldName("z");
81  pass.setFilterLimits(0.0, 1.0);
82  pass.filter(*cloud_filtered);
83 
84  std::vector<pcl_ptr> layers;
85  layers.push_back(pcl_points);
86  layers.push_back(cloud_filtered);
87 
88  while (app) // Application still alive?
89  {
90  draw_pointcloud(app, app_state, layers);
91  }
92 
93  return EXIT_SUCCESS;
94 }
95 catch (const rs2::error & e)
96 {
97  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
98  return EXIT_FAILURE;
99 }
100 catch (const std::exception & e)
101 {
102  std::cerr << e.what() << std::endl;
103  return EXIT_FAILURE;
104 }
105 
106 // Registers the state variable and callbacks to allow mouse control of the pointcloud
107 void register_glfw_callbacks(window& app, state& app_state)
108 {
109  app.on_left_mouse = [&](bool pressed)
110  {
111  app_state.ml = pressed;
112  };
113 
114  app.on_mouse_scroll = [&](double xoffset, double yoffset)
115  {
116  app_state.offset_x += static_cast<float>(xoffset);
117  app_state.offset_y += static_cast<float>(yoffset);
118  };
119 
120  app.on_mouse_move = [&](double x, double y)
121  {
122  if (app_state.ml)
123  {
124  app_state.yaw -= (x - app_state.last_x);
125  app_state.yaw = std::max(app_state.yaw, -120.0);
126  app_state.yaw = std::min(app_state.yaw, +120.0);
127  app_state.pitch += (y - app_state.last_y);
128  app_state.pitch = std::max(app_state.pitch, -80.0);
129  app_state.pitch = std::min(app_state.pitch, +80.0);
130  }
131  app_state.last_x = x;
132  app_state.last_y = y;
133  };
134 
135  app.on_key_release = [&](int key)
136  {
137  if (key == 32) // Escape
138  {
139  app_state.yaw = app_state.pitch = 0; app_state.offset_x = app_state.offset_y = 0.0;
140  }
141  };
142 }
143 
144 // Handles all the OpenGL calls needed to display the point cloud
145 void draw_pointcloud(window& app, state& app_state, const std::vector<pcl_ptr>& points)
146 {
147  // OpenGL commands that prep screen for the pointcloud
148  glPopMatrix();
150 
151  float width = app.width(), height = app.height();
152 
153  glClearColor(153.f / 255, 153.f / 255, 153.f / 255, 1);
155 
157  glPushMatrix();
158  gluPerspective(60, width / height, 0.01f, 10.0f);
159 
161  glPushMatrix();
162  gluLookAt(0, 0, 0, 0, 0, 1, 0, -1, 0);
163 
164  glTranslatef(0, 0, +0.5f + app_state.offset_y*0.05f);
165  glRotated(app_state.pitch, 1, 0, 0);
166  glRotated(app_state.yaw, 0, 1, 0);
167  glTranslatef(0, 0, -0.5f);
168 
169  glPointSize(width / 640);
171 
172  int color = 0;
173 
174  for (auto&& pc : points)
175  {
176  auto c = colors[(color++) % (sizeof(colors) / sizeof(float3))];
177 
179  glColor3f(c.x, c.y, c.z);
180 
181  /* this segment actually prints the pointcloud */
182  for (int i = 0; i < pc->points.size(); i++)
183  {
184  auto&& p = pc->points[i];
185  if (p.z)
186  {
187  // upload the point and texture coordinates only for points we have depth data for
188  glVertex3f(p.x, p.y, p.z);
189  }
190  }
191 
192  glEnd();
193  }
194 
195  // OpenGL cleanup
196  glPopMatrix();
198  glPopMatrix();
199  glPopAttrib();
200  glPushMatrix();
201 }
std::function< void(bool)> on_left_mouse
Definition: example.hpp:501
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
state()
Definition: rs-pcl.cpp:12
GLint y
int main(int argc, char *argv[])
Definition: rs-pcl.cpp:48
#define GL_TEXTURE_2D
#define glBegin
bool ml
Definition: rs-pcl.cpp:14
GLfloat GLfloat p
Definition: glext.h:12687
#define glPopMatrix
GLuint color
#define GL_PROJECTION
stream_profile get_profile() const
Definition: rs_frame.hpp:557
#define glPushAttrib
#define glPointSize
GLint GLint GLsizei GLsizei GLsizei depth
#define glVertex3f
e
Definition: rmse.py:177
#define glEnable
GLuint64 key
Definition: glext.h:8966
size_t size() const
Definition: rs_frame.hpp:800
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
GLdouble f
float3 colors[]
Definition: rs-pcl.cpp:44
pcl_ptr points_to_pcl(const rs2::points &points)
Definition: rs-pcl.cpp:23
#define GL_COLOR_BUFFER_BIT
const GLubyte * c
Definition: glext.h:12690
GLdouble x
float width() const
Definition: example.hpp:627
#define glPushMatrix
#define glClear
points calculate(frame depth) const
GLint GLsizei GLsizei height
const vertex * get_vertices() const
Definition: rs_frame.hpp:767
#define glTranslatef
void register_glfw_callbacks(window &app, state &app_state)
Definition: rs-pcl.cpp:107
#define glEnd
#define GL_DEPTH_BUFFER_BIT
#define GL_MODELVIEW
float height() const
Definition: example.hpp:628
std::function< void(int)> on_key_release
Definition: example.hpp:504
double yaw
Definition: rs-pcl.cpp:14
#define glColor3f
GLint GLint GLint yoffset
pcl::PointCloud< pcl::PointXYZ >::Ptr pcl_ptr
Definition: rs-pcl.cpp:17
double pitch
Definition: rs-pcl.cpp:14
int min(int a, int b)
Definition: lz4s.c:73
float offset_y
Definition: rs-pcl.cpp:14
#define glPopAttrib
#define glClearColor
std::ostream & cerr()
std::function< void(double, double)> on_mouse_scroll
Definition: example.hpp:502
int i
double last_x
Definition: rs-pcl.cpp:14
GLenum GLsizei GLsizei GLsizei GLsizei layers
Definition: glext.h:5770
#define glRotated
pipeline_profile start()
#define GL_ALL_ATTRIB_BITS
std::function< void(double, double)> on_mouse_move
Definition: example.hpp:503
GLint GLint xoffset
void draw_pointcloud(window &app, state &app_state, const std::vector< pcl_ptr > &points)
Definition: rs-pcl.cpp:145
#define GL_POINTS
#define glMatrixMode
const std::string & get_failed_function() const
Definition: rs_types.hpp:112
GLint GLsizei width
GLdouble GLdouble GLint GLint const GLdouble * points
float offset_x
Definition: rs-pcl.cpp:14
double last_y
Definition: rs-pcl.cpp:14


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