Skip to content

Commit

Permalink
Fixing u0 coordinate while rendering PointCloud in Align Depth GL block
Browse files Browse the repository at this point in the history
  • Loading branch information
Arun-Prasad-V committed Jan 12, 2024
1 parent e16f1bd commit 33c359b
Show file tree
Hide file tree
Showing 4 changed files with 194 additions and 2 deletions.
2 changes: 1 addition & 1 deletion examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ add_subdirectory(save-to-disk)
add_subdirectory(multicam)
add_subdirectory(pointcloud)
add_subdirectory(align)
add_subdirectory(align-gl)
add_subdirectory(align-advanced)
add_subdirectory(sensor-control)
add_subdirectory(measure)
Expand All @@ -37,4 +38,3 @@ add_subdirectory(record-playback)
add_subdirectory(motion)
add_subdirectory(gl)
add_subdirectory(hdr)

15 changes: 15 additions & 0 deletions examples/align-gl/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# License: Apache 2.0. See LICENSE file in root directory.
# Copyright(c) 2019 Intel Corporation. All Rights Reserved.
# minimum required cmake version: 3.1.0
cmake_minimum_required(VERSION 3.1.0)

project(RealsenseExamplesAlignGl )

if(BUILD_GRAPHICAL_EXAMPLES)
add_executable(rs-align-gl rs-align-gl.cpp ../../third-party/imgui/imgui.cpp ../../third-party/imgui/imgui_draw.cpp ../../third-party/imgui/imgui_impl_glfw.cpp)
set_property(TARGET rs-align-gl PROPERTY CXX_STANDARD 11)
target_link_libraries(rs-align-gl ${DEPENDENCIES} realsense2-gl)
include_directories(../../common ../../third-party/imgui ../../examples)
set_target_properties (rs-align-gl PROPERTIES FOLDER Examples)
install(TARGETS rs-align-gl RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR})
endif()
177 changes: 177 additions & 0 deletions examples/align-gl/rs-align-gl.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,177 @@
// 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"
#include "example.hpp" // Include short list of convenience functions for rendering
#include <librealsense2-gl/rs_processing_gl.hpp> // Include GPU-Processing API


/*
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;

// The following toggle is going to control
// if we will use CPU or GPU for depth data processing
bool use_gpu_processing = true;

// Create and initialize GUI related objects
window app(1280, 720, "RealSense Align Example"); // Simple window handling
ImGui_ImplGlfw_Init(app, false); // ImGui library intializition

// Once we have a window, initialize GL module
// Pass our window to enable sharing of textures between processed frames and the window
rs2::gl::init_processing(app, use_gpu_processing);
// Initialize rendering module:
rs2::gl::init_rendering();

rs2::gl::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::gl::align align_to_depth(RS2_STREAM_DEPTH);
rs2::gl::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();
}
2 changes: 1 addition & 1 deletion src/gl/align-gl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ void build_opengl_projection_for_intrinsics(matrix4& frustum,
// additional row is inserted to map the z-coordinate to
// OpenGL.
matrix4 tproj;
tproj(0,0) = float(alpha); tproj(0,1) = float(skew); tproj(0,2) = 0.f;
tproj(0,0) = float(alpha); tproj(0,1) = float(skew); tproj(0,2) = float(u0);
tproj(1,1) = float(beta); tproj(1,2) = float(v0);
tproj(2,2) = float(-(N+F)); tproj(2,3) = float(-N*F);
tproj(3,2) = 1.f;
Expand Down

0 comments on commit 33c359b

Please sign in to comment.