-
Notifications
You must be signed in to change notification settings - Fork 4.8k
/
rs-align.cpp
163 lines (140 loc) · 5.99 KB
/
rs-align.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2019 Intel Corporation. All Rights Reserved.
#include <librealsense2/rs.hpp>
#include "example-imgui.hpp"
/*
This example introduces the concept of spatial stream alignment.
For example usecase of alignment, please check out align-advanced and measure demos.
The need for spatial alignment (from here "align") arises from the fact
that not all camera streams are captured from a single viewport.
Align process lets the user translate images from one viewport to another.
That said, results of align are synthetic streams, and suffer from several artifacts:
1. Sampling - mapping stream to a different viewport will modify the resolution of the frame
to match the resolution of target viewport. This will either cause downsampling or
upsampling via interpolation. The interpolation used needs to be of type
Nearest Neighbor to avoid introducing non-existing values.
2. Occlussion - Some pixels in the resulting image correspond to 3D coordinates that the original
sensor did not see, because these 3D points were occluded in the original viewport.
Such pixels may hold invalid texture values.
*/
// This example assumes camera with depth and color
// streams, and direction lets you define the target stream
enum class direction
{
to_depth,
to_color
};
// Forward definition of UI rendering, implemented below
void render_slider(rect location, float* alpha, direction* dir);
int main(int argc, char * argv[]) try
{
std::string serial;
if (!device_with_streams({ RS2_STREAM_COLOR,RS2_STREAM_DEPTH }, serial))
return EXIT_SUCCESS;
// Create and initialize GUI related objects
window app(1280, 720, "RealSense Align Example"); // Simple window handling
ImGui_ImplGlfw_Init(app, false); // ImGui library intializition
rs2::colorizer c; // Helper to colorize depth images
texture depth_image, color_image; // Helpers for renderig images
// Create a pipeline to easily configure and start the camera
rs2::pipeline pipe;
rs2::config cfg;
if (!serial.empty())
cfg.enable_device(serial);
cfg.enable_stream(RS2_STREAM_DEPTH);
cfg.enable_stream(RS2_STREAM_COLOR);
pipe.start(cfg);
// Define two align objects. One will be used to align
// to depth viewport and the other to color.
// Creating align object is an expensive operation
// that should not be performed in the main loop
rs2::align align_to_depth(RS2_STREAM_DEPTH);
rs2::align align_to_color(RS2_STREAM_COLOR);
float alpha = 0.5f; // Transparancy coefficient
direction dir = direction::to_depth; // Alignment direction
while (app) // Application still alive?
{
// Using the align object, we block the application until a frameset is available
rs2::frameset frameset = pipe.wait_for_frames();
if (dir == direction::to_depth)
{
// Align all frames to depth viewport
frameset = align_to_depth.process(frameset);
}
else
{
// Align all frames to color viewport
frameset = align_to_color.process(frameset);
}
// With the aligned frameset we proceed as usual
auto depth = frameset.get_depth_frame();
auto color = frameset.get_color_frame();
auto colorized_depth = c.colorize(depth);
glEnable(GL_BLEND);
// Use the Alpha channel for blending
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
if (dir == direction::to_depth)
{
// When aligning to depth, first render depth image
// and then overlay color on top with transparancy
depth_image.render(colorized_depth, { 0, 0, app.width(), app.height() });
color_image.render(color, { 0, 0, app.width(), app.height() }, alpha);
}
else
{
// When aligning to color, first render color image
// and then overlay depth image on top
color_image.render(color, { 0, 0, app.width(), app.height() });
depth_image.render(colorized_depth, { 0, 0, app.width(), app.height() }, 1 - alpha);
}
glColor4f(1.f, 1.f, 1.f, 1.f);
glDisable(GL_BLEND);
// Render the UI:
ImGui_ImplGlfw_NewFrame(1);
render_slider({ 15.f, app.height() - 60, app.width() - 30, app.height() }, &alpha, &dir);
ImGui::Render();
}
return EXIT_SUCCESS;
}
catch (const rs2::error & e)
{
std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
return EXIT_FAILURE;
}
catch (const std::exception & e)
{
std::cerr << e.what() << std::endl;
return EXIT_FAILURE;
}
void render_slider(rect location, float* alpha, direction* dir)
{
static const int flags = ImGuiWindowFlags_NoCollapse
| ImGuiWindowFlags_NoScrollbar
| ImGuiWindowFlags_NoSavedSettings
| ImGuiWindowFlags_NoTitleBar
| ImGuiWindowFlags_NoResize
| ImGuiWindowFlags_NoMove;
ImGui::SetNextWindowPos({ location.x, location.y });
ImGui::SetNextWindowSize({ location.w, location.h });
// Render transparency slider:
ImGui::Begin("slider", nullptr, flags);
ImGui::PushItemWidth(-1);
ImGui::SliderFloat("##Slider", alpha, 0.f, 1.f);
ImGui::PopItemWidth();
if (ImGui::IsItemHovered())
ImGui::SetTooltip("Texture Transparancy: %.3f", *alpha);
// Render direction checkboxes:
bool to_depth = (*dir == direction::to_depth);
bool to_color = (*dir == direction::to_color);
if (ImGui::Checkbox("Align To Depth", &to_depth))
{
*dir = to_depth ? direction::to_depth : direction::to_color;
}
ImGui::SameLine();
ImGui::SetCursorPosX(location.w - 140);
if (ImGui::Checkbox("Align To Color", &to_color))
{
*dir = to_color ? direction::to_color : direction::to_depth;
}
ImGui::End();
}