Skip to content

Commit

Permalink
Merge branch 'development' into windows_hid_support
Browse files Browse the repository at this point in the history
  • Loading branch information
abernste authored Nov 28, 2018
2 parents 2979926 + e82dc15 commit da040ac
Show file tree
Hide file tree
Showing 43 changed files with 2,258 additions and 1,184 deletions.
1 change: 1 addition & 0 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ endif()

add_subdirectory(software-device)
add_subdirectory(capture)
add_subdirectory(callback)
add_subdirectory(save-to-disk)
add_subdirectory(multicam)
add_subdirectory(pointcloud)
Expand Down
2 changes: 1 addition & 1 deletion examples/align/rs-align.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ int main(int argc, char * argv[]) try
rect pip_stream{ 0, 0, w / 5, h / 5 };
pip_stream = pip_stream.adjust_ratio({ static_cast<float>(aligned_depth_frame.get_width()),static_cast<float>(aligned_depth_frame.get_height()) });
pip_stream.x = altered_other_frame_rect.x + altered_other_frame_rect.w - pip_stream.w - (std::max(w, h) / 25);
pip_stream.y = altered_other_frame_rect.y + altered_other_frame_rect.h - pip_stream.h - (std::max(w, h) / 25);
pip_stream.y = altered_other_frame_rect.y + (std::max(w, h) / 25);

// Render depth (as picture in pipcture)
renderer.upload(c.process(aligned_depth_frame));
Expand Down
25 changes: 25 additions & 0 deletions examples/callback/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# minimum required cmake version: 3.1.0
cmake_minimum_required(VERSION 3.1.0)

project(rs-callback)

# Save the command line compile commands in the build output
set(CMAKE_EXPORT_COMPILE_COMMANDS 1)

include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
endif()

if(BUILD_GRAPHICAL_EXAMPLES)
add_executable(${PROJECT_NAME} ${PROJECT_NAME}.cpp)
target_link_libraries(${PROJECT_NAME} ${DEPENDENCIES})
include_directories(${PROJECT_NAME} ../ ../../third-party/tclap/include)
set_target_properties (${PROJECT_NAME} PROPERTIES FOLDER "Examples")

install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR})
endif()
90 changes: 90 additions & 0 deletions examples/callback/readme.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
# rs-callback Sample

## Overview

This sample demonstrates how to configure the camera for streaming frames using the pipeline's callback API.
This API is recommended when streaming high frequency data such as IMU ([Inertial measurement unit](https://en.wikipedia.org/wiki/Inertial_measurement_unit)) since the callback is invoked immediately once the a frame is ready.
This sample prints a frame counter for each stream, the code demonstrates how it can be done correctly by synchronizing the callbacks.

## Expected Output
![rs-callback](https://user-images.githubusercontent.com/18511514/48921401-37a0c680-eea8-11e8-9ab4-18e566d69a8a.PNG)

## Code Overview

First, we include the Intel® RealSense™ Cross-Platform API.
All but advanced functionality is provided through a single header:
```cpp
#include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
```

We define frame counters that will be updated every time a frame arrives.
This counters will be used in the application main loop to print how many frames arrived from each stream.
```cpp
std::map<int, int> counters;
std::map<int, std::string> stream_names;
```

The mutex object is a synchronization primitive that will be used to protect our frame counters from being simultaneously accessed by multiple threads.
```cpp
std::mutex mutex;
```

Define the frame callback which will be invoked by the pipeline on the sensors thread once a frame (or synchronised frameset) is ready.
```cpp
// Define frame callback
// The callback is executed on a sensor thread and can be called simultaneously from multiple sensors.
// Therefore any modification to shared data should be done under lock.
auto callback = [&](const rs2::frame& frame)
{
std::lock_guard<std::mutex> lock(mutex);
if (rs2::frameset fs = frame.as<rs2::frameset>())
{
// With callbacks, all synchronized stream will arrive in a single frameset
for (rs2::frame& f : fs)
counters[f.get_profile().unique_id()]++;
}
else
{
// Stream that bypass synchronization (such as IMU) will produce single frames
counters[frame.get_profile().unique_id()]++;
}
};
```

The SDK API entry point is the `pipeline` class:
```cpp
// Declare the RealSense pipeline, encapsulating the actual device and sensors
rs2::pipeline pipe;

// Start streaming through the callback with default recommended configuration
// The default video configuration contains Depth and Color streams
// If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default
rs2::pipeline_profile profiles = pipe.start(callback);
```

Collect the stream names from the returned `pipeline_profile` object:
```cpp
// Collect the enabled streams names
for (auto p : profiles.get_streams())
stream_names[p.unique_id()] = p.stream_name();
```

Finally, print the frame counters once every second.
After calling `start`, the main thread will continue to execute work, so even when no other action is required, we need to keep the application alive.
In order to protect our counters from being accessed simultaneously, access the counters using the mutex.
```cpp
std::cout << "RealSense callback sample" << std::endl << std::endl;

while (true)
{
std::this_thread::sleep_for(std::chrono::seconds(1));

std::lock_guard<std::mutex> lock(mutex);

std::cout << "\r";
for (auto p : counters)
{
std::cout << stream_names[p.first] << "[" << p.first << "]: " << p.second << " [frames] || ";
}
}
```
78 changes: 78 additions & 0 deletions examples/callback/rs-callback.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2017 Intel Corporation. All Rights Reserved.

#include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
#include <iostream>
#include <map>
#include <chrono>
#include <mutex>
#include <thread>

// The callback example demonstrates asynchronous usage of the pipeline
int main(int argc, char * argv[]) try
{
//rs2::log_to_console(RS2_LOG_SEVERITY_ERROR);

std::map<int, int> counters;
std::map<int, std::string> stream_names;
std::mutex mutex;

// Define frame callback
// The callback is executed on a sensor thread and can be called simultaneously from multiple sensors
// Therefore any modification to common memory should be done under lock
auto callback = [&](const rs2::frame& frame)
{
std::lock_guard<std::mutex> lock(mutex);
if (rs2::frameset fs = frame.as<rs2::frameset>())
{
// With callbacks, all synchronized stream will arrive in a single frameset
for (const rs2::frame& f : fs)
counters[f.get_profile().unique_id()]++;
}
else
{
// Stream that bypass synchronization (such as IMU) will produce single frames
counters[frame.get_profile().unique_id()]++;
}
};

// Declare RealSense pipeline, encapsulating the actual device and sensors.
rs2::pipeline pipe;

// Start streaming through the callback with default recommended configuration
// The default video configuration contains Depth and Color streams
// If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default
//
rs2::pipeline_profile profiles = pipe.start(callback);

// Collect the enabled streams names
for (auto p : profiles.get_streams())
stream_names[p.unique_id()] = p.stream_name();

std::cout << "RealSense callback sample" << std::endl << std::endl;

while (true)
{
std::this_thread::sleep_for(std::chrono::seconds(1));

std::lock_guard<std::mutex> lock(mutex);

std::cout << "\r";
for (auto p : counters)
{
std::cout << stream_names[p.first] << "[" << p.first << "]: " << p.second << " [frames] || ";
}
}

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;
}
35 changes: 19 additions & 16 deletions examples/capture/readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,9 @@ Next, we include a [very short helper library](../example.hpp) to encapsulate Op
```

This header lets us easily open a new window and prepare textures for rendering.
The `texture` class is designed to hold video frame data for rendering.
```cpp
// Create a simple OpenGL window for rendering:
window app(1280, 720, "RealSense Capture Example");
// Declare two textures on the GPU, one for depth and one for color
texture depth_image, color_image;
```
Depth data is usually provided on a 12-bit grayscale which is not very useful for visualization.
Expand All @@ -38,28 +35,34 @@ To enhance visualization, we provide an API that converts the grayscale image to
rs2::colorizer color_map;
```

The sample prints frame rates of each enabled stream, this is done by rates_printer filter._
```cpp
// Declare rates printer for showing streaming rates of the enabled streams.
rs2::rates_printer printer;
```

The SDK API entry point is the `pipeline` class:
```cpp
// Declare the RealSense pipeline, encapsulating the actual device and sensors
rs2::pipeline pipe;
// Start streaming with the default recommended configuration
pipe.start();
```

Next, we wait for the next set of frames, effectively blocking the program:
```cpp
rs2::frameset data = pipe.wait_for_frames(); // Wait for next set of frames from the camera
// Start streaming with default recommended configuration
// The default video configuration contains Depth and Color streams
// If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default
pipe.start();
```

Using the `frameset` object we find the first depth frame and the first color frame in the set:
Next, we wait for the next set of frames, effectively blocking the program.
Once a frameset arrives, apply both the colorizer and the rates_printer filters._
```cpp
rs2::frame depth = color_map(data.get_depth_frame()); // Find and colorize the depth data
rs2::frame color = data.get_color_frame(); // Find the color data
rs2::frameset data = pipe.wait_for_frames(). // Wait for next set of frames from the camera
apply_filter(printer). // Print each enabled stream frame rate
apply_filter(color_map); // Find and colorize the depth data
```
Finally, depth and color rendering is implemented by the `texture` class from [example.hpp](../example.hpp)
Finally, render the images by the `window` class from [example.hpp](../example.hpp)
```cpp
// Render depth on to the first half of the screen and color on to the second
depth_image.render(depth, { 0, 0, app.width() / 2, app.height() });
color_image.render(color, { app.width() / 2, 0, app.width() / 2, app.height() });
// Show method, when applied on frameset, break it to frames and upload each frame into a gl textures
// Each texture is displayed on different viewport according to it's stream unique id
app.show(data);
```
28 changes: 13 additions & 15 deletions examples/capture/rs-capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,31 +11,29 @@ int main(int argc, char * argv[]) try
rs2::log_to_console(RS2_LOG_SEVERITY_ERROR);
// Create a simple OpenGL window for rendering:
window app(1280, 720, "RealSense Capture Example");
// Declare two textures on the GPU, one for color and one for depth
texture depth_image, color_image;

// Declare depth colorizer for pretty visualization of depth data
rs2::colorizer color_map;
// Declare rates printer for showing streaming rates of the enabled streams.
rs2::rates_printer printer;

// Declare RealSense pipeline, encapsulating the actual device and sensors
rs2::pipeline pipe;

// Start streaming with default recommended configuration
// The default video configuration contains Depth and Color streams
// If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default
pipe.start();

while(app) // Application still alive?
while (app) // Application still alive?
{
rs2::frameset data = pipe.wait_for_frames(); // Wait for next set of frames from the camera

rs2::frame depth = color_map.process(data.get_depth_frame()); // Find and colorize the depth data
rs2::frame color = data.get_color_frame(); // Find the color data
rs2::frameset data = pipe.wait_for_frames(). // Wait for next set of frames from the camera
apply_filter(printer). // Print each enabled stream frame rate
apply_filter(color_map); // Find and colorize the depth data

// For cameras that don't have RGB sensor, we'll render infrared frames instead of color
if (!color)
color = data.get_infrared_frame();

// Render depth on to the first half of the screen and color on to the second
depth_image.render(depth, { 0, 0, app.width() / 2, app.height() });
color_image.render(color, { app.width() / 2, 0, app.width() / 2, app.height() });
// The show method, when applied on frameset, break it to frames and upload each frame into a gl textures
// Each texture is displayed on different viewport according to it's stream unique id
app.show(data);
}

return EXIT_SUCCESS;
Expand All @@ -49,4 +47,4 @@ catch (const std::exception& e)
{
std::cerr << e.what() << std::endl;
return EXIT_FAILURE;
}
}
3 changes: 1 addition & 2 deletions examples/cmake/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,7 @@ cmake_minimum_required(VERSION 3.1.0)
project(hello_librealsense2)

# Find librealsense2 installed package
# We provide a search hint to the default Windows installation path
find_package(realsense2 REQUIRED HINTS "Intel RealSense SDK 2.0")
find_package(realsense2 REQUIRED)

# Enable C++11
set(CMAKE_CXX_STANDARD 11)
Expand Down
50 changes: 50 additions & 0 deletions examples/cmake/readme.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
# CMake Sample

## Overview

This sample demonstrates how to create a basic librealsense application using CMake.
Currently this sample is supported only by Linux OS.

## Prerequisite
Install the SDK or build it from source ([Linux](https://github.com/IntelRealSense/librealsense/blob/master/doc/distribution_linux.md))

## Expected Output
![cmake_example](https://user-images.githubusercontent.com/18511514/48919868-06bb9400-ee9e-11e8-9c93-5bca41d5954c.PNG)

## Code Overview

Set minimum required CMake version
```
cmake_minimum_required(VERSION 3.1.0)
```

Name the project, in this sample the project name will be also the executable name
```
project(hello_librealsense2)
```

Find librealsense installation, this feature is currently available only for Linux
```
# Find librealsense2 installed package
find_package(realsense2 REQUIRED)
```

Enable C++ 11 standard in the applicatoin
```
# Enable C++11
set(CMAKE_CXX_STANDARD 11)
set(CMAKE_CXX_STANDARD_REQUIRED TRUE)
```

Point to the source files, in this simple example we have only one cpp file
```
# Add the application sources to the target
add_executable(${PROJECT_NAME} hello_librealsense2.cpp)
```

Link librealsense, the variable ${realsense2_LIBRARY} is set by "find_package"
```
# Link librealsense2 to the target
target_link_libraries(${PROJECT_NAME} ${realsense2_LIBRARY})
```

Loading

0 comments on commit da040ac

Please sign in to comment.