c-tutorial-3-pointcloud.c
Go to the documentation of this file.
1 /* License: Apache 2.0. See LICENSE file in root directory.
2  Copyright(c) 2015 Intel Corporation. All Rights Reserved. */
3 
4 /***************************************************\
5 * librealsense tutorial #3 - Point cloud generation *
6 \***************************************************/
7 
8 /* First include the librealsense C header file */
9 #include <librealsense/rs.h>
10 #include <stdlib.h>
11 #include <stdint.h>
12 #include <stdio.h>
13 #include <math.h>
14 
15 /* Additionall,y include the librealsense utilities header file */
16 #include <librealsense/rsutil.h>
17 
18 /* Also include GLFW to allow for graphical display */
19 #define GLFW_INCLUDE_GLU
20 #include <GLFW/glfw3.h>
21 
22 /* Function calls to librealsense may raise errors of type rs_error */
23 rs_error * e = 0;
25 {
26  if(e)
27  {
28  printf("rs_error was raised when calling %s(%s):\n", rs_get_failed_function(e), rs_get_failed_args(e));
29  printf(" %s\n", rs_get_error_message(e));
30  exit(EXIT_FAILURE);
31  }
32 }
33 
34 double yaw, pitch, lastX, lastY; int ml;
35 static void on_mouse_button(GLFWwindow * win, int button, int action, int mods)
36 {
37  if(button == GLFW_MOUSE_BUTTON_LEFT) ml = action == GLFW_PRESS;
38 }
39 static double clamp(double val, double lo, double hi) { return val < lo ? lo : val > hi ? hi : val; }
40 static void on_cursor_pos(GLFWwindow * win, double x, double y)
41 {
42  if(ml)
43  {
44  yaw = clamp(yaw - (x - lastX), -120, 120);
45  pitch = clamp(pitch + (y - lastY), -80, 80);
46  }
47  lastX = x;
48  lastY = y;
49 }
50 
51 int main()
52 {
53  /* Turn on logging. We can separately enable logging to console or to file, and use different severity filters for each. */
55  check_error();
56  /*rs_log_to_file(RS_LOG_SEVERITY_DEBUG, "librealsense.log", &e);
57  check_error();*/
58 
59  /* Create a context object. This object owns the handles to all connected realsense devices. */
61  check_error();
62  printf("There are %d connected RealSense devices.\n", rs_get_device_count(ctx, &e));
63  check_error();
64  if(rs_get_device_count(ctx, &e) == 0) return EXIT_FAILURE;
65 
66  /* This tutorial will access only a single device, but it is trivial to extend to multiple devices */
67  rs_device * dev = rs_get_device(ctx, 0, &e);
68  check_error();
69  printf("\nUsing device 0, an %s\n", rs_get_device_name(dev, &e));
70  check_error();
71  printf(" Serial number: %s\n", rs_get_device_serial(dev, &e));
72  check_error();
73  printf(" Firmware version: %s\n", rs_get_device_firmware_version(dev, &e));
74  check_error();
75 
76  /* Configure depth and color to run with the device's preferred settings */
78  check_error();
80  check_error();
81  rs_start_device(dev, &e);
82  check_error();
83 
84  /* Open a GLFW window to display our output */
85  glfwInit();
86  GLFWwindow * win = glfwCreateWindow(1280, 960, "librealsense tutorial #3", NULL, NULL);
90  while(!glfwWindowShouldClose(win))
91  {
92  /* Wait for new frame data */
94  rs_wait_for_frames(dev, &e);
95  check_error();
96 
97  /* Retrieve our images */
98  const uint16_t * depth_image = (const uint16_t *)rs_get_frame_data(dev, RS_STREAM_DEPTH, &e);
99  check_error();
100  const uint8_t * color_image = (const uint8_t *)rs_get_frame_data(dev, RS_STREAM_COLOR, &e);
101  check_error();
102 
103  /* Retrieve camera parameters for mapping between depth and color */
104  rs_intrinsics depth_intrin, color_intrin;
105  rs_extrinsics depth_to_color;
106  rs_get_stream_intrinsics(dev, RS_STREAM_DEPTH, &depth_intrin, &e);
107  check_error();
108  rs_get_device_extrinsics(dev, RS_STREAM_DEPTH, RS_STREAM_COLOR, &depth_to_color, &e);
109  check_error();
110  rs_get_stream_intrinsics(dev, RS_STREAM_COLOR, &color_intrin, &e);
111  check_error();
112  float scale = rs_get_device_depth_scale(dev, &e);
113  check_error();
114 
115  /* Set up a perspective transform in a space that we can rotate by clicking and dragging the mouse */
116  glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
117  glMatrixMode(GL_PROJECTION);
118  glLoadIdentity();
119  gluPerspective(60, (float)1280/960, 0.01f, 20.0f);
120  glMatrixMode(GL_MODELVIEW);
121  glLoadIdentity();
122  gluLookAt(0,0,0, 0,0,1, 0,-1,0);
123  glTranslatef(0,0,+0.5f);
124  glRotated(pitch, 1, 0, 0);
125  glRotated(yaw, 0, 1, 0);
126  glTranslatef(0,0,-0.5f);
127 
128  /* We will render our depth data as a set of points in 3D space */
129  glPointSize(2);
130  glEnable(GL_DEPTH_TEST);
131  glBegin(GL_POINTS);
132 
133  int dx, dy;
134  for(dy=0; dy<depth_intrin.height; ++dy)
135  {
136  for(dx=0; dx<depth_intrin.width; ++dx)
137  {
138  /* Retrieve the 16-bit depth value and map it into a depth in meters */
139  uint16_t depth_value = depth_image[dy * depth_intrin.width + dx];
140  float depth_in_meters = depth_value * scale;
141 
142  /* Skip over pixels with a depth value of zero, which is used to indicate no data */
143  if(depth_value == 0) continue;
144 
145  /* Map from pixel coordinates in the depth image to pixel coordinates in the color image */
146  float depth_pixel[2] = {(float)dx, (float)dy};
147  float depth_point[3], color_point[3], color_pixel[2];
148  rs_deproject_pixel_to_point(depth_point, &depth_intrin, depth_pixel, depth_in_meters);
149  rs_transform_point_to_point(color_point, &depth_to_color, depth_point);
150  rs_project_point_to_pixel(color_pixel, &color_intrin, color_point);
151 
152  /* Use the color from the nearest color pixel, or pure white if this point falls outside the color image */
153  const int cx = (int)roundf(color_pixel[0]), cy = (int)roundf(color_pixel[1]);
154  if(cx < 0 || cy < 0 || cx >= color_intrin.width || cy >= color_intrin.height)
155  {
156  glColor3ub(255, 255, 255);
157  }
158  else
159  {
160  glColor3ubv(color_image + (cy * color_intrin.width + cx) * 3);
161  }
162 
163  /* Emit a vertex at the 3D location of this depth pixel */
164  glVertex3f(depth_point[0], depth_point[1], depth_point[2]);
165  }
166  }
167  glEnd();
168 
169  glfwSwapBuffers(win);
170  }
171 
172  return EXIT_SUCCESS;
173 }
static void on_mouse_button(GLFWwindow *win, int button, int action, int mods)
#define RS_API_VERSION
Definition: rs.h:28
int main()
void rs_get_stream_intrinsics(const rs_device *device, rs_stream stream, rs_intrinsics *intrin, rs_error **error)
Retrieves intrinsic camera parameters for a specific stream.
Definition: rs.cpp:289
Definition: rs.cpp:16
static void on_cursor_pos(GLFWwindow *win, double x, double y)
int rs_get_device_count(const rs_context *context, rs_error **error)
Determines number of connected devices.
Definition: rs.cpp:113
GLint GLint GLint GLint GLint GLint y
Definition: glext.h:114
void rs_log_to_console(rs_log_severity min_severity, rs_error **error)
Starts logging to console.
Definition: rs.cpp:769
GLenum GLenum GLenum GLenum GLenum scale
Definition: glext.h:9820
const void * rs_get_frame_data(const rs_device *device, rs_stream stream, rs_error **error)
Retrieves the contents of the latest frame on a stream.
Definition: rs.cpp:490
double yaw
GLFWAPI GLFWmousebuttonfun glfwSetMouseButtonCallback(GLFWwindow *window, GLFWmousebuttonfun cbfun)
Sets the mouse button callback.
Definition: input.c:482
double pitch
void check_error()
#define GLFW_MOUSE_BUTTON_LEFT
Definition: glfw3.h:432
const char * rs_get_device_name(const rs_device *device, rs_error **error)
Retrieves human-readable device model string.
Definition: rs.cpp:128
const char * rs_get_error_message(const rs_error *error)
Returns static pointer to error message.
Definition: rs.cpp:751
float rs_get_device_depth_scale(const rs_device *device, rs_error **error)
Retrieves mapping between the units of the depth image and meters.
Definition: rs.cpp:420
static void rs_project_point_to_pixel(float pixel[2], const struct rs_intrinsics *intrin, const float point[3])
Definition: rsutil.h:11
Exposes librealsense functionality for C compilers.
static void rs_transform_point_to_point(float to_point[3], const struct rs_extrinsics *extrin, const float from_point[3])
Definition: rsutil.h:55
rs_error * e
struct GLFWwindow GLFWwindow
Opaque window object.
Definition: glfw3.h:722
const char * rs_get_failed_function(const rs_error *error)
Returns static pointer to name of a failing function in case of error.
Definition: rs.cpp:749
GLFWAPI int glfwInit(void)
Initializes the GLFW library.
rs_context * rs_create_context(int api_version, rs_error **error)
Creates RealSense context that is required for the rest of the API.
Definition: rs.cpp:75
void rs_get_device_extrinsics(const rs_device *device, rs_stream from_stream, rs_stream to_stream, rs_extrinsics *extrin, rs_error **error)
Retrieves extrinsic transformation between the viewpoints of two different streams.
Definition: rs.cpp:163
GLfloat f
Definition: glext.h:1868
static double clamp(double val, double lo, double hi)
typedef int(WINAPI *PFNWGLRELEASEPBUFFERDCARBPROC)(HPBUFFERARB hPbuffer
double lastY
const char * rs_get_device_firmware_version(const rs_device *device, rs_error **error)
Retrieves the version of the firmware currently installed on the device.
Definition: rs.cpp:156
GLFWAPI void glfwSwapBuffers(GLFWwindow *window)
Swaps the front and back buffers of the specified window.
Definition: context.c:544
GLFWAPI void glfwMakeContextCurrent(GLFWwindow *window)
Makes the context of the specified window current for the calling thread.
Definition: context.c:531
static void rs_deproject_pixel_to_point(float point[3], const struct rs_intrinsics *intrin, const float pixel[2], float depth)
Definition: rsutil.h:33
const char * rs_get_failed_args(const rs_error *error)
Returns static pointer to arguments of a failing function in case of error.
Definition: rs.cpp:750
GLFWAPI GLFWcursorposfun glfwSetCursorPosCallback(GLFWwindow *window, GLFWcursorposfun cbfun)
Sets the cursor position callback.
Definition: input.c:491
double lastX
auto ctx
int height
Definition: rs.h:303
int width
Definition: rs.h:302
Video stream intrinsics.
Definition: rs.h:300
Cross-stream extrinsics: encode the topology describing how the different devices are connected...
Definition: rs.h:332
GLFWAPI GLFWwindow * glfwCreateWindow(int width, int height, const char *title, GLFWmonitor *monitor, GLFWwindow *share)
Creates a window and its associated context.
Definition: window.c:116
rs_device * dev
rs_device * rs_get_device(rs_context *context, int index, rs_error **error)
Retrieves connected device by index.
Definition: rs.cpp:120
const char * rs_get_device_serial(const rs_device *device, rs_error **error)
Retrieves unique serial number of the device.
Definition: rs.cpp:135
void rs_wait_for_frames(rs_device *device, rs_error **error)
Blocks until new frames are available.
Definition: rs.cpp:428
GLFWAPI void glfwPollEvents(void)
Processes all pending events.
Definition: window.c:682
void rs_enable_stream_preset(rs_device *device, rs_stream stream, rs_preset preset, rs_error **error)
Enables a specific stream and requests properties using a preset.
Definition: rs.cpp:232
void rs_start_device(rs_device *device, rs_error **error)
Begins streaming on all enabled streams for this device.
Definition: rs.cpp:383
#define GLFW_PRESS
The key or mouse button was pressed.
Definition: glfw3.h:232
GLint GLint GLint GLint GLint x
Definition: glext.h:114
GLuint GLfloat * val
Definition: glext.h:1490
GLFWAPI int glfwWindowShouldClose(GLFWwindow *window)
Checks the close flag of the specified window.
Definition: window.c:406


librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Fri Mar 13 2020 03:16:11