diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index e8ffb38ab9..3b8021e54c 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -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) diff --git a/examples/align/rs-align.cpp b/examples/align/rs-align.cpp index 098d4a503a..eca695a647 100644 --- a/examples/align/rs-align.cpp +++ b/examples/align/rs-align.cpp @@ -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(aligned_depth_frame.get_width()),static_cast(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)); diff --git a/examples/callback/CMakeLists.txt b/examples/callback/CMakeLists.txt new file mode 100644 index 0000000000..6658752d25 --- /dev/null +++ b/examples/callback/CMakeLists.txt @@ -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() diff --git a/examples/callback/readme.md b/examples/callback/readme.md new file mode 100644 index 0000000000..3f191fddf1 --- /dev/null +++ b/examples/callback/readme.md @@ -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 // 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 counters; +std::map 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 lock(mutex); + if (rs2::frameset fs = frame.as()) + { + // 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 lock(mutex); + + std::cout << "\r"; + for (auto p : counters) + { + std::cout << stream_names[p.first] << "[" << p.first << "]: " << p.second << " [frames] || "; + } +} +``` diff --git a/examples/callback/rs-callback.cpp b/examples/callback/rs-callback.cpp new file mode 100644 index 0000000000..3c54651954 --- /dev/null +++ b/examples/callback/rs-callback.cpp @@ -0,0 +1,78 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2017 Intel Corporation. All Rights Reserved. + +#include // Include RealSense Cross Platform API +#include +#include +#include +#include +#include + +// 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 counters; + std::map 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 lock(mutex); + if (rs2::frameset fs = frame.as()) + { + // 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 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; +} diff --git a/examples/capture/readme.md b/examples/capture/readme.md index fb243a1c04..afd5a49b7b 100644 --- a/examples/capture/readme.md +++ b/examples/capture/readme.md @@ -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. @@ -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); ``` diff --git a/examples/capture/rs-capture.cpp b/examples/capture/rs-capture.cpp index c472718770..a7874d48ca 100644 --- a/examples/capture/rs-capture.cpp +++ b/examples/capture/rs-capture.cpp @@ -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; @@ -49,4 +47,4 @@ catch (const std::exception& e) { std::cerr << e.what() << std::endl; return EXIT_FAILURE; -} +} \ No newline at end of file diff --git a/examples/cmake/CMakeLists.txt b/examples/cmake/CMakeLists.txt index ba4c050262..cf1bf0a378 100644 --- a/examples/cmake/CMakeLists.txt +++ b/examples/cmake/CMakeLists.txt @@ -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) diff --git a/examples/cmake/readme.md b/examples/cmake/readme.md new file mode 100644 index 0000000000..a0bf81110e --- /dev/null +++ b/examples/cmake/readme.md @@ -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}) +``` + diff --git a/examples/example.hpp b/examples/example.hpp index fe3b0d9a9a..a7a319c04d 100644 --- a/examples/example.hpp +++ b/examples/example.hpp @@ -10,7 +10,13 @@ #include #include #include +#include +#include +#include +#define PI 3.14159265358979323846 +#define IMU_FRAME_WIDTH 1280 +#define IMU_FRAME_HEIGHT 720 ////////////////////////////// // Basic Data Types // ////////////////////////////// @@ -53,41 +59,27 @@ inline void draw_text(int x, int y, const char * text) glDisableClientState(GL_VERTEX_ARRAY); } +void set_viewport(const rect& r) +{ + glViewport(r.x, r.y, r.w, r.h); + glLoadIdentity(); + glMatrixMode(GL_PROJECTION); + glOrtho(0, r.w, r.h, 0, -1, +1); +} + //////////////////////// // Image display code // //////////////////////// class texture { -public: - void render(const rs2::frameset& frames, int window_width, int window_height) - { - std::vector supported_frames; - for (auto f : frames) - { - if (can_render(f)) - supported_frames.push_back(f); - } - if (supported_frames.empty()) - return; - - std::sort(supported_frames.begin(), supported_frames.end(), [](rs2::frame first, rs2::frame second) - { return first.get_profile().stream_type() < second.get_profile().stream_type(); }); - - auto image_grid = calc_grid(float2{ (float)window_width, (float)window_height }, supported_frames); - - int image_index = 0; - for (auto f : supported_frames) - { - upload(f); - show(image_grid.at(image_index)); - image_index++; - } - } + GLuint gl_handle = 0; + rs2_stream stream = RS2_STREAM_ANY; - void render(const rs2::video_frame& frame, const rect& r) +public: + void render(const rs2::video_frame& frame, const rect& rect) { upload(frame); - show(r.adjust_ratio({ float(width), float(height) })); + show(rect.adjust_ratio({ (float)frame.get_width(), (float)frame.get_height() })); } void upload(const rs2::video_frame& frame) @@ -99,8 +91,8 @@ class texture GLenum err = glGetError(); auto format = frame.get_profile().format(); - width = frame.get_width(); - height = frame.get_height(); + auto width = frame.get_width(); + auto height = frame.get_height(); stream = frame.get_profile().stream_type(); glBindTexture(GL_TEXTURE_2D, gl_handle); @@ -128,92 +120,247 @@ class texture glBindTexture(GL_TEXTURE_2D, 0); } - GLuint get_gl_handle() { return gl_handle; } - void show(const rect& r) const { if (!gl_handle) return; + set_viewport(r); + glBindTexture(GL_TEXTURE_2D, gl_handle); glEnable(GL_TEXTURE_2D); - glBegin(GL_QUAD_STRIP); - glTexCoord2f(0.f, 1.f); glVertex2f(r.x, r.y + r.h); - glTexCoord2f(0.f, 0.f); glVertex2f(r.x, r.y); - glTexCoord2f(1.f, 1.f); glVertex2f(r.x + r.w, r.y + r.h); - glTexCoord2f(1.f, 0.f); glVertex2f(r.x + r.w, r.y); + glBegin(GL_QUADS); + glTexCoord2f(0, 0); glVertex2f(0, 0); + glTexCoord2f(0, 1); glVertex2f(0, r.h); + glTexCoord2f(1, 1); glVertex2f(r.w, r.h); + glTexCoord2f(1, 0); glVertex2f(r.w, 0); glEnd(); glDisable(GL_TEXTURE_2D); glBindTexture(GL_TEXTURE_2D, 0); + draw_text(0.05 * r.w, r.h - 0.05*r.h, rs2_stream_to_string(stream)); + } + + GLuint get_gl_handle() { return gl_handle; } +}; - draw_text((int)r.x + 15, (int)r.y + 20, rs2_stream_to_string(stream)); +class imu_drawer +{ +public: + void render(const rs2::motion_frame& frame, const rect& r) + { + draw_motion(frame, r.adjust_ratio({ IMU_FRAME_WIDTH, IMU_FRAME_HEIGHT })); } + GLuint get_gl_handle() { return _gl_handle; } + private: - GLuint gl_handle = 0; - int width = 0; - int height = 0; - rs2_stream stream = RS2_STREAM_ANY; + GLuint _gl_handle = 0; - bool can_render(const rs2::frame& f) const + void draw_motion(const rs2::motion_frame& f, const rect& r) { - auto format = f.get_profile().format(); - switch (format) + if (!_gl_handle) + glGenTextures(1, &_gl_handle); + + set_viewport(r); + draw_text(0.05 * r.w, r.h - 0.1*r.h, f.get_profile().stream_name().c_str()); + + auto md = f.get_motion_data(); + auto x = md.x; + auto y = md.y; + auto z = md.z; + + glMatrixMode(GL_PROJECTION); + glPushMatrix(); + glLoadIdentity(); + + glOrtho(-2.8, 2.8, -2.4, 2.4, -7, 7); + + glRotatef(25, 1.0f, 0.0f, 0.0f); + + glTranslatef(0, -0.33f, -1.f); + + glRotatef(-135, 0.0f, 1.0f, 0.0f); + + glRotatef(180, 0.0f, 0.0f, 1.0f); + glRotatef(-90, 0.0f, 1.0f, 0.0f); + + draw_axes(); + + draw_circle(1, 0, 0, 0, 1, 0); + draw_circle(0, 1, 0, 0, 0, 1); + draw_circle(1, 0, 0, 0, 0, 1); + + const auto canvas_size = 230; + const auto vec_threshold = 0.01f; + float norm = std::sqrt(x * x + y * y + z * z); + if (norm < vec_threshold) { - case RS2_FORMAT_RGB8: - case RS2_FORMAT_RGBA8: - case RS2_FORMAT_Y8: - return true; - default: - return false; + const auto radius = 0.05; + static const int circle_points = 100; + static const float angle = 2.0f * 3.1416f / circle_points; + + glColor3f(1.0f, 1.0f, 1.0f); + glBegin(GL_POLYGON); + double angle1 = 0.0; + glVertex2d(radius * cos(0.0), radius * sin(0.0)); + int i; + for (i = 0; i < circle_points; i++) + { + glVertex2d(radius * cos(angle1), radius *sin(angle1)); + angle1 += angle; + } + glEnd(); + } + else + { + auto vectorWidth = 5.f; + glLineWidth(vectorWidth); + glBegin(GL_LINES); + glColor3f(1.0f, 1.0f, 1.0f); + glVertex3f(0.0f, 0.0f, 0.0f); + glVertex3f(x / norm, y / norm, z / norm); + glEnd(); + + // Save model and projection matrix for later + GLfloat model[16]; + glGetFloatv(GL_MODELVIEW_MATRIX, model); + GLfloat proj[16]; + glGetFloatv(GL_PROJECTION_MATRIX, proj); + + glLoadIdentity(); + glOrtho(-canvas_size, canvas_size, -canvas_size, canvas_size, -1, +1); + + std::ostringstream s1; + const auto precision = 3; + + glRotatef(180, 1.0f, 0.0f, 0.0f); + + s1 << "(" << std::fixed << std::setprecision(precision) << x << "," << std::fixed << std::setprecision(precision) << y << "," << std::fixed << std::setprecision(precision) << z << ")"; + print_text_in_3d(x, y, z, s1.str().c_str(), false, model, proj, 1 / norm); + + std::ostringstream s2; + s2 << std::setprecision(precision) << norm; + print_text_in_3d(x / 2, y / 2, z / 2, s2.str().c_str(), true, model, proj, 1 / norm); } + glMatrixMode(GL_PROJECTION); + glPopMatrix(); } - rect calc_grid(float2 window, int streams) + //IMU drawing helper functions + void multiply_vector_by_matrix(GLfloat vec[], GLfloat mat[], GLfloat* result) { - if (window.x <= 0 || window.y <= 0 || streams <= 0) - throw std::runtime_error("invalid window configuration request, failed to calculate window grid"); - float ratio = window.x / window.y; - auto x = sqrt(ratio * (float)streams); - auto y = (float)streams / x; - auto w = round(x); - auto h = round(y); - if (w == 0 || h == 0) - throw std::runtime_error("invalid window configuration request, failed to calculate window grid"); - while (w*h > streams) - h > w ? h-- : w--; - while (w*h < streams) - h > w ? w++ : h++; - auto new_w = round(window.x / w); - auto new_h = round(window.y / h); - // column count, line count, cell width cell height - return rect{ static_cast(w), static_cast(h), static_cast(new_w), static_cast(new_h) }; + const auto N = 4; + for (int i = 0; i < N; i++) + { + result[i] = 0; + for (int j = 0; j < N; j++) + { + result[i] += vec[j] * mat[N*j + i]; + } + } + return; } - std::vector calc_grid(float2 window, std::vector& frames) + float2 xyz_to_xy(float x, float y, float z, GLfloat model[], GLfloat proj[], float vec_norm) { - auto grid = calc_grid(window, frames.size()); + GLfloat vec[4] = { x, y, z, 0 }; + float tmp_result[4]; + float result[4]; - int index = 0; - std::vector rv; - int curr_line = -1; - for (auto f : frames) - { - auto mod = index % (int)grid.x; - auto fw = (float)frames[index].get_width(); - auto fh = (float)frames[index].get_height(); + const auto canvas_size = 230; - float cell_x_postion = (float)(mod * grid.w); - if (mod == 0) curr_line++; - float cell_y_position = curr_line * grid.h; + multiply_vector_by_matrix(vec, model, tmp_result); + multiply_vector_by_matrix(tmp_result, proj, result); - auto r = rect{ cell_x_postion, cell_y_position, grid.w, grid.h }; - rv.push_back(r.adjust_ratio(float2{ fw, fh })); - index++; - } + return{ canvas_size * vec_norm *result[0], canvas_size * vec_norm *result[1] }; + } - return rv; + void print_text_in_3d(float x, float y, float z, const char* text, bool center_text, GLfloat model[], GLfloat proj[], float vec_norm) + { + auto xy = xyz_to_xy(x, y, z, model, proj, vec_norm); + auto w = (center_text) ? stb_easy_font_width((char*)text) : 0; + glColor3f(1.0f, 1.0f, 1.0f); + draw_text((int)(xy.x - w / 2), (int)xy.y, text); } + + static void draw_axes(float axis_size = 1.f, float axisWidth = 4.f) + { + // Triangles For X axis + glBegin(GL_TRIANGLES); + glColor3f(1.0f, 0.0f, 0.0f); + glVertex3f(axis_size * 1.1f, 0.f, 0.f); + glVertex3f(axis_size, -axis_size * 0.05f, 0.f); + glVertex3f(axis_size, axis_size * 0.05f, 0.f); + glVertex3f(axis_size * 1.1f, 0.f, 0.f); + glVertex3f(axis_size, 0.f, -axis_size * 0.05f); + glVertex3f(axis_size, 0.f, axis_size * 0.05f); + glEnd(); + + // Triangles For Y axis + glBegin(GL_TRIANGLES); + glColor3f(0.f, 1.f, 0.f); + glVertex3f(0.f, axis_size * 1.1f, 0.0f); + glVertex3f(0.f, axis_size, 0.05f * axis_size); + glVertex3f(0.f, axis_size, -0.05f * axis_size); + glVertex3f(0.f, axis_size * 1.1f, 0.0f); + glVertex3f(0.05f * axis_size, axis_size, 0.f); + glVertex3f(-0.05f * axis_size, axis_size, 0.f); + glEnd(); + + // Triangles For Z axis + glBegin(GL_TRIANGLES); + glColor3f(0.0f, 0.0f, 1.0f); + glVertex3f(0.0f, 0.0f, 1.1f * axis_size); + glVertex3f(0.0f, 0.05f * axis_size, 1.0f * axis_size); + glVertex3f(0.0f, -0.05f * axis_size, 1.0f * axis_size); + glVertex3f(0.0f, 0.0f, 1.1f * axis_size); + glVertex3f(0.05f * axis_size, 0.f, 1.0f * axis_size); + glVertex3f(-0.05f * axis_size, 0.f, 1.0f * axis_size); + glEnd(); + + glLineWidth(axisWidth); + + // Drawing Axis + glBegin(GL_LINES); + // X axis - Red + glColor3f(1.0f, 0.0f, 0.0f); + glVertex3f(0.0f, 0.0f, 0.0f); + glVertex3f(axis_size, 0.0f, 0.0f); + + // Y axis - Green + glColor3f(0.0f, 1.0f, 0.0f); + glVertex3f(0.0f, 0.0f, 0.0f); + glVertex3f(0.0f, axis_size, 0.0f); + + // Z axis - Blue + glColor3f(0.0f, 0.0f, 1.0f); + glVertex3f(0.0f, 0.0f, 0.0f); + glVertex3f(0.0f, 0.0f, axis_size); + glEnd(); + } + + // intensity is grey intensity + static void draw_circle(float xx, float xy, float xz, float yx, float yy, float yz, float radius = 1.1, float3 center = { 0.0, 0.0, 0.0 }, float intensity = 0.5f) + { + const auto N = 50; + glColor3f(intensity, intensity, intensity); + glLineWidth(2); + glBegin(GL_LINE_STRIP); + + for (int i = 0; i <= N; i++) + { + const double theta = (2 * PI / N) * i; + const auto cost = static_cast(cos(theta)); + const auto sint = static_cast(sin(theta)); + glVertex3f( + center.x + radius * (xx * cost + yx * sint), + center.y + radius * (xy * cost + yy * sint), + center.z + radius * (xz * cost + yz * sint) + ); + } + glEnd(); + } + }; class window @@ -293,11 +440,129 @@ class window glfwTerminate(); } + void show(rs2::frame frame) + { + show(frame, { 0, 0, (float)_width, (float)_height }); + } + + void show(const rs2::frame& frame, const rect& rect) + { + if (auto fs = frame.as()) + render_frameset(fs, rect); + if (auto vf = frame.as()) + render_video_frame(vf, rect); + if (auto mf = frame.as()) + render_motoin_frame(mf, rect); + } + operator GLFWwindow*() { return win; } private: GLFWwindow * win; + std::map _textures; + std::map _imus; int _width, _height; + + void render_video_frame(const rs2::video_frame& f, const rect& r) + { + auto& t = _textures[f.get_profile().unique_id()]; + t.render(f, r); + } + + void render_motoin_frame(const rs2::motion_frame& f, const rect& r) + { + auto& i = _imus[f.get_profile().unique_id()]; + i.render(f, r); + } + + void render_frameset(const rs2::frameset& frames, const rect& r) + { + std::vector supported_frames; + for (auto f : frames) + { + if (can_render(f)) + supported_frames.push_back(f); + } + if (supported_frames.empty()) + return; + + std::sort(supported_frames.begin(), supported_frames.end(), [](rs2::frame first, rs2::frame second) + { return first.get_profile().stream_type() < second.get_profile().stream_type(); }); + + auto image_grid = calc_grid(r, supported_frames); + + int image_index = 0; + for (auto f : supported_frames) + { + auto r = image_grid.at(image_index); + show(f, r); + image_index++; + } + } + + bool can_render(const rs2::frame& f) const + { + auto format = f.get_profile().format(); + switch (format) + { + case RS2_FORMAT_RGB8: + case RS2_FORMAT_RGBA8: + case RS2_FORMAT_Y8: + case RS2_FORMAT_MOTION_XYZ32F: + return true; + default: + return false; + } + } + + rect calc_grid(rect r, int streams) + { + if (r.w <= 0 || r.h <= 0 || streams <= 0) + throw std::runtime_error("invalid window configuration request, failed to calculate window grid"); + float ratio = r.w / r.h; + auto x = sqrt(ratio * (float)streams); + auto y = (float)streams / x; + auto w = round(x); + auto h = round(y); + if (w == 0 || h == 0) + throw std::runtime_error("invalid window configuration request, failed to calculate window grid"); + while (w*h > streams) + h > w ? h-- : w--; + while (w*h < streams) + h > w ? w++ : h++; + auto new_w = round(r.w / w); + auto new_h = round(r.h / h); + // column count, line count, cell width cell height + return rect{ static_cast(w), static_cast(h), static_cast(new_w), static_cast(new_h) }; + } + + std::vector calc_grid(rect r, std::vector& frames) + { + auto grid = calc_grid(r, frames.size()); + + std::vector rv; + int curr_line = -1; + + for (int i = 0; i < frames.size(); i++) + { + auto mod = i % (int)grid.x; + float fw = IMU_FRAME_WIDTH; + float fh = IMU_FRAME_HEIGHT; + if (auto vf = frames[i].as()) + { + fw = (float)vf.get_width(); + fh = (float)vf.get_height(); + } + float cell_x_postion = (float)(mod * grid.w); + if (mod == 0) curr_line++; + float cell_y_position = curr_line * grid.h; + float2 margin = { grid.w * 0.02f, grid.h * 0.02f }; + auto r = rect{ cell_x_postion + margin.x, cell_y_position + margin.y, grid.w - 2 * margin.x, grid.h }; + rv.push_back(r.adjust_ratio(float2{ fw, fh })); + } + + return rv; + } }; // Struct for managing rotation of pointcloud view @@ -314,7 +579,6 @@ struct glfw_state { texture tex; }; - // Handles all the OpenGL calls needed to display the point cloud void draw_pointcloud(float width, float height, glfw_state& app_state, rs2::points& points) { diff --git a/examples/multicam/rs-multicam.cpp b/examples/multicam/rs-multicam.cpp index 4e359dec36..46a53ef912 100644 --- a/examples/multicam/rs-multicam.cpp +++ b/examples/multicam/rs-multicam.cpp @@ -122,17 +122,10 @@ class device_container // For each device get its frames for (auto&& id_to_frame : view.second.frames_per_stream) { - // If the frame is available - if (id_to_frame.second) - { - view.second.tex.upload(id_to_frame.second); - } rect frame_location{ view_width * (stream_no % cols), view_height * (stream_no / cols), view_width, view_height }; if (rs2::video_frame vid_frame = id_to_frame.second.as()) { - rect adjuested = frame_location.adjust_ratio({ static_cast(vid_frame.get_width()) - , static_cast(vid_frame.get_height()) }); - view.second.tex.show(adjuested); + view.second.tex.render(vid_frame, frame_location); stream_no++; } } diff --git a/examples/record-playback/rs-record-playback.cpp b/examples/record-playback/rs-record-playback.cpp index b788828851..7736fad1ab 100644 --- a/examples/record-playback/rs-record-playback.cpp +++ b/examples/record-playback/rs-record-playback.cpp @@ -194,7 +194,7 @@ int main(int argc, char * argv[]) try ImGui::Render(); // Render depth frames from the default configuration, the recorder or the playback - depth_image.render(depth, { app.width() / 4, 0, 3 * app.width() / 5, 3 * app.height() / 5 + 50 }); + depth_image.render(depth, { app.width() * 0.25f, app.height() * 0.25f, app.width() * 0.5f, app.height() * 0.75f }); } return EXIT_SUCCESS; } diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index 0c420a98f2..5c92d262d8 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -1,31 +1,32 @@ target_sources(${LRS_TARGET} PRIVATE - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_types.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_context.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_device.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_frame.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_option.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_processing.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_record_playback.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_sensor.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_internal.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_pipeline.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_types.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_context.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_device.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_frame.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_option.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_processing.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_record_playback.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_sensor.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_internal.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_pipeline.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_config.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_types.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_context.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_device.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_frame.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_processing.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_record_playback.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_sensor.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_internal.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_pipeline.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_types.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_context.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_device.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_frame.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_processing.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_record_playback.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_sensor.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_internal.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_pipeline.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rsutil.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs_advanced_mode.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs_advanced_mode.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_advanced_mode_command.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rsutil.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs_advanced_mode.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs_advanced_mode.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_advanced_mode_command.h" ) diff --git a/include/librealsense2/h/rs_config.h b/include/librealsense2/h/rs_config.h new file mode 100644 index 0000000000..c365b71350 --- /dev/null +++ b/include/librealsense2/h/rs_config.h @@ -0,0 +1,198 @@ +/* License: Apache 2.0. See LICENSE file in root directory. +Copyright(c) 2017 Intel Corporation. All Rights Reserved. */ + +/** \file rs_pipeline.h +* \brief +* Exposes RealSense processing-block functionality for C compilers +*/ + + +#ifndef LIBREALSENSE_RS2_CONFIG_H +#define LIBREALSENSE_RS2_CONFIG_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "rs_types.h" +#include "rs_sensor.h" + + /** + * Create a config instance + * The config allows pipeline users to request filters for the pipeline streams and device selection and configuration. + * This is an optional step in pipeline creation, as the pipeline resolves its streaming device internally. + * Config provides its users a way to set the filters and test if there is no conflict with the pipeline requirements + * from the device. It also allows the user to find a matching device for the config filters and the pipeline, in order to + * select a device explicitly, and modify its controls before streaming starts. + * + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + * \return rs2_config* A pointer to a new config instance + */ + rs2_config* rs2_create_config(rs2_error** error); + + /** + * Deletes an instance of a config + * + * \param[in] config A pointer to an instance of a config + */ + void rs2_delete_config(rs2_config* config); + + /** + * Enable a device stream explicitly, with selected stream parameters. + * The method allows the application to request a stream with specific configuration. If no stream is explicitly enabled, the pipeline + * configures the device and its streams according to the attached computer vision modules and processing blocks requirements, or + * default configuration for the first available device. + * The application can configure any of the input stream parameters according to its requirement, or set to 0 for don't care value. + * The config accumulates the application calls for enable configuration methods, until the configuration is applied. Multiple enable + * stream calls for the same stream with conflicting parameters override each other, and the last call is maintained. + * Upon calling \c resolve(), the config checks for conflicts between the application configuration requests and the attached computer + * vision modules and processing blocks requirements, and fails if conflicts are found. Before \c resolve() is called, no conflict + * check is done. + * + * \param[in] config A pointer to an instance of a config + * \param[in] stream Stream type to be enabled + * \param[in] index Stream index, used for multiple streams of the same type. -1 indicates any. + * \param[in] width Stream image width - for images streams. 0 indicates any. + * \param[in] height Stream image height - for images streams. 0 indicates any. + * \param[in] format Stream data format - pixel format for images streams, of data type for other streams. RS2_FORMAT_ANY indicates any. + * \param[in] framerate Stream frames per second. 0 indicates any. + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_enable_stream(rs2_config* config, + rs2_stream stream, + int index, + int width, + int height, + rs2_format format, + int framerate, + rs2_error** error); + + /** + * Enable all device streams explicitly. + * The conditions and behavior of this method are similar to those of \c enable_stream(). + * This filter enables all raw streams of the selected device. The device is either selected explicitly by the application, + * or by the pipeline requirements or default. The list of streams is device dependent. + * + * \param[in] config A pointer to an instance of a config + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_enable_all_stream(rs2_config* config, rs2_error ** error); + + /** + * Select a specific device explicitly by its serial number, to be used by the pipeline. + * The conditions and behavior of this method are similar to those of \c enable_stream(). + * This method is required if the application needs to set device or sensor settings prior to pipeline streaming, to enforce + * the pipeline to use the configured device. + * + * \param[in] config A pointer to an instance of a config + * \param[in] serial device serial number, as returned by RS2_CAMERA_INFO_SERIAL_NUMBER + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_enable_device(rs2_config* config, const char* serial, rs2_error ** error); + + /** + * Select a recorded device from a file, to be used by the pipeline through playback. + * The device available streams are as recorded to the file, and \c resolve() considers only this device and configuration + * as available. + * This request cannot be used if enable_record_to_file() is called for the current config, and vise versa + * By default, playback is repeated once the file ends. To control this, see 'rs2_config_enable_device_from_file_repeat_option'. + * + * \param[in] config A pointer to an instance of a config + * \param[in] file The playback file of the device + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_enable_device_from_file(rs2_config* config, const char* file, rs2_error ** error); + + /** + * Select a recorded device from a file, to be used by the pipeline through playback. + * The device available streams are as recorded to the file, and \c resolve() considers only this device and configuration + * as available. + * This request cannot be used if enable_record_to_file() is called for the current config, and vise versa + * + * \param[in] config A pointer to an instance of a config + * \param[in] file The playback file of the device + * \param[in] repeat_playback if true, when file ends the playback starts again, in an infinite loop; + if false, when file ends playback does not start again, and should by stopped manually by the user. + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_enable_device_from_file_repeat_option(rs2_config* config, const char* file, int repeat_playback, rs2_error ** error); + + /** + * Requires that the resolved device would be recorded to file + * This request cannot be used if enable_device_from_file() is called for the current config, and vise versa + * + * \param[in] config A pointer to an instance of a config + * \param[in] file The desired file for the output record + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_enable_record_to_file(rs2_config* config, const char* file, rs2_error ** error); + + + /** + * Disable a device stream explicitly, to remove any requests on this stream type. + * The stream can still be enabled due to pipeline computer vision module request. This call removes any filter on the + * stream configuration. + * + * \param[in] config A pointer to an instance of a config + * \param[in] stream Stream type, for which the filters are cleared + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_disable_stream(rs2_config* config, rs2_stream stream, rs2_error ** error); + + /** + * Disable a device stream explicitly, to remove any requests on this stream profile. + * The stream can still be enabled due to pipeline computer vision module request. This call removes any filter on the + * stream configuration. + * + * \param[in] config A pointer to an instance of a config + * \param[in] stream Stream type, for which the filters are cleared + * \param[in] index Stream index, for which the filters are cleared + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_disable_indexed_stream(rs2_config* config, rs2_stream stream, int index, rs2_error ** error); + + /** + * Disable all device stream explicitly, to remove any requests on the streams profiles. + * The streams can still be enabled due to pipeline computer vision module request. This call removes any filter on the + * streams configuration. + * + * \param[in] config A pointer to an instance of a config + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ + void rs2_config_disable_all_streams(rs2_config* config, rs2_error ** error); + + /** + * Resolve the configuration filters, to find a matching device and streams profiles. + * The method resolves the user configuration filters for the device and streams, and combines them with the requirements of + * the computer vision modules and processing blocks attached to the pipeline. If there are no conflicts of requests, it looks + * for an available device, which can satisfy all requests, and selects the first matching streams configuration. In the absence + * of any request, the rs2::config selects the first available device and the first color and depth streams configuration. + * The pipeline profile selection during \c start() follows the same method. Thus, the selected profile is the same, if no + * change occurs to the available devices occurs. + * Resolving the pipeline configuration provides the application access to the pipeline selected device for advanced control. + * The returned configuration is not applied to the device, so the application doesn't own the device sensors. However, the + * application can call \c enable_device(), to enforce the device returned by this method is selected by pipeline \c start(), + * and configure the device and sensors options or extensions before streaming starts. + * + * \param[in] config A pointer to an instance of a config + * \param[in] pipe The pipeline for which the selected filters are applied + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + * \return A matching device and streams profile, which satisfies the filters and pipeline requests. + */ + rs2_pipeline_profile* rs2_config_resolve(rs2_config* config, rs2_pipeline* pipe, rs2_error ** error); + + /** + * Check if the config can resolve the configuration filters, to find a matching device and streams profiles. + * The resolution conditions are as described in \c resolve(). + * + * \param[in] config A pointer to an instance of a config + * \param[in] pipe The pipeline for which the selected filters are applied + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + * \return True if a valid profile selection exists, false if no selection can be found under the config filters and the available devices. + */ + int rs2_config_can_resolve(rs2_config* config, rs2_pipeline* pipe, rs2_error ** error); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/include/librealsense2/h/rs_pipeline.h b/include/librealsense2/h/rs_pipeline.h index f617236a79..1018c778d1 100644 --- a/include/librealsense2/h/rs_pipeline.h +++ b/include/librealsense2/h/rs_pipeline.h @@ -16,6 +16,7 @@ extern "C" { #include "rs_types.h" #include "rs_sensor.h" +#include "rs_config.h" /** * Create a pipeline instance @@ -111,7 +112,6 @@ extern "C" { */ rs2_pipeline_profile* rs2_pipeline_start(rs2_pipeline* pipe, rs2_error ** error); - /** * Start the pipeline streaming according to the configuraion. * The pipeline streaming loop captures samples from the device, and delivers them to the attached computer vision modules @@ -132,6 +132,72 @@ extern "C" { */ rs2_pipeline_profile* rs2_pipeline_start_with_config(rs2_pipeline* pipe, rs2_config* config, rs2_error ** error); + /** + * Start the pipeline streaming with its default configuration. + * The pipeline captures samples from the device, and delivers them to the through the provided frame callback. + * Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised. + * When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception. + * + * \param[in] pipe A pointer to an instance of the pipeline + * \param[in] on_frame function pointer to register as per-frame callback + * \param[in] user auxiliary data the user wishes to receive together with every frame callback + * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored + * \return The actual pipeline device and streams profile, which was successfully configured to the streaming device. + */ + rs2_pipeline_profile* rs2_pipeline_start_with_callback(rs2_pipeline* pipe, rs2_frame_callback_ptr on_frame, void* user, rs2_error ** error); + + /** + * Start the pipeline streaming with its default configuration. + * The pipeline captures samples from the device, and delivers them to the through the provided frame callback. + * Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised. + * When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception. + * + * \param[in] pipe A pointer to an instance of the pipeline + * \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant streaming lock + * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored + * \return The actual pipeline device and streams profile, which was successfully configured to the streaming device. + */ + rs2_pipeline_profile* rs2_pipeline_start_with_callback_cpp(rs2_pipeline* pipe, rs2_frame_callback* callback, rs2_error ** error); + + /** + * Start the pipeline streaming according to the configuraion. + * The pipeline captures samples from the device, and delivers them to the through the provided frame callback. + * Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised. + * When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception. + * The pipeline selects and activates the device upon start, according to configuration or a default configuration. + * When the rs2::config is provided to the method, the pipeline tries to activate the config \c resolve() result. If the application + * requests are conflicting with pipeline computer vision modules or no matching device is available on the platform, the method fails. + * Available configurations and devices may change between config \c resolve() call and pipeline start, in case devices are connected + * or disconnected, or another application acquires ownership of a device. + * + * \param[in] pipe A pointer to an instance of the pipeline + * \param[in] config A rs2::config with requested filters on the pipeline configuration. By default no filters are applied. + * \param[in] on_frame function pointer to register as per-frame callback + * \param[in] user auxiliary data the user wishes to receive together with every frame callback + * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored + * \return The actual pipeline device and streams profile, which was successfully configured to the streaming device. + */ + rs2_pipeline_profile* rs2_pipeline_start_with_config_and_callback(rs2_pipeline* pipe, rs2_config* config, rs2_frame_callback_ptr on_frame, void* user, rs2_error ** error); + + /** + * Start the pipeline streaming according to the configuraion. + * The pipeline captures samples from the device, and delivers them to the through the provided frame callback. + * Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised. + * When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception. + * The pipeline selects and activates the device upon start, according to configuration or a default configuration. + * When the rs2::config is provided to the method, the pipeline tries to activate the config \c resolve() result. If the application + * requests are conflicting with pipeline computer vision modules or no matching device is available on the platform, the method fails. + * Available configurations and devices may change between config \c resolve() call and pipeline start, in case devices are connected + * or disconnected, or another application acquires ownership of a device. + * + * \param[in] pipe A pointer to an instance of the pipeline + * \param[in] config A rs2::config with requested filters on the pipeline configuration. By default no filters are applied. + * \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant streaming lock + * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored + * \return The actual pipeline device and streams profile, which was successfully configured to the streaming device. + */ + rs2_pipeline_profile* rs2_pipeline_start_with_config_and_callback_cpp(rs2_pipeline* pipe, rs2_config* config, rs2_frame_callback* callback, rs2_error ** error); + /** * Return the active device and streams profiles, used by the pipeline. * The pipeline streams profiles are selected during \c start(). The method returns a valid result only when the pipeline is active - @@ -175,181 +241,6 @@ extern "C" { */ void rs2_delete_pipeline_profile(rs2_pipeline_profile* profile); - /** - * Create a config instance - * The config allows pipeline users to request filters for the pipeline streams and device selection and configuration. - * This is an optional step in pipeline creation, as the pipeline resolves its streaming device internally. - * Config provides its users a way to set the filters and test if there is no conflict with the pipeline requirements - * from the device. It also allows the user to find a matching device for the config filters and the pipeline, in order to - * select a device explicitly, and modify its controls before streaming starts. - * - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - * \return rs2_config* A pointer to a new config instance - */ - rs2_config* rs2_create_config(rs2_error** error); - - /** - * Deletes an instance of a config - * - * \param[in] config A pointer to an instance of a config - */ - void rs2_delete_config(rs2_config* config); - - /** - * Enable a device stream explicitly, with selected stream parameters. - * The method allows the application to request a stream with specific configuration. If no stream is explicitly enabled, the pipeline - * configures the device and its streams according to the attached computer vision modules and processing blocks requirements, or - * default configuration for the first available device. - * The application can configure any of the input stream parameters according to its requirement, or set to 0 for don't care value. - * The config accumulates the application calls for enable configuration methods, until the configuration is applied. Multiple enable - * stream calls for the same stream with conflicting parameters override each other, and the last call is maintained. - * Upon calling \c resolve(), the config checks for conflicts between the application configuration requests and the attached computer - * vision modules and processing blocks requirements, and fails if conflicts are found. Before \c resolve() is called, no conflict - * check is done. - * - * \param[in] config A pointer to an instance of a config - * \param[in] stream Stream type to be enabled - * \param[in] index Stream index, used for multiple streams of the same type. -1 indicates any. - * \param[in] width Stream image width - for images streams. 0 indicates any. - * \param[in] height Stream image height - for images streams. 0 indicates any. - * \param[in] format Stream data format - pixel format for images streams, of data type for other streams. RS2_FORMAT_ANY indicates any. - * \param[in] framerate Stream frames per second. 0 indicates any. - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_enable_stream(rs2_config* config, - rs2_stream stream, - int index, - int width, - int height, - rs2_format format, - int framerate, - rs2_error** error); - - /** - * Enable all device streams explicitly. - * The conditions and behavior of this method are similar to those of \c enable_stream(). - * This filter enables all raw streams of the selected device. The device is either selected explicitly by the application, - * or by the pipeline requirements or default. The list of streams is device dependent. - * - * \param[in] config A pointer to an instance of a config - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_enable_all_stream(rs2_config* config, rs2_error ** error); - - /** - * Select a specific device explicitly by its serial number, to be used by the pipeline. - * The conditions and behavior of this method are similar to those of \c enable_stream(). - * This method is required if the application needs to set device or sensor settings prior to pipeline streaming, to enforce - * the pipeline to use the configured device. - * - * \param[in] config A pointer to an instance of a config - * \param[in] serial device serial number, as returned by RS2_CAMERA_INFO_SERIAL_NUMBER - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_enable_device(rs2_config* config, const char* serial, rs2_error ** error); - - /** - * Select a recorded device from a file, to be used by the pipeline through playback. - * The device available streams are as recorded to the file, and \c resolve() considers only this device and configuration - * as available. - * This request cannot be used if enable_record_to_file() is called for the current config, and vise versa - * By default, playback is repeated once the file ends. To control this, see 'rs2_config_enable_device_from_file_repeat_option'. - * - * \param[in] config A pointer to an instance of a config - * \param[in] file The playback file of the device - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_enable_device_from_file(rs2_config* config, const char* file, rs2_error ** error); - - /** - * Select a recorded device from a file, to be used by the pipeline through playback. - * The device available streams are as recorded to the file, and \c resolve() considers only this device and configuration - * as available. - * This request cannot be used if enable_record_to_file() is called for the current config, and vise versa - * - * \param[in] config A pointer to an instance of a config - * \param[in] file The playback file of the device - * \param[in] repeat_playback if true, when file ends the playback starts again, in an infinite loop; - if false, when file ends playback does not start again, and should by stopped manually by the user. - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_enable_device_from_file_repeat_option(rs2_config* config, const char* file, int repeat_playback, rs2_error ** error); - - /** - * Requires that the resolved device would be recorded to file - * This request cannot be used if enable_device_from_file() is called for the current config, and vise versa - * - * \param[in] config A pointer to an instance of a config - * \param[in] file The desired file for the output record - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_enable_record_to_file(rs2_config* config, const char* file, rs2_error ** error); - - - /** - * Disable a device stream explicitly, to remove any requests on this stream type. - * The stream can still be enabled due to pipeline computer vision module request. This call removes any filter on the - * stream configuration. - * - * \param[in] config A pointer to an instance of a config - * \param[in] stream Stream type, for which the filters are cleared - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_disable_stream(rs2_config* config, rs2_stream stream, rs2_error ** error); - - /** - * Disable a device stream explicitly, to remove any requests on this stream profile. - * The stream can still be enabled due to pipeline computer vision module request. This call removes any filter on the - * stream configuration. - * - * \param[in] config A pointer to an instance of a config - * \param[in] stream Stream type, for which the filters are cleared - * \param[in] index Stream index, for which the filters are cleared - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_disable_indexed_stream(rs2_config* config, rs2_stream stream, int index, rs2_error ** error); - - /** - * Disable all device stream explicitly, to remove any requests on the streams profiles. - * The streams can still be enabled due to pipeline computer vision module request. This call removes any filter on the - * streams configuration. - * - * \param[in] config A pointer to an instance of a config - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ - void rs2_config_disable_all_streams(rs2_config* config, rs2_error ** error); - - /** - * Resolve the configuration filters, to find a matching device and streams profiles. - * The method resolves the user configuration filters for the device and streams, and combines them with the requirements of - * the computer vision modules and processing blocks attached to the pipeline. If there are no conflicts of requests, it looks - * for an available device, which can satisfy all requests, and selects the first matching streams configuration. In the absence - * of any request, the rs2::config selects the first available device and the first color and depth streams configuration. - * The pipeline profile selection during \c start() follows the same method. Thus, the selected profile is the same, if no - * change occurs to the available devices occurs. - * Resolving the pipeline configuration provides the application access to the pipeline selected device for advanced control. - * The returned configuration is not applied to the device, so the application doesn't own the device sensors. However, the - * application can call \c enable_device(), to enforce the device returned by this method is selected by pipeline \c start(), - * and configure the device and sensors options or extensions before streaming starts. - * - * \param[in] config A pointer to an instance of a config - * \param[in] pipe The pipeline for which the selected filters are applied - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - * \return A matching device and streams profile, which satisfies the filters and pipeline requests. - */ - rs2_pipeline_profile* rs2_config_resolve(rs2_config* config, rs2_pipeline* pipe, rs2_error ** error); - - /** - * Check if the config can resolve the configuration filters, to find a matching device and streams profiles. - * The resolution conditions are as described in \c resolve(). - * - * \param[in] config A pointer to an instance of a config - * \param[in] pipe The pipeline for which the selected filters are applied - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - * \return True if a valid profile selection exists, false if no selection can be found under the config filters and the available devices. - */ - int rs2_config_can_resolve(rs2_config* config, rs2_pipeline* pipe, rs2_error ** error); - #ifdef __cplusplus } #endif diff --git a/include/librealsense2/h/rs_processing.h b/include/librealsense2/h/rs_processing.h index 7836470b18..351f003c34 100644 --- a/include/librealsense2/h/rs_processing.h +++ b/include/librealsense2/h/rs_processing.h @@ -187,6 +187,13 @@ rs2_processing_block* rs2_create_disparity_transform_block(unsigned char transfo */ rs2_processing_block* rs2_create_hole_filling_filter_block(rs2_error** error); +/** +* Creates a rates printer block. The printer prints the actual FPS of the invoked frame stream. +* The block ignores reapiting frames and calculats the FPS only if the frame number of the relevant frame was changed. +* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored +*/ +rs2_processing_block* rs2_create_rates_printer_block(rs2_error** error); + #ifdef __cplusplus } #endif diff --git a/include/librealsense2/hpp/rs_frame.hpp b/include/librealsense2/hpp/rs_frame.hpp index 2cfb65932a..5ed99a74df 100644 --- a/include/librealsense2/hpp/rs_frame.hpp +++ b/include/librealsense2/hpp/rs_frame.hpp @@ -791,7 +791,7 @@ namespace rs2 * Retrieve back the motion data from IMU sensor * \return rs2_vector - 3D vector in Euclidean coordinate space. */ - rs2_vector get_motion_data() + rs2_vector get_motion_data() const { auto data = reinterpret_cast(get_data()); return rs2_vector{ data[0], data[1], data[2] }; @@ -998,7 +998,5 @@ namespace rs2 private: size_t _size; }; - - } #endif // LIBREALSENSE_RS2_FRAME_HPP diff --git a/include/librealsense2/hpp/rs_pipeline.hpp b/include/librealsense2/hpp/rs_pipeline.hpp index 9500f37da3..2342d15498 100644 --- a/include/librealsense2/hpp/rs_pipeline.hpp +++ b/include/librealsense2/hpp/rs_pipeline.hpp @@ -403,6 +403,54 @@ namespace rs2 return pipeline_profile(p); } + /** + * Start the pipeline streaming with its default configuration. + * The pipeline captures samples from the device, and delivers them to the through the provided frame callback. + * Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised. + * When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception. + * + * \param[in] callback Stream callback, can be any callable object accepting rs2::frame + * \return The actual pipeline device and streams profile, which was successfully configured to the streaming device. + */ + template + pipeline_profile start(S callback) + { + rs2_error* e = nullptr; + auto p = std::shared_ptr( + rs2_pipeline_start_with_callback_cpp(_pipeline.get(), new frame_callback(callback), &e), + rs2_delete_pipeline_profile); + + error::handle(e); + return pipeline_profile(p); + } + + /** + * Start the pipeline streaming according to the configuraion. + * The pipeline captures samples from the device, and delivers them to the through the provided frame callback. + * Starting the pipeline is possible only when it is not started. If the pipeline was started, an exception is raised. + * When starting the pipeline with a callback both \c wait_for_frames() or \c poll_for_frames() will throw exception. + * The pipeline selects and activates the device upon start, according to configuration or a default configuration. + * When the rs2::config is provided to the method, the pipeline tries to activate the config \c resolve() result. + * If the application requests are conflicting with pipeline computer vision modules or no matching device is available on + * the platform, the method fails. + * Available configurations and devices may change between config \c resolve() call and pipeline start, in case devices + * are connected or disconnected, or another application acquires ownership of a device. + * + * \param[in] config A rs2::config with requested filters on the pipeline configuration. By default no filters are applied. + * \param[in] callback Stream callback, can be any callable object accepting rs2::frame + * \return The actual pipeline device and streams profile, which was successfully configured to the streaming device. + */ + template + pipeline_profile start(const config& config, S callback) + { + rs2_error* e = nullptr; + auto p = std::shared_ptr( + rs2_pipeline_start_with_config_and_callback_cpp(_pipeline.get(), config.get().get(), new frame_callback(callback), &e), + rs2_delete_pipeline_profile); + + error::handle(e); + return pipeline_profile(p); + } /** * Stop the pipeline streaming. diff --git a/include/librealsense2/hpp/rs_processing.hpp b/include/librealsense2/hpp/rs_processing.hpp index ec17796fd3..127d6fb35f 100644 --- a/include/librealsense2/hpp/rs_processing.hpp +++ b/include/librealsense2/hpp/rs_processing.hpp @@ -776,5 +776,29 @@ namespace rs2 return block; } }; + + class rates_printer : public filter + { + public: + /** + * Create hole filling processing block + * the processing perform the hole filling base on different hole filling mode. + */ + rates_printer() : filter(init(), 1) {} + + private: + friend class context; + + std::shared_ptr init() + { + rs2_error* e = nullptr; + auto block = std::shared_ptr( + rs2_create_rates_printer_block(&e), + rs2_delete_processing_block); + error::handle(e); + + return block; + } + }; } #endif // LIBREALSENSE_RS2_PROCESSING_HPP diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 647afde26e..95a27ece89 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -8,6 +8,7 @@ include(${_rel_path}/media/CMakeLists.txt) include(${_rel_path}/mock/CMakeLists.txt) include(${_rel_path}/proc/CMakeLists.txt) include(${_rel_path}/res/CMakeLists.txt) +include(${_rel_path}/pipeline/CMakeLists.txt) if(FORCE_LIBUVC) include(${_rel_path}/libuvc/CMakeLists.txt) @@ -41,7 +42,6 @@ target_sources(${LRS_TARGET} PRIVATE "${CMAKE_CURRENT_LIST_DIR}/environment.cpp" "${CMAKE_CURRENT_LIST_DIR}/device_hub.cpp" - "${CMAKE_CURRENT_LIST_DIR}/pipeline.cpp" "${CMAKE_CURRENT_LIST_DIR}/archive.cpp" "${CMAKE_CURRENT_LIST_DIR}/context.cpp" "${CMAKE_CURRENT_LIST_DIR}/device.cpp" @@ -65,8 +65,6 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/software-device.h" "${CMAKE_CURRENT_LIST_DIR}/environment.h" "${CMAKE_CURRENT_LIST_DIR}/device_hub.h" - "${CMAKE_CURRENT_LIST_DIR}/pipeline.h" - "${CMAKE_CURRENT_LIST_DIR}/config.h" "${CMAKE_CURRENT_LIST_DIR}/archive.h" "${CMAKE_CURRENT_LIST_DIR}/concurrency.h" "${CMAKE_CURRENT_LIST_DIR}/context.h" diff --git a/src/ds5/ds5-factory.cpp b/src/ds5/ds5-factory.cpp index 4aa3b37e58..b40f21198d 100644 --- a/src/ds5/ds5-factory.cpp +++ b/src/ds5/ds5-factory.cpp @@ -430,8 +430,8 @@ namespace librealsense tags.push_back({ RS2_STREAM_COLOR, -1, width, height, RS2_FORMAT_RGB8, fps, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); tags.push_back({ RS2_STREAM_DEPTH, -1, width, height, RS2_FORMAT_Z16, fps, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); tags.push_back({ RS2_STREAM_INFRARED, -1, width, height, RS2_FORMAT_Y8, fps, profile_tag::PROFILE_TAG_SUPERSET }); - tags.push_back({RS2_STREAM_GYRO, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, 400, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); - tags.push_back({RS2_STREAM_ACCEL, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, 250, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); + tags.push_back({RS2_STREAM_GYRO, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, 200, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); + tags.push_back({RS2_STREAM_ACCEL, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, 63, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); return tags; }; @@ -457,7 +457,7 @@ namespace librealsense { std::vector tags; tags.push_back({RS2_STREAM_GYRO, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, 200, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); - tags.push_back({RS2_STREAM_ACCEL, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, 125, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); + tags.push_back({RS2_STREAM_ACCEL, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, 63, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT }); return tags; }; diff --git a/src/pipeline.cpp b/src/pipeline.cpp deleted file mode 100644 index 28aac11713..0000000000 --- a/src/pipeline.cpp +++ /dev/null @@ -1,672 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2015 Intel Corporation. All Rights Reserved. - -#include -#include "proc/synthetic-stream.h" -#include "proc/syncer-processing-block.h" -#include "pipeline.h" -#include "stream.h" -#include "media/record/record_device.h" -#include "media/ros/ros_writer.h" - -namespace librealsense -{ - pipeline_processing_block::pipeline_processing_block(const std::vector& streams_to_aggregate) : - _queue(new single_consumer_frame_queue(1)), - _streams_ids(streams_to_aggregate) - { - auto processing_callback = [&](frame_holder frame, synthetic_source_interface* source) - { - handle_frame(std::move(frame), source); - }; - - set_processing_callback(std::shared_ptr( - new internal_frame_processor_callback(processing_callback))); - } - - void pipeline_processing_block::handle_frame(frame_holder frame, synthetic_source_interface* source) - { - std::lock_guard lock(_mutex); - auto comp = dynamic_cast(frame.frame); - if (comp) - { - for (auto i = 0; i< comp->get_embedded_frames_count(); i++) - { - auto f = comp->get_frame(i); - f->acquire(); - _last_set[f->get_stream()->get_unique_id()] = f; - } - - for (int s : _streams_ids) - { - if (!_last_set[s]) - return; - } - - std::vector set; - for (auto&& s : _last_set) - { - set.push_back(s.second.clone()); - } - auto fref = source->allocate_composite_frame(std::move(set)); - if (!fref) - { - LOG_ERROR("Failed to allocate composite frame"); - return; - } - _queue->enqueue(fref); - } - else - { - LOG_ERROR("Non composite frame arrived to pipeline::handle_frame"); - assert(false); - } - } - - bool pipeline_processing_block::dequeue(frame_holder* item, unsigned int timeout_ms) - { - return _queue->dequeue(item, timeout_ms); - } - - bool pipeline_processing_block::try_dequeue(frame_holder* item) - { - return _queue->try_dequeue(item); - } - - /* - - ______ ______ .__ __. _______ __ _______ - / | / __ \ | \ | | | ____|| | / _____| - | ,----'| | | | | \| | | |__ | | | | __ - | | | | | | | . ` | | __| | | | | |_ | - | `----.| `--' | | |\ | | | | | | |__| | - \______| \______/ |__| \__| |__| |__| \______| - - */ - pipeline_config::pipeline_config() - { - //empty - } - void pipeline_config::enable_stream(rs2_stream stream, int index, uint32_t width, uint32_t height, rs2_format format, uint32_t fps) - { - std::lock_guard lock(_mtx); - _resolved_profile.reset(); - _stream_requests[{stream, index}] = { stream, index, width, height, format, fps }; - } - - void pipeline_config::enable_all_stream() - { - std::lock_guard lock(_mtx); - _resolved_profile.reset(); - _stream_requests.clear(); - _enable_all_streams = true; - } - - void pipeline_config::enable_device(const std::string& serial) - { - std::lock_guard lock(_mtx); - _resolved_profile.reset(); - _device_request.serial = serial; - } - - void pipeline_config::enable_device_from_file(const std::string& file, bool repeat_playback = true) - { - std::lock_guard lock(_mtx); - if (!_device_request.record_output.empty()) - { - throw std::runtime_error("Configuring both device from file, and record to file is unsupported"); - } - _resolved_profile.reset(); - _device_request.filename = file; - _playback_loop = repeat_playback; - } - - void pipeline_config::enable_record_to_file(const std::string& file) - { - std::lock_guard lock(_mtx); - if (!_device_request.filename.empty()) - { - throw std::runtime_error("Configuring both device from file, and record to file is unsupported"); - } - _resolved_profile.reset(); - _device_request.record_output = file; - } - - std::shared_ptr pipeline_config::get_cached_resolved_profile() - { - std::lock_guard lock(_mtx); - return _resolved_profile; - } - - void pipeline_config::disable_stream(rs2_stream stream, int index) - { - std::lock_guard lock(_mtx); - auto itr = std::begin(_stream_requests); - while (itr != std::end(_stream_requests)) - { - //if this is the same stream type and also the user either requested all or it has the same index - if (itr->first.first == stream && (index == -1 || itr->first.second == index)) - { - itr = _stream_requests.erase(itr); - } - else - { - ++itr; - } - } - _resolved_profile.reset(); - } - - void pipeline_config::disable_all_streams() - { - std::lock_guard lock(_mtx); - _stream_requests.clear(); - _enable_all_streams = false; - _resolved_profile.reset(); - } - - std::shared_ptr pipeline_config::resolve(std::shared_ptr dev) - { - util::config config; - - //if the user requested all streams - if (_enable_all_streams) - { - for (size_t i = 0; i < dev->get_sensors_count(); ++i) - { - auto&& sub = dev->get_sensor(i); - auto profiles = sub.get_stream_profiles(PROFILE_TAG_SUPERSET); - config.enable_streams(profiles); - } - return std::make_shared(dev, config, _device_request.record_output); - } - - //If the user did not request anything, give it the default, on playback all recorded streams are marked as default. - if (_stream_requests.empty()) - { - auto default_profiles = get_default_configuration(dev); - config.enable_streams(default_profiles); - return std::make_shared(dev, config, _device_request.record_output); - } - - //Enabled requested streams - for (auto&& req : _stream_requests) - { - auto r = req.second; - config.enable_stream(r.stream, r.stream_index, r.width, r.height, r.format, r.fps); - } - return std::make_shared(dev, config, _device_request.record_output); - } - - std::shared_ptr pipeline_config::resolve(std::shared_ptr pipe, const std::chrono::milliseconds& timeout) - { - std::lock_guard lock(_mtx); - _resolved_profile.reset(); - - //Resolve the the device that was specified by the user, this call will wait in case the device is not availabe. - auto requested_device = resolve_device_requests(pipe, timeout); - if (requested_device != nullptr) - { - _resolved_profile = resolve(requested_device); - return _resolved_profile; - } - - //Look for satisfy device in case the user did not specify one. - auto devs = pipe->get_context()->query_devices(RS2_PRODUCT_LINE_ANY_INTEL); - for (auto dev_info : devs) - { - try - { - auto dev = dev_info->create_device(true); - _resolved_profile = resolve(dev); - return _resolved_profile; - } - catch (const std::exception& e) - { - LOG_DEBUG("Iterate available devices - config can not be resolved. " << e.what()); - } - } - - //If no device found wait for one - auto dev = pipe->wait_for_device(timeout); - if (dev != nullptr) - { - _resolved_profile = resolve(dev); - return _resolved_profile; - } - - throw std::runtime_error("Failed to resolve request. No device found that satisfies all requirements"); - - assert(0); //Unreachable code - } - - bool pipeline_config::can_resolve(std::shared_ptr pipe) - { - try - { // Try to resolve from connected devices. Non-blocking call - resolve(pipe); - _resolved_profile.reset(); - } - catch (const std::exception& e) - { - LOG_DEBUG("Config can not be resolved. " << e.what()); - return false; - } - catch (...) - { - return false; - } - return true; - } - - std::shared_ptr pipeline_config::get_or_add_playback_device(std::shared_ptr pipe, const std::string& file) - { - //Check if the file is already loaded to context, and if so return that device - for (auto&& d : pipe->get_context()->query_devices(RS2_PRODUCT_LINE_ANY)) - { - auto playback_devs = d->get_device_data().playback_devices; - for (auto&& p : playback_devs) - { - if (p.file_path == file) - { - return d->create_device(); - } - } - } - - return pipe->get_context()->add_device(file); - } - - std::shared_ptr pipeline_config::resolve_device_requests(std::shared_ptr pipe, const std::chrono::milliseconds& timeout) - { - //Prefer filename over serial - if(!_device_request.filename.empty()) - { - std::shared_ptr dev; - try - { - dev = get_or_add_playback_device(pipe, _device_request.filename); - } - catch(const std::exception& e) - { - throw std::runtime_error(to_string() << "Failed to resolve request. Request to enable_device_from_file(\"" << _device_request.filename << "\") was invalid, Reason: " << e.what()); - } - //check if a serial number was also requested, and check again the device - if (!_device_request.serial.empty()) - { - if (!dev->supports_info(RS2_CAMERA_INFO_SERIAL_NUMBER)) - { - throw std::runtime_error(to_string() << "Failed to resolve request. " - "Conflic between enable_device_from_file(\"" << _device_request.filename - << "\") and enable_device(\"" << _device_request.serial << "\"), " - "File does not contain a device with such serial"); - } - else - { - std::string s = dev->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER); - if (s != _device_request.serial) - { - throw std::runtime_error(to_string() << "Failed to resolve request. " - "Conflic between enable_device_from_file(\"" << _device_request.filename - << "\") and enable_device(\"" << _device_request.serial << "\"), " - "File contains device with different serial number (" << s << "\")"); - } - } - } - return dev; - } - - if (!_device_request.serial.empty()) - { - return pipe->wait_for_device(timeout, _device_request.serial); - } - - return nullptr; - } - - stream_profiles pipeline_config::get_default_configuration(std::shared_ptr dev) - { - stream_profiles default_profiles; - - for (unsigned int i = 0; i < dev->get_sensors_count(); i++) - { - auto&& sensor = dev->get_sensor(i); - auto profiles = sensor.get_stream_profiles(profile_tag::PROFILE_TAG_DEFAULT); - default_profiles.insert(std::end(default_profiles), std::begin(profiles), std::end(profiles)); - } - - return default_profiles; - } - - bool pipeline_config::get_repeat_playback() { - return _playback_loop; - } - - /* - .______ __ .______ _______ __ __ .__ __. _______ - | _ \ | | | _ \ | ____|| | | | | \ | | | ____| - | |_) | | | | |_) | | |__ | | | | | \| | | |__ - | ___/ | | | ___/ | __| | | | | | . ` | | __| - | | | | | | | |____ | `----.| | | |\ | | |____ - | _| |__| | _| |_______||_______||__| |__| \__| |_______| - */ - - pipeline::pipeline(std::shared_ptr ctx) - :_ctx(ctx), _hub(ctx, RS2_PRODUCT_LINE_ANY_INTEL), _dispatcher(10) - {} - - pipeline::~pipeline() - { - try - { - unsafe_stop(); - } - catch (...) {} - } - - std::shared_ptr pipeline::start(std::shared_ptr conf) - { - std::lock_guard lock(_mtx); - if (_active_profile) - { - throw librealsense::wrong_api_call_sequence_exception("start() cannot be called before stop()"); - } - unsafe_start(conf); - return unsafe_get_active_profile(); - } - - std::shared_ptr pipeline::start_with_record(std::shared_ptr conf, const std::string& file) - { - std::lock_guard lock(_mtx); - if (_active_profile) - { - throw librealsense::wrong_api_call_sequence_exception("start() cannot be called before stop()"); - } - conf->enable_record_to_file(file); - unsafe_start(conf); - return unsafe_get_active_profile(); - } - - std::shared_ptr pipeline::get_active_profile() const - { - std::lock_guard lock(_mtx); - return unsafe_get_active_profile(); - } - - std::shared_ptr pipeline::unsafe_get_active_profile() const - { - if (!_active_profile) - throw librealsense::wrong_api_call_sequence_exception("get_active_profile() can only be called between a start() and a following stop()"); - - return _active_profile; - } - - void pipeline::unsafe_start(std::shared_ptr conf) - { - std::shared_ptr profile = nullptr; - //first try to get the previously resolved profile (if exists) - auto cached_profile = conf->get_cached_resolved_profile(); - if (cached_profile) - { - profile = cached_profile; - } - else - { - const int NUM_TIMES_TO_RETRY = 3; - for (int i = 1; i <= NUM_TIMES_TO_RETRY; i++) - { - try - { - profile = conf->resolve(shared_from_this(), std::chrono::seconds(5)); - break; - } - catch (...) - { - if (i == NUM_TIMES_TO_RETRY) - throw; - } - } - } - - assert(profile); - assert(profile->_multistream.get_profiles().size() > 0); - - std::vector unique_ids; - for (auto&& s : profile->get_active_streams()) - { - unique_ids.push_back(s->get_unique_id()); - } - - _syncer = std::unique_ptr(new syncer_process_unit()); - _pipeline_process = std::unique_ptr(new pipeline_processing_block(unique_ids)); - - auto pipeline_process_callback = [&](frame_holder fref) - { - _pipeline_process->invoke(std::move(fref)); - }; - - frame_callback_ptr to_pipeline_process = { - new internal_frame_callback(pipeline_process_callback), - [](rs2_frame_callback* p) { p->release(); } - }; - - _syncer->set_output_callback(to_pipeline_process); - - auto to_syncer = [&](frame_holder fref) - { - _syncer->invoke(std::move(fref)); - }; - - frame_callback_ptr syncer_callback = { - new internal_frame_callback(to_syncer), - [](rs2_frame_callback* p) { p->release(); } - }; - - auto dev = profile->get_device(); - if (auto playback = As(dev)) - { - _playback_stopped_token = playback->playback_status_changed += [this, syncer_callback](rs2_playback_status status) - { - if (status == RS2_PLAYBACK_STATUS_STOPPED) - { - _dispatcher.invoke([this, syncer_callback](dispatcher::cancellable_timer t) - { - //If the pipeline holds a playback device, and it reached the end of file (stopped) - //Then we restart it - if (_active_profile && _prev_conf->get_repeat_playback()) - { - _active_profile->_multistream.open(); - _active_profile->_multistream.start(syncer_callback); - } - }); - } - }; - } - - _dispatcher.start(); - profile->_multistream.open(); - profile->_multistream.start(syncer_callback); - _active_profile = profile; - _prev_conf = std::make_shared(*conf); - } - - void pipeline::stop() - { - std::lock_guard lock(_mtx); - if (!_active_profile) - { - throw librealsense::wrong_api_call_sequence_exception("stop() cannot be called before start()"); - } - unsafe_stop(); - } - - void pipeline::unsafe_stop() - { - if (_active_profile) - { - try - { - auto dev = _active_profile->get_device(); - if (auto playback = As(dev)) - { - playback->playback_status_changed -= _playback_stopped_token; - } - _active_profile->_multistream.stop(); - _active_profile->_multistream.close(); - _dispatcher.stop(); - } - catch(...) - { - } // Stop will throw if device was disconnected. TODO - refactoring anticipated - } - _active_profile.reset(); - _syncer.reset(); - _pipeline_process.reset(); - _prev_conf.reset(); - } - frame_holder pipeline::wait_for_frames(unsigned int timeout_ms) - { - std::lock_guard lock(_mtx); - if (!_active_profile) - { - throw librealsense::wrong_api_call_sequence_exception("wait_for_frames cannot be called before start()"); - } - - frame_holder f; - if (_pipeline_process->dequeue(&f, timeout_ms)) - { - return f; - } - - //hub returns true even if device already reconnected - if (!_hub.is_connected(*_active_profile->get_device())) - { - try - { - auto prev_conf = _prev_conf; - unsafe_stop(); - unsafe_start(prev_conf); - - if (_pipeline_process->dequeue(&f, timeout_ms)) - { - return f; - } - - } - catch (const std::exception& e) - { - throw std::runtime_error(to_string() << "Device disconnected. Failed to recconect: "< lock(_mtx); - - if (!_active_profile) - { - throw librealsense::wrong_api_call_sequence_exception("poll_for_frames cannot be called before start()"); - } - - if (_pipeline_process->try_dequeue(frame)) - { - return true; - } - return false; - } - - bool pipeline::try_wait_for_frames(frame_holder* frame, unsigned int timeout_ms) - { - std::lock_guard lock(_mtx); - if (!_active_profile) - { - throw librealsense::wrong_api_call_sequence_exception("try_wait_for_frames cannot be called before start()"); - } - - if (_pipeline_process->dequeue(frame, timeout_ms)) - { - return true; - } - - //hub returns true even if device already reconnected - if (!_hub.is_connected(*_active_profile->get_device())) - { - try - { - auto prev_conf = _prev_conf; - unsafe_stop(); - unsafe_start(prev_conf); - return _pipeline_process->dequeue(frame, timeout_ms); - } - catch (const std::exception& e) - { - LOG_INFO(e.what()); - return false; - } - } - return false; - } - - std::shared_ptr pipeline::wait_for_device(const std::chrono::milliseconds& timeout, const std::string& serial) - { - // Pipeline's device selection shall be deterministic - return _hub.wait_for_device(timeout, false, serial); - } - - std::shared_ptr pipeline::get_context() const - { - return _ctx; - } - - - /* - .______ .______ ______ _______ __ __ _______ - | _ \ | _ \ / __ \ | ____|| | | | | ____| - | |_) | | |_) | | | | | | |__ | | | | | |__ - | ___/ | / | | | | | __| | | | | | __| - | | | |\ \----.| `--' | | | | | | `----.| |____ - | _| | _| `._____| \______/ |__| |__| |_______||_______| - */ - - pipeline_profile::pipeline_profile(std::shared_ptr dev, - util::config config, - const std::string& to_file) : - _dev(dev), _to_file(to_file) - { - if (!to_file.empty()) - { - if (!dev) - throw librealsense::invalid_value_exception("Failed to create a pipeline_profile, device is null"); - - _dev = std::make_shared(dev, std::make_shared(to_file, dev->compress_while_record())); - } - _multistream = config.resolve(_dev.get()); - } - - std::shared_ptr pipeline_profile::get_device() - { - //pipeline_profile can be retrieved from a pipeline_config and pipeline::start() - //either way, it is created by the pipeline - - //TODO: handle case where device has disconnected and reconnected - //TODO: remember to recreate the device as record device in case of to_file.empty() == false - if (!_dev) - { - throw std::runtime_error("Device is unavailable"); - } - return _dev; - } - - stream_profiles pipeline_profile::get_active_streams() const - { - auto profiles_per_sensor = _multistream.get_profiles_per_sensor(); - stream_profiles profiles; - for (auto&& kvp : profiles_per_sensor) - for (auto&& p : kvp.second) - profiles.push_back(p); - - return profiles; - } -} diff --git a/src/pipeline.h b/src/pipeline.h deleted file mode 100644 index 92e00304da..0000000000 --- a/src/pipeline.h +++ /dev/null @@ -1,126 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2015 Intel Corporation. All Rights Reserved. - -#pragma once - -#include -#include - -#include "device_hub.h" -#include "sync.h" -#include "config.h" - -namespace librealsense -{ - class processing_block; - class pipeline_processing_block : public processing_block - { - std::mutex _mutex; - std::map _last_set; - std::unique_ptr> _queue; - std::vector _streams_ids; - void handle_frame(frame_holder frame, synthetic_source_interface* source); - public: - pipeline_processing_block(const std::vector& streams_to_aggregate); - bool dequeue(frame_holder* item, unsigned int timeout_ms = 5000); - bool try_dequeue(frame_holder* item); - }; - - class pipeline; - class pipeline_profile - { - public: - pipeline_profile(std::shared_ptr dev, util::config config, const std::string& file = ""); - std::shared_ptr get_device(); - stream_profiles get_active_streams() const; - util::config::multistream _multistream; - private: - std::shared_ptr _dev; - std::string _to_file; - }; - - class pipeline_config; - class pipeline : public std::enable_shared_from_this - { - public: - //Top level API - explicit pipeline(std::shared_ptr ctx); - ~pipeline(); - std::shared_ptr start(std::shared_ptr conf); - std::shared_ptr start_with_record(std::shared_ptr conf, const std::string& file); - void stop(); - std::shared_ptr get_active_profile() const; - frame_holder wait_for_frames(unsigned int timeout_ms = 5000); - bool poll_for_frames(frame_holder* frame); - bool try_wait_for_frames(frame_holder* frame, unsigned int timeout_ms); - //Non top level API - std::shared_ptr wait_for_device(const std::chrono::milliseconds& timeout = std::chrono::hours::max(), - const std::string& serial = ""); - std::shared_ptr get_context() const; - - - private: - void unsafe_start(std::shared_ptr conf); - void unsafe_stop(); - std::shared_ptr unsafe_get_active_profile() const; - - std::shared_ptr _ctx; - mutable std::mutex _mtx; - device_hub _hub; - std::shared_ptr _active_profile; - frame_callback_ptr _callback; - std::unique_ptr _syncer; - std::unique_ptr _pipeline_process; - std::shared_ptr _prev_conf; - int _playback_stopped_token = -1; - dispatcher _dispatcher; - }; - - class pipeline_config - { - public: - pipeline_config(); - void enable_stream(rs2_stream stream, int index, uint32_t width, uint32_t height, rs2_format format, uint32_t framerate); - void enable_all_stream(); - void enable_device(const std::string& serial); - void enable_device_from_file(const std::string& file, bool repeat_playback); - void enable_record_to_file(const std::string& file); - void disable_stream(rs2_stream stream, int index = -1); - void disable_all_streams(); - std::shared_ptr resolve(std::shared_ptr pipe, const std::chrono::milliseconds& timeout = std::chrono::milliseconds(0)); - bool can_resolve(std::shared_ptr pipe); - bool get_repeat_playback(); - - //Non top level API - std::shared_ptr get_cached_resolved_profile(); - - pipeline_config(const pipeline_config& other) - { - _device_request = other._device_request; - _stream_requests = other._stream_requests; - _enable_all_streams = other._enable_all_streams; - _stream_requests = other._stream_requests; - _resolved_profile = nullptr; - _playback_loop = other._playback_loop; - } - private: - struct device_request - { - std::string serial; - std::string filename; - std::string record_output; - }; - std::shared_ptr get_or_add_playback_device(std::shared_ptr pipe, const std::string& file); - std::shared_ptr resolve_device_requests(std::shared_ptr pipe, const std::chrono::milliseconds& timeout); - stream_profiles get_default_configuration(std::shared_ptr dev); - std::shared_ptr resolve(std::shared_ptr dev); - - device_request _device_request; - std::map, util::config::request_type> _stream_requests; - std::mutex _mtx; - bool _enable_all_streams = false; - std::shared_ptr _resolved_profile; - bool _playback_loop; - }; - -} diff --git a/src/pipeline/CMakeLists.txt b/src/pipeline/CMakeLists.txt new file mode 100644 index 0000000000..13c8cad669 --- /dev/null +++ b/src/pipeline/CMakeLists.txt @@ -0,0 +1,13 @@ +target_sources(${LRS_TARGET} + PRIVATE + "${CMAKE_CURRENT_LIST_DIR}/pipeline.cpp" + "${CMAKE_CURRENT_LIST_DIR}/config.cpp" + "${CMAKE_CURRENT_LIST_DIR}/profile.cpp" + "${CMAKE_CURRENT_LIST_DIR}/aggregator.cpp" + + "${CMAKE_CURRENT_LIST_DIR}/pipeline.h" + "${CMAKE_CURRENT_LIST_DIR}/config.h" + "${CMAKE_CURRENT_LIST_DIR}/profile.h" + "${CMAKE_CURRENT_LIST_DIR}/resolver.h" + "${CMAKE_CURRENT_LIST_DIR}/aggregator.h" +) diff --git a/src/pipeline/aggregator.cpp b/src/pipeline/aggregator.cpp new file mode 100644 index 0000000000..103a9ded73 --- /dev/null +++ b/src/pipeline/aggregator.cpp @@ -0,0 +1,106 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2015 Intel Corporation. All Rights Reserved. + +#include +#include "stream.h" +#include "aggregator.h" + +namespace librealsense +{ + namespace pipeline + { + aggregator::aggregator(const std::vector& streams_to_aggregate, const std::vector& streams_to_sync) : + _queue(new single_consumer_frame_queue(1)), + _streams_to_aggregate_ids(streams_to_aggregate), + _streams_to_sync_ids(streams_to_sync) + { + auto processing_callback = [&](frame_holder frame, synthetic_source_interface* source) + { + handle_frame(std::move(frame), source); + }; + + set_processing_callback(std::shared_ptr( + new internal_frame_processor_callback(processing_callback))); + } + + void aggregator::handle_frame(frame_holder frame, synthetic_source_interface* source) + { + std::lock_guard lock(_mutex); + auto comp = dynamic_cast(frame.frame); + if (comp) + { + for (auto i = 0; i < comp->get_embedded_frames_count(); i++) + { + auto f = comp->get_frame(i); + f->acquire(); + _last_set[f->get_stream()->get_unique_id()] = f; + } + + // in case not all required streams were aggregated don't publish the frame set + for (int s : _streams_to_aggregate_ids) + { + if (!_last_set[s]) + return; + } + + // prepare the output frame set for wait_for_frames/poll_frames calls + std::vector sync_set; + // prepare the output frame set for the callbacks + std::vector async_set; + for (auto&& s : _last_set) + { + sync_set.push_back(s.second.clone()); + // send only the synchronized frames to the user callback + if (std::find(_streams_to_sync_ids.begin(), _streams_to_sync_ids.end(), + s.second->get_stream()->get_unique_id()) != _streams_to_sync_ids.end()) + async_set.push_back(s.second.clone()); + } + + frame_holder sync_fref = source->allocate_composite_frame(std::move(sync_set)); + frame_holder async_fref = source->allocate_composite_frame(std::move(async_set)); + + if (!sync_fref || !async_fref) + { + LOG_ERROR("Failed to allocate composite frame"); + return; + } + // for async pipeline usage - provide only the synchronized frames to the user via callback + source->frame_ready(async_fref.clone()); + + // for sync pipeline usage - push the aggregated to the output queue + _queue->enqueue(sync_fref.clone()); + } + else + { + source->frame_ready(frame.clone()); + _last_set[frame->get_stream()->get_unique_id()] = frame.clone(); + if (_streams_to_sync_ids.empty() && _last_set.size() == _streams_to_aggregate_ids.size()) + { + // prepare the output frame set for wait_for_frames/poll_frames calls + std::vector sync_set; + for (auto&& s : _last_set) + sync_set.push_back(s.second.clone()); + + frame_holder sync_fref = source->allocate_composite_frame(std::move(sync_set)); + if (!sync_fref) + { + LOG_ERROR("Failed to allocate composite frame"); + return; + } + // for sync pipeline usage - push the aggregated to the output queue + _queue->enqueue(sync_fref.clone()); + } + } + } + + bool aggregator::dequeue(frame_holder* item, unsigned int timeout_ms) + { + return _queue->dequeue(item, timeout_ms); + } + + bool aggregator::try_dequeue(frame_holder* item) + { + return _queue->try_dequeue(item); + } + } +} diff --git a/src/pipeline/aggregator.h b/src/pipeline/aggregator.h new file mode 100644 index 0000000000..e4714a8f52 --- /dev/null +++ b/src/pipeline/aggregator.h @@ -0,0 +1,28 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2015 Intel Corporation. All Rights Reserved. + +#pragma once + +#include "sync.h" +#include "proc/synthetic-stream.h" +#include "proc/syncer-processing-block.h" + +namespace librealsense +{ + namespace pipeline + { + class aggregator : public processing_block + { + std::mutex _mutex; + std::map _last_set; + std::unique_ptr> _queue; + std::vector _streams_to_aggregate_ids; + std::vector _streams_to_sync_ids; + void handle_frame(frame_holder frame, synthetic_source_interface* source); + public: + aggregator(const std::vector& streams_to_aggregate, const std::vector& streams_to_sync); + bool dequeue(frame_holder* item, unsigned int timeout_ms = 5000); + bool try_dequeue(frame_holder* item); + }; + } +} diff --git a/src/pipeline/config.cpp b/src/pipeline/config.cpp new file mode 100644 index 0000000000..3a08a5c650 --- /dev/null +++ b/src/pipeline/config.cpp @@ -0,0 +1,270 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2015 Intel Corporation. All Rights Reserved. + +#include "config.h" +#include "pipeline.h" + +namespace librealsense +{ + namespace pipeline + { + config::config() + { + //empty + } + void config::enable_stream(rs2_stream stream, int index, uint32_t width, uint32_t height, rs2_format format, uint32_t fps) + { + std::lock_guard lock(_mtx); + _resolved_profile.reset(); + _stream_requests[{stream, index}] = { stream, index, width, height, format, fps }; + } + + void config::enable_all_stream() + { + std::lock_guard lock(_mtx); + _resolved_profile.reset(); + _stream_requests.clear(); + _enable_all_streams = true; + } + + void config::enable_device(const std::string& serial) + { + std::lock_guard lock(_mtx); + _resolved_profile.reset(); + _device_request.serial = serial; + } + + void config::enable_device_from_file(const std::string& file, bool repeat_playback = true) + { + std::lock_guard lock(_mtx); + if (!_device_request.record_output.empty()) + { + throw std::runtime_error("Configuring both device from file, and record to file is unsupported"); + } + _resolved_profile.reset(); + _device_request.filename = file; + _playback_loop = repeat_playback; + } + + void config::enable_record_to_file(const std::string& file) + { + std::lock_guard lock(_mtx); + if (!_device_request.filename.empty()) + { + throw std::runtime_error("Configuring both device from file, and record to file is unsupported"); + } + _resolved_profile.reset(); + _device_request.record_output = file; + } + + std::shared_ptr config::get_cached_resolved_profile() + { + std::lock_guard lock(_mtx); + return _resolved_profile; + } + + void config::disable_stream(rs2_stream stream, int index) + { + std::lock_guard lock(_mtx); + auto itr = std::begin(_stream_requests); + while (itr != std::end(_stream_requests)) + { + //if this is the same stream type and also the user either requested all or it has the same index + if (itr->first.first == stream && (index == -1 || itr->first.second == index)) + { + itr = _stream_requests.erase(itr); + } + else + { + ++itr; + } + } + _resolved_profile.reset(); + } + + void config::disable_all_streams() + { + std::lock_guard lock(_mtx); + _stream_requests.clear(); + _enable_all_streams = false; + _resolved_profile.reset(); + } + + std::shared_ptr config::resolve(std::shared_ptr dev) + { + util::config config; + + //if the user requested all streams + if (_enable_all_streams) + { + for (size_t i = 0; i < dev->get_sensors_count(); ++i) + { + auto&& sub = dev->get_sensor(i); + auto profiles = sub.get_stream_profiles(PROFILE_TAG_SUPERSET); + config.enable_streams(profiles); + } + return std::make_shared(dev, config, _device_request.record_output); + } + + //If the user did not request anything, give it the default, on playback all recorded streams are marked as default. + if (_stream_requests.empty()) + { + auto default_profiles = get_default_configuration(dev); + config.enable_streams(default_profiles); + return std::make_shared(dev, config, _device_request.record_output); + } + + //Enabled requested streams + for (auto&& req : _stream_requests) + { + auto r = req.second; + config.enable_stream(r.stream, r.stream_index, r.width, r.height, r.format, r.fps); + } + return std::make_shared(dev, config, _device_request.record_output); + } + + std::shared_ptr config::resolve(std::shared_ptr pipe, const std::chrono::milliseconds& timeout) + { + std::lock_guard lock(_mtx); + _resolved_profile.reset(); + + //Resolve the the device that was specified by the user, this call will wait in case the device is not availabe. + auto requested_device = resolve_device_requests(pipe, timeout); + if (requested_device != nullptr) + { + _resolved_profile = resolve(requested_device); + return _resolved_profile; + } + + //Look for satisfy device in case the user did not specify one. + auto devs = pipe->get_context()->query_devices(RS2_PRODUCT_LINE_ANY_INTEL); + for (auto dev_info : devs) + { + try + { + auto dev = dev_info->create_device(true); + _resolved_profile = resolve(dev); + return _resolved_profile; + } + catch (const std::exception& e) + { + LOG_DEBUG("Iterate available devices - config can not be resolved. " << e.what()); + } + } + + //If no device found wait for one + auto dev = pipe->wait_for_device(timeout); + if (dev != nullptr) + { + _resolved_profile = resolve(dev); + return _resolved_profile; + } + + throw std::runtime_error("Failed to resolve request. No device found that satisfies all requirements"); + + assert(0); //Unreachable code + } + + bool config::can_resolve(std::shared_ptr pipe) + { + try + { // Try to resolve from connected devices. Non-blocking call + resolve(pipe); + _resolved_profile.reset(); + } + catch (const std::exception& e) + { + LOG_DEBUG("Config can not be resolved. " << e.what()); + return false; + } + catch (...) + { + return false; + } + return true; + } + + std::shared_ptr config::get_or_add_playback_device(std::shared_ptr ctx, const std::string& file) + { + //Check if the file is already loaded to context, and if so return that device + for (auto&& d : ctx->query_devices(RS2_PRODUCT_LINE_ANY)) + { + auto playback_devs = d->get_device_data().playback_devices; + for (auto&& p : playback_devs) + { + if (p.file_path == file) + { + return d->create_device(); + } + } + } + + return ctx->add_device(file); + } + + std::shared_ptr config::resolve_device_requests(std::shared_ptr pipe, const std::chrono::milliseconds& timeout) + { + //Prefer filename over serial + if (!_device_request.filename.empty()) + { + std::shared_ptr dev; + try + { + dev = get_or_add_playback_device(pipe->get_context(), _device_request.filename); + } + catch (const std::exception& e) + { + throw std::runtime_error(to_string() << "Failed to resolve request. Request to enable_device_from_file(\"" << _device_request.filename << "\") was invalid, Reason: " << e.what()); + } + //check if a serial number was also requested, and check again the device + if (!_device_request.serial.empty()) + { + if (!dev->supports_info(RS2_CAMERA_INFO_SERIAL_NUMBER)) + { + throw std::runtime_error(to_string() << "Failed to resolve request. " + "Conflic between enable_device_from_file(\"" << _device_request.filename + << "\") and enable_device(\"" << _device_request.serial << "\"), " + "File does not contain a device with such serial"); + } + else + { + std::string s = dev->get_info(RS2_CAMERA_INFO_SERIAL_NUMBER); + if (s != _device_request.serial) + { + throw std::runtime_error(to_string() << "Failed to resolve request. " + "Conflic between enable_device_from_file(\"" << _device_request.filename + << "\") and enable_device(\"" << _device_request.serial << "\"), " + "File contains device with different serial number (" << s << "\")"); + } + } + } + return dev; + } + + if (!_device_request.serial.empty()) + { + return pipe->wait_for_device(timeout, _device_request.serial); + } + + return nullptr; + } + + stream_profiles config::get_default_configuration(std::shared_ptr dev) + { + stream_profiles default_profiles; + + for (unsigned int i = 0; i < dev->get_sensors_count(); i++) + { + auto&& sensor = dev->get_sensor(i); + auto profiles = sensor.get_stream_profiles(profile_tag::PROFILE_TAG_DEFAULT); + default_profiles.insert(std::end(default_profiles), std::begin(profiles), std::end(profiles)); + } + + return default_profiles; + } + + bool config::get_repeat_playback() { + return _playback_loop; + } + } +} diff --git a/src/pipeline/config.h b/src/pipeline/config.h new file mode 100644 index 0000000000..0ff67f5786 --- /dev/null +++ b/src/pipeline/config.h @@ -0,0 +1,65 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2015 Intel Corporation. All Rights Reserved. + +#pragma once + +#include +#include + +#include "resolver.h" + +namespace librealsense +{ + namespace pipeline + { + class profile; + class pipeline; + + class config + { + public: + config(); + void enable_stream(rs2_stream stream, int index, uint32_t width, uint32_t height, rs2_format format, uint32_t framerate); + void enable_all_stream(); + void enable_device(const std::string& serial); + void enable_device_from_file(const std::string& file, bool repeat_playback); + void enable_record_to_file(const std::string& file); + void disable_stream(rs2_stream stream, int index = -1); + void disable_all_streams(); + std::shared_ptr resolve(std::shared_ptr pipe, const std::chrono::milliseconds& timeout = std::chrono::milliseconds(0)); + bool can_resolve(std::shared_ptr pipe); + bool get_repeat_playback(); + + //Non top level API + std::shared_ptr get_cached_resolved_profile(); + + config(const config& other) + { + _device_request = other._device_request; + _stream_requests = other._stream_requests; + _enable_all_streams = other._enable_all_streams; + _stream_requests = other._stream_requests; + _resolved_profile = nullptr; + _playback_loop = other._playback_loop; + } + private: + struct device_request + { + std::string serial; + std::string filename; + std::string record_output; + }; + std::shared_ptr get_or_add_playback_device(std::shared_ptr ctx, const std::string& file); + std::shared_ptr resolve_device_requests(std::shared_ptr pipe, const std::chrono::milliseconds& timeout); + stream_profiles get_default_configuration(std::shared_ptr dev); + std::shared_ptr resolve(std::shared_ptr dev); + + device_request _device_request; + std::map, util::config::request_type> _stream_requests; + std::mutex _mtx; + bool _enable_all_streams = false; + std::shared_ptr _resolved_profile; + bool _playback_loop; + }; + } +} diff --git a/src/pipeline/pipeline.cpp b/src/pipeline/pipeline.cpp new file mode 100644 index 0000000000..d66b48a347 --- /dev/null +++ b/src/pipeline/pipeline.cpp @@ -0,0 +1,318 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2015 Intel Corporation. All Rights Reserved. + +#include +#include "pipeline.h" +#include "stream.h" +#include "media/record/record_device.h" +#include "media/ros/ros_writer.h" + +namespace librealsense +{ + namespace pipeline + { + pipeline::pipeline(std::shared_ptr ctx) : + _ctx(ctx), + _dispatcher(10), + _hub(ctx, RS2_PRODUCT_LINE_ANY_INTEL), + _synced_streams({ RS2_STREAM_COLOR, RS2_STREAM_DEPTH, RS2_STREAM_INFRARED, RS2_STREAM_FISHEYE }) + {} + + pipeline::~pipeline() + { + try + { + unsafe_stop(); + } + catch (...) {} + } + + std::shared_ptr pipeline::start(std::shared_ptr conf, frame_callback_ptr callback) + { + std::lock_guard lock(_mtx); + if (_active_profile) + { + throw librealsense::wrong_api_call_sequence_exception("start() cannot be called before stop()"); + } + _streams_callback = callback; + unsafe_start(conf); + return unsafe_get_active_profile(); + } + + std::shared_ptr pipeline::get_active_profile() const + { + std::lock_guard lock(_mtx); + return unsafe_get_active_profile(); + } + + std::shared_ptr pipeline::unsafe_get_active_profile() const + { + if (!_active_profile) + throw librealsense::wrong_api_call_sequence_exception("get_active_profile() can only be called between a start() and a following stop()"); + + return _active_profile; + } + + void pipeline::unsafe_start(std::shared_ptr conf) + { + std::shared_ptr profile = nullptr; + //first try to get the previously resolved profile (if exists) + auto cached_profile = conf->get_cached_resolved_profile(); + if (cached_profile) + { + profile = cached_profile; + } + else + { + const int NUM_TIMES_TO_RETRY = 3; + for (int i = 1; i <= NUM_TIMES_TO_RETRY; i++) + { + try + { + profile = conf->resolve(shared_from_this(), std::chrono::seconds(5)); + break; + } + catch (...) + { + if (i == NUM_TIMES_TO_RETRY) + throw; + } + } + } + + assert(profile); + assert(profile->_multistream.get_profiles().size() > 0); + + auto synced_streams_ids = on_start(profile); + + frame_callback_ptr callbacks = get_callback(synced_streams_ids); + + auto dev = profile->get_device(); + if (auto playback = As(dev)) + { + _playback_stopped_token = playback->playback_status_changed += [this, callbacks](rs2_playback_status status) + { + if (status == RS2_PLAYBACK_STATUS_STOPPED) + { + _dispatcher.invoke([this, callbacks](dispatcher::cancellable_timer t) + { + //If the pipeline holds a playback device, and it reached the end of file (stopped) + //Then we restart it + if (_active_profile && _prev_conf->get_repeat_playback()) + { + _active_profile->_multistream.open(); + _active_profile->_multistream.start(callbacks); + } + }); + } + }; + } + + _dispatcher.start(); + profile->_multistream.open(); + profile->_multistream.start(callbacks); + _active_profile = profile; + _prev_conf = std::make_shared(*conf); + } + + void pipeline::stop() + { + std::lock_guard lock(_mtx); + if (!_active_profile) + { + throw librealsense::wrong_api_call_sequence_exception("stop() cannot be called before start()"); + } + unsafe_stop(); + } + + void pipeline::unsafe_stop() + { + if (_active_profile) + { + try + { + auto dev = _active_profile->get_device(); + if (auto playback = As(dev)) + { + playback->playback_status_changed -= _playback_stopped_token; + } + _active_profile->_multistream.stop(); + _active_profile->_multistream.close(); + _dispatcher.stop(); + } + catch (...) + { + } // Stop will throw if device was disconnected. TODO - refactoring anticipated + } + _active_profile.reset(); + _prev_conf.reset(); + _streams_callback.reset(); + } + + std::shared_ptr pipeline::wait_for_device(const std::chrono::milliseconds& timeout, const std::string& serial) + { + // pipeline's device selection shall be deterministic + return _hub.wait_for_device(timeout, false, serial); + } + + std::shared_ptr pipeline::get_context() const + { + return _ctx; + } + + std::vector pipeline::on_start(std::shared_ptr profile) + { + std::vector _streams_to_aggregate_ids; + std::vector _streams_to_sync_ids; + bool sync_any = false; + if (std::find(_synced_streams.begin(), _synced_streams.end(), RS2_STREAM_ANY) != _synced_streams.end()) + sync_any = true; + // check wich of the active profiles should be synced and update the sync list accordinglly + for (auto&& s : profile->get_active_streams()) + { + _streams_to_aggregate_ids.push_back(s->get_unique_id()); + bool sync_current = sync_any; + if (!sync_any && std::find(_synced_streams.begin(), _synced_streams.end(), s->get_stream_type()) != _synced_streams.end()) + sync_current = true; + if(sync_current) + _streams_to_sync_ids.push_back(s->get_unique_id()); + } + + _syncer = std::unique_ptr(new syncer_process_unit()); + _aggregator = std::unique_ptr(new aggregator(_streams_to_aggregate_ids, _streams_to_sync_ids)); + + if (_streams_callback) + _aggregator->set_output_callback(_streams_callback); + + return _streams_to_sync_ids; + } + + frame_callback_ptr pipeline::get_callback(std::vector synced_streams_ids) + { + auto pipeline_process_callback = [&](frame_holder fref) + { + _aggregator->invoke(std::move(fref)); + }; + + frame_callback_ptr to_pipeline_process = { + new internal_frame_callback(pipeline_process_callback), + [](rs2_frame_callback* p) { p->release(); } + }; + + _syncer->set_output_callback(to_pipeline_process); + + auto to_syncer = [&, synced_streams_ids](frame_holder fref) + { + // if the user requested to sync the frame push it to the syncer, otherwise push it to the aggregator + if (std::find(synced_streams_ids.begin(), synced_streams_ids.end(), fref->get_stream()->get_unique_id()) != synced_streams_ids.end()) + _syncer->invoke(std::move(fref)); + else + _aggregator->invoke(std::move(fref)); + }; + + frame_callback_ptr rv = { + new internal_frame_callback(to_syncer), + [](rs2_frame_callback* p) { p->release(); } + }; + + return rv; + } + + frame_holder pipeline::wait_for_frames(unsigned int timeout_ms) + { + std::lock_guard lock(_mtx); + if (!_active_profile) + { + throw librealsense::wrong_api_call_sequence_exception("wait_for_frames cannot be called before start()"); + } + if (_streams_callback) + { + throw librealsense::wrong_api_call_sequence_exception("wait_for_frames cannot be called if a callback was provided"); + } + + frame_holder f; + if (_aggregator->dequeue(&f, timeout_ms)) + { + return f; + } + + //hub returns true even if device already reconnected + if (!_hub.is_connected(*_active_profile->get_device())) + { + try + { + auto prev_conf = _prev_conf; + unsafe_stop(); + unsafe_start(prev_conf); + + if (_aggregator->dequeue(&f, timeout_ms)) + { + return f; + } + + } + catch (const std::exception& e) + { + throw std::runtime_error(to_string() << "Device disconnected. Failed to recconect: " << e.what() << timeout_ms); + } + } + throw std::runtime_error(to_string() << "Frame didn't arrived within " << timeout_ms); + } + + bool pipeline::poll_for_frames(frame_holder* frame) + { + std::lock_guard lock(_mtx); + + if (!_active_profile) + { + throw librealsense::wrong_api_call_sequence_exception("poll_for_frames cannot be called before start()"); + } + if (_streams_callback) + { + throw librealsense::wrong_api_call_sequence_exception("poll_for_frames cannot be called if a callback was provided"); + } + + if (_aggregator->try_dequeue(frame)) + { + return true; + } + return false; + } + + bool pipeline::try_wait_for_frames(frame_holder* frame, unsigned int timeout_ms) + { + std::lock_guard lock(_mtx); + if (!_active_profile) + { + throw librealsense::wrong_api_call_sequence_exception("try_wait_for_frames cannot be called before start()"); + } + if (_streams_callback) + { + throw librealsense::wrong_api_call_sequence_exception("try_wait_for_frames cannot be called if a callback was provided"); + } + + if (_aggregator->dequeue(frame, timeout_ms)) + { + return true; + } + + //hub returns true even if device already reconnected + if (!_hub.is_connected(*_active_profile->get_device())) + { + try + { + auto prev_conf = _prev_conf; + unsafe_stop(); + unsafe_start(prev_conf); + return _aggregator->dequeue(frame, timeout_ms); + } + catch (const std::exception& e) + { + LOG_INFO(e.what()); + return false; + } + } + return false; + } + } +} diff --git a/src/pipeline/pipeline.h b/src/pipeline/pipeline.h new file mode 100644 index 0000000000..3d85bd7378 --- /dev/null +++ b/src/pipeline/pipeline.h @@ -0,0 +1,64 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2015 Intel Corporation. All Rights Reserved. + +#pragma once + +#include +#include + +#include "device_hub.h" +#include "sync.h" +#include "profile.h" +#include "config.h" +#include "resolver.h" +#include "aggregator.h" + +namespace librealsense +{ + namespace pipeline + { + class pipeline : public std::enable_shared_from_this + { + public: + //Top level API + explicit pipeline(std::shared_ptr ctx); + virtual ~pipeline(); + std::shared_ptr start(std::shared_ptr conf, frame_callback_ptr callback = nullptr); + void stop(); + std::shared_ptr get_active_profile() const; + frame_holder wait_for_frames(unsigned int timeout_ms = 5000); + bool poll_for_frames(frame_holder* frame); + bool try_wait_for_frames(frame_holder* frame, unsigned int timeout_ms); + + //Non top level API + std::shared_ptr wait_for_device(const std::chrono::milliseconds& timeout = std::chrono::hours::max(), + const std::string& serial = ""); + std::shared_ptr get_context() const; + + protected: + frame_callback_ptr get_callback(std::vector unique_ids); + std::vector on_start(std::shared_ptr profile); + + void unsafe_start(std::shared_ptr conf); + void unsafe_stop(); + + mutable std::mutex _mtx; + std::shared_ptr _active_profile; + device_hub _hub; + std::shared_ptr _prev_conf; + + private: + std::shared_ptr unsafe_get_active_profile() const; + + std::shared_ptr _ctx; + int _playback_stopped_token = -1; + dispatcher _dispatcher; + + std::unique_ptr _syncer; + std::unique_ptr _aggregator; + + frame_callback_ptr _streams_callback; + std::vector _synced_streams; + }; + } +} diff --git a/src/pipeline/profile.cpp b/src/pipeline/profile.cpp new file mode 100644 index 0000000000..f44ad3e847 --- /dev/null +++ b/src/pipeline/profile.cpp @@ -0,0 +1,52 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2015 Intel Corporation. All Rights Reserved. + +#include "profile.h" +#include "media/record/record_device.h" +#include "media/ros/ros_writer.h" + +namespace librealsense +{ + namespace pipeline + { + profile::profile(std::shared_ptr dev, + util::config config, + const std::string& to_file) : + _dev(dev), _to_file(to_file) + { + if (!to_file.empty()) + { + if (!dev) + throw librealsense::invalid_value_exception("Failed to create a profile, device is null"); + + _dev = std::make_shared(dev, std::make_shared(to_file, dev->compress_while_record())); + } + _multistream = config.resolve(_dev.get()); + } + + std::shared_ptr profile::get_device() + { + //profile can be retrieved from a pipeline_config and pipeline::start() + //either way, it is created by the pipeline + + //TODO: handle case where device has disconnected and reconnected + //TODO: remember to recreate the device as record device in case of to_file.empty() == false + if (!_dev) + { + throw std::runtime_error("Device is unavailable"); + } + return _dev; + } + + stream_profiles profile::get_active_streams() const + { + auto profiles_per_sensor = _multistream.get_profiles_per_sensor(); + stream_profiles profiles; + for (auto&& kvp : profiles_per_sensor) + for (auto&& p : kvp.second) + profiles.push_back(p); + + return profiles; + } + } +} diff --git a/src/pipeline/profile.h b/src/pipeline/profile.h new file mode 100644 index 0000000000..b05a18a902 --- /dev/null +++ b/src/pipeline/profile.h @@ -0,0 +1,24 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2015 Intel Corporation. All Rights Reserved. + +#pragma once + +#include "resolver.h" + +namespace librealsense +{ + namespace pipeline + { + class profile + { + public: + profile(std::shared_ptr dev, util::config config, const std::string& file = ""); + std::shared_ptr get_device(); + stream_profiles get_active_streams() const; + util::config::multistream _multistream; + private: + std::shared_ptr _dev; + std::string _to_file; + }; + } +} diff --git a/src/config.h b/src/pipeline/resolver.h similarity index 96% rename from src/config.h rename to src/pipeline/resolver.h index 96e04dd31b..0abaab38da 100644 --- a/src/config.h +++ b/src/pipeline/resolver.h @@ -1,8 +1,7 @@ // License: Apache 2.0. See LICENSE file in root directory. // Copyright(c) 2015 Intel Corporation. All Rights Reserved. -#ifndef CONFIG_HPP -#define CONFIG_HPP +#pragma once #include #include @@ -17,7 +16,6 @@ namespace librealsense { - namespace util { enum config_preset @@ -51,8 +49,6 @@ namespace librealsense } }; - - static bool match_stream(const index_type& a, const index_type& b) { if (a.stream != RS2_STREAM_ANY && b.stream != RS2_STREAM_ANY && (a.stream != b.stream)) @@ -75,7 +71,6 @@ namespace librealsense if (a.fps() != 0 && b.fps() != 0 && (a.fps() != b.fps())) return false; - if (auto vid_a = dynamic_cast(a)) { if (auto vid_b = dynamic_cast(b)) @@ -87,7 +82,6 @@ namespace librealsense } else return false; } - return true; } @@ -113,7 +107,6 @@ namespace librealsense return true; } - static bool contradicts(stream_profile_interface* a, stream_profiles others) { for (auto request : others) @@ -135,20 +128,19 @@ namespace librealsense } } } - return false; } static bool contradicts(stream_profile_interface* a, const std::vector& others) { - for (auto request : others) - { - if (a->get_framerate() != 0 && request.fps != 0 && (a->get_framerate() != request.fps)) - return true; - } - if (auto vid_a = dynamic_cast(a)) { + for (auto request : others) + { + if (a->get_framerate() != 0 && request.fps != 0 && (a->get_framerate() != request.fps)) + return true; + } + for (auto request : others) { // Patch for DS5U_S that allows different resolutions on multi-pin device @@ -160,7 +152,6 @@ namespace librealsense return true; } } - return false; } @@ -182,6 +173,7 @@ namespace librealsense if (a.stream_index == -1) return true; return false; } + std::map get_requests() { return _requests; @@ -200,7 +192,6 @@ namespace librealsense _results(std::move(results)) {} - void open() { for (auto && kvp : _dev_to_profiles) { @@ -250,20 +241,23 @@ namespace librealsense void enable_streams(stream_profiles profiles) { std::map, std::vector>> profiles_map; + for (auto profile : profiles) { profiles_map[std::make_tuple(profile->get_unique_id(), profile->get_stream_index())].push_back(profile); } + for (auto profs : profiles_map) { std::sort(begin(profs.second), end(profs.second), sort_best_quality); - auto p = dynamic_cast(profs.second.front().get()); - if (!p) + auto p = profs.second.front().get(); + auto vp = dynamic_cast(p); + if (vp) { - LOG_ERROR("prof is not video_stream_profile"); - throw std::logic_error("Failed to resolve request. internal error"); + enable_stream(vp->get_stream_type(), vp->get_stream_index(), vp->get_width(), vp->get_height(), vp->get_format(), vp->get_framerate()); + continue; } - enable_stream(p->get_stream_type(), p->get_stream_index(), p->get_width(), p->get_height(), p->get_format(), p->get_framerate()); + enable_stream(p->get_stream_type(), p->get_stream_index(), 0, 0, p->get_format(), p->get_framerate()); } } @@ -292,7 +286,6 @@ namespace librealsense itr++; } } - } void disable_all() @@ -528,8 +521,5 @@ namespace librealsense std::map _requests; bool require_all; }; - } } - -#endif diff --git a/src/proc/CMakeLists.txt b/src/proc/CMakeLists.txt index 3bd7702adc..d03499fe5c 100644 --- a/src/proc/CMakeLists.txt +++ b/src/proc/CMakeLists.txt @@ -20,6 +20,8 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/temporal-filter.cpp" "${CMAKE_CURRENT_LIST_DIR}/hole-filling-filter.cpp" "${CMAKE_CURRENT_LIST_DIR}/disparity-transform.cpp" + "${CMAKE_CURRENT_LIST_DIR}/rates_printer.cpp" + "${CMAKE_CURRENT_LIST_DIR}/processing-blocks-factory.h" "${CMAKE_CURRENT_LIST_DIR}/align.h" "${CMAKE_CURRENT_LIST_DIR}/colorizer.h" @@ -32,4 +34,5 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/hole-filling-filter.h" "${CMAKE_CURRENT_LIST_DIR}/syncer-processing-block.h" "${CMAKE_CURRENT_LIST_DIR}/disparity-transform.h" + "${CMAKE_CURRENT_LIST_DIR}/rates_printer.h" ) diff --git a/src/proc/rates_printer.cpp b/src/proc/rates_printer.cpp new file mode 100644 index 0000000000..20452afc44 --- /dev/null +++ b/src/proc/rates_printer.cpp @@ -0,0 +1,85 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2018 Intel Corporation. All Rights Reserved. + +#include "rates_printer.h" + +namespace librealsense +{ + bool rates_printer::should_process(const rs2::frame& frame) + { + return frame && !frame.is(); + } + + rs2::frame rates_printer::process_frame(const rs2::frame_source& source, const rs2::frame& f) + { + if (_profiles.empty()) + { + std::cout << std::endl << "#### RS Frame Rate Printer ####" << std::endl; + _last_print_time = std::chrono::steady_clock::now(); + } + _profiles[f.get_profile().get()].on_frame_arrival(f); + print(); + return f; + } + + void rates_printer::print() + { + auto period = std::chrono::milliseconds(1000 / _render_rate).count(); + auto curr_time = std::chrono::steady_clock::now(); + double diff = std::chrono::duration_cast(curr_time - _last_print_time).count(); + + if (diff < period) + return; + + _last_print_time = curr_time; + + std::cout << std::fixed; + std::cout << std::setprecision(1); + std::cout << "\r"; + for (auto p : _profiles) + { + auto sp = p.second.get_stream_profile(); + std::cout << sp.stream_name() << "[" << sp.stream_index() << "]: " << + p.second.get_fps() << "/" << sp.fps() << " [FPS] || "; + } + } + + rates_printer::profile::profile() : _counter(0), _last_frame_number(0), _acctual_fps(0) + { + } + + int rates_printer::profile::last_frame_number() + { + return _last_frame_number; + } + + rs2::stream_profile rates_printer::profile::get_stream_profile() + { + return _stream_profile; + } + + float rates_printer::profile::get_fps() + { + return _acctual_fps; + } + + void rates_printer::profile::on_frame_arrival(const rs2::frame& f) + { + if (!_stream_profile) + { + _stream_profile = f.get_profile(); + _last_time = std::chrono::steady_clock::now(); + } + if (_last_frame_number >= f.get_frame_number()) + return; + _last_frame_number = f.get_frame_number(); + auto curr_time = std::chrono::steady_clock::now(); + _time_points.push_back(curr_time); + auto oldest = _time_points[0]; + if (_time_points.size() > _stream_profile.fps()) + _time_points.erase(_time_points.begin()); + double diff = std::chrono::duration_cast(curr_time - oldest).count() / 1000.0; + if (diff > 0) + _acctual_fps = _time_points.size() / diff; + } +} diff --git a/src/proc/rates_printer.h b/src/proc/rates_printer.h new file mode 100644 index 0000000000..401b266bfe --- /dev/null +++ b/src/proc/rates_printer.h @@ -0,0 +1,45 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2017 Intel Corporation. All Rights Reserved. + +#pragma once +#include "synthetic-stream.h" +#include +#include +#include + +namespace librealsense +{ + class rates_printer : public generic_processing_block + { + public: + rates_printer() {}; + virtual ~rates_printer() = default; + + protected: + rs2::frame process_frame(const rs2::frame_source& source, const rs2::frame& f) override; + bool should_process(const rs2::frame& frame) override; + private: + class profile + { + private: + rs2::stream_profile _stream_profile; + int _counter; + std::vector _time_points; + int _last_frame_number; + float _acctual_fps; + std::chrono::steady_clock::time_point _last_time; + public: + profile(); + int last_frame_number(); + rs2::stream_profile get_stream_profile(); + float get_fps(); + void on_frame_arrival(const rs2::frame& f); + }; + + void print(); + + int _render_rate = 2; + std::map _profiles; + std::chrono::steady_clock::time_point _last_print_time; + }; +} diff --git a/src/realsense.def b/src/realsense.def index 3ecfac5d8f..f334bc9f4a 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -164,6 +164,7 @@ EXPORTS rs2_create_temporal_filter_block rs2_create_spatial_filter_block rs2_create_hole_filling_filter_block + rs2_create_rates_printer_block rs2_create_disparity_transform_block rs2_embedded_frames_count rs2_extract_frame @@ -232,10 +233,15 @@ EXPORTS rs2_delete_pipeline rs2_pipeline_start rs2_pipeline_start_with_config + rs2_pipeline_start_with_callback + rs2_pipeline_start_with_config_and_callback + rs2_pipeline_start_with_callback_cpp + rs2_pipeline_start_with_config_and_callback_cpp rs2_pipeline_get_active_profile rs2_pipeline_profile_get_device rs2_pipeline_profile_get_streams rs2_delete_pipeline_profile + rs2_create_config rs2_delete_config rs2_config_enable_stream diff --git a/src/rs.cpp b/src/rs.cpp index cfd39970bb..908fd91423 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -25,10 +25,11 @@ #include "proc/decimation-filter.h" #include "proc/spatial-filter.h" #include "proc/hole-filling-filter.h" +#include "proc/rates_printer.h" #include "media/playback/playback_device.h" #include "stream.h" #include "../include/librealsense2/h/rs_types.h" -#include "pipeline.h" +#include "pipeline/pipeline.h" #include "environment.h" #include "proc/temporal-filter.h" #include "software-device.h" @@ -84,17 +85,17 @@ struct rs2_device_hub struct rs2_pipeline { - std::shared_ptr pipe; + std::shared_ptr pipeline; }; struct rs2_config { - std::shared_ptr config; + std::shared_ptr config; }; struct rs2_pipeline_profile { - std::shared_ptr profile; + std::shared_ptr profile; }; struct rs2_frame_queue @@ -1384,7 +1385,7 @@ rs2_pipeline* rs2_create_pipeline(rs2_context* ctx, rs2_error ** error) BEGIN_AP { VALIDATE_NOT_NULL(ctx); - auto pipe = std::make_shared(ctx->ctx); + auto pipe = std::make_shared(ctx->ctx); return new rs2_pipeline{ pipe }; } @@ -1394,7 +1395,7 @@ void rs2_pipeline_stop(rs2_pipeline* pipe, rs2_error ** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(pipe); - pipe->pipe->stop(); + pipe->pipeline->stop(); } HANDLE_EXCEPTIONS_AND_RETURN(, pipe) @@ -1402,7 +1403,7 @@ rs2_frame* rs2_pipeline_wait_for_frames(rs2_pipeline* pipe, unsigned int timeout { VALIDATE_NOT_NULL(pipe); - auto f = pipe->pipe->wait_for_frames(timeout_ms); + auto f = pipe->pipeline->wait_for_frames(timeout_ms); auto frame = f.frame; f.frame = nullptr; return (rs2_frame*)(frame); @@ -1415,7 +1416,7 @@ int rs2_pipeline_poll_for_frames(rs2_pipeline * pipe, rs2_frame** output_frame, VALIDATE_NOT_NULL(output_frame); librealsense::frame_holder fh; - if (pipe->pipe->poll_for_frames(&fh)) + if (pipe->pipeline->poll_for_frames(&fh)) { frame_interface* result = nullptr; std::swap(result, fh.frame); @@ -1432,7 +1433,7 @@ int rs2_pipeline_try_wait_for_frames(rs2_pipeline* pipe, rs2_frame** output_fram VALIDATE_NOT_NULL(output_frame); librealsense::frame_holder fh; - if (pipe->pipe->try_wait_for_frames(&fh, timeout_ms)) + if (pipe->pipeline->try_wait_for_frames(&fh, timeout_ms)) { frame_interface* result = nullptr; std::swap(result, fh.frame); @@ -1454,7 +1455,7 @@ NOEXCEPT_RETURN(, pipe) rs2_pipeline_profile* rs2_pipeline_start(rs2_pipeline* pipe, rs2_error ** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(pipe); - return new rs2_pipeline_profile{ pipe->pipe->start(std::make_shared()) }; + return new rs2_pipeline_profile{ pipe->pipeline->start(std::make_shared()) }; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, pipe) @@ -1462,15 +1463,53 @@ rs2_pipeline_profile* rs2_pipeline_start_with_config(rs2_pipeline* pipe, rs2_con { VALIDATE_NOT_NULL(pipe); VALIDATE_NOT_NULL(config); - return new rs2_pipeline_profile{ pipe->pipe->start(config->config) }; + return new rs2_pipeline_profile{ pipe->pipeline->start(config->config) }; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, pipe, config) +rs2_pipeline_profile* rs2_pipeline_start_with_callback(rs2_pipeline* pipe, rs2_frame_callback_ptr on_frame, void* user, rs2_error ** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(pipe); + librealsense::frame_callback_ptr callback(new librealsense::frame_callback(on_frame, user), [](rs2_frame_callback* p) { p->release(); }); + return new rs2_pipeline_profile{ pipe->pipeline->start(std::make_shared(), move(callback)) }; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, pipe, on_frame, user) + +rs2_pipeline_profile* rs2_pipeline_start_with_config_and_callback(rs2_pipeline* pipe, rs2_config* config, rs2_frame_callback_ptr on_frame, void* user, rs2_error ** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(pipe); + VALIDATE_NOT_NULL(config); + librealsense::frame_callback_ptr callback(new librealsense::frame_callback(on_frame, user), [](rs2_frame_callback* p) { p->release(); }); + return new rs2_pipeline_profile{ pipe->pipeline->start(config->config, callback) }; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, pipe, config, on_frame, user) + +rs2_pipeline_profile* rs2_pipeline_start_with_callback_cpp(rs2_pipeline* pipe, rs2_frame_callback* callback, rs2_error ** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(pipe); + VALIDATE_NOT_NULL(callback); + + return new rs2_pipeline_profile{ pipe->pipeline->start(std::make_shared(), + { callback, [](rs2_frame_callback* p) { p->release(); } }) }; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, pipe, callback) + +rs2_pipeline_profile* rs2_pipeline_start_with_config_and_callback_cpp(rs2_pipeline* pipe, rs2_config* config, rs2_frame_callback* callback, rs2_error ** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(pipe); + VALIDATE_NOT_NULL(config); + VALIDATE_NOT_NULL(callback); + + return new rs2_pipeline_profile{ pipe->pipeline->start(config->config, + { callback, [](rs2_frame_callback* p) { p->release(); } }) }; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, pipe, config, callback) + rs2_pipeline_profile* rs2_pipeline_get_active_profile(rs2_pipeline* pipe, rs2_error ** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(pipe); - return new rs2_pipeline_profile{ pipe->pipe->get_active_profile() }; + return new rs2_pipeline_profile{ pipe->pipeline->get_active_profile() }; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, pipe) @@ -1502,7 +1541,7 @@ NOEXCEPT_RETURN(, profile) //config rs2_config* rs2_create_config(rs2_error** error) BEGIN_API_CALL { - return new rs2_config{ std::make_shared() }; + return new rs2_config{ std::make_shared() }; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, 0) @@ -1597,7 +1636,7 @@ rs2_pipeline_profile* rs2_config_resolve(rs2_config* config, rs2_pipeline* pipe, { VALIDATE_NOT_NULL(config); VALIDATE_NOT_NULL(pipe); - return new rs2_pipeline_profile{ config->config->resolve(pipe->pipe) }; + return new rs2_pipeline_profile{ config->config->resolve(pipe->pipeline) }; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, config, pipe) @@ -1605,7 +1644,7 @@ int rs2_config_can_resolve(rs2_config* config, rs2_pipeline* pipe, rs2_error ** { VALIDATE_NOT_NULL(config); VALIDATE_NOT_NULL(pipe); - return config->config->can_resolve(pipe->pipe) ? 1 : 0; + return config->config->can_resolve(pipe->pipeline) ? 1 : 0; } HANDLE_EXCEPTIONS_AND_RETURN(0, config, pipe) @@ -1828,6 +1867,14 @@ rs2_processing_block* rs2_create_hole_filling_filter_block(rs2_error** error) BE } NOARGS_HANDLE_EXCEPTIONS_AND_RETURN(nullptr) +rs2_processing_block* rs2_create_rates_printer_block(rs2_error** error) BEGIN_API_CALL +{ + auto block = std::make_shared(); + + return new rs2_processing_block{ block }; +} +NOARGS_HANDLE_EXCEPTIONS_AND_RETURN(nullptr) + float rs2_get_depth_scale(rs2_sensor* sensor, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(sensor); diff --git a/third-party/sqlite/sqlite3.c b/third-party/sqlite/sqlite3.c index 4d26b9e04f..e90916faf6 100644 --- a/third-party/sqlite/sqlite3.c +++ b/third-party/sqlite/sqlite3.c @@ -10447,7 +10447,7 @@ struct fts5_api { ** autoconf-based build */ #ifdef _HAVE_SQLITE_CONFIG_H -#include "config.h" +#include "pipeline/resolver.h" #endif /************** Include sqliteLimit.h in the middle of sqliteInt.h ***********/ diff --git a/unit-tests/unit-tests-live.cpp b/unit-tests/unit-tests-live.cpp index 945556ddb4..6d7950a64b 100644 --- a/unit-tests/unit-tests-live.cpp +++ b/unit-tests/unit-tests-live.cpp @@ -4487,6 +4487,49 @@ TEST_CASE("Pipeline stream enable hierarchy", "[pipeline]") } } +TEST_CASE("Pipeline stream with callback", "[live][pipeline][using_pipeline]") +{ + rs2::context ctx; + + if (!make_context(SECTION_FROM_TEST_NAME, &ctx)) + return; + + rs2::pipeline pipe(ctx); + rs2::frame_queue q; + + auto callback = [&](const rs2::frame& f) + { + q.enqueue(f); + }; + + // Stream with callback + pipe.start(callback); + REQUIRE_THROWS(pipe.wait_for_frames()); + rs2::frameset frame_from_queue; + REQUIRE_THROWS(pipe.poll_for_frames(&frame_from_queue)); + REQUIRE_THROWS(pipe.try_wait_for_frames(&frame_from_queue)); + + rs2::frame frame_from_callback = q.wait_for_frame(); + pipe.stop(); + + REQUIRE(frame_from_callback); + REQUIRE(frame_from_queue == false); + + frame_from_callback = rs2::frame(); + frame_from_queue = rs2::frameset(); + + // Stream without callback + pipe.start(); + REQUIRE_NOTHROW(pipe.wait_for_frames()); + REQUIRE_NOTHROW(pipe.poll_for_frames(&frame_from_queue)); + REQUIRE_NOTHROW(pipe.try_wait_for_frames(&frame_from_queue)); + + pipe.stop(); + + REQUIRE(frame_from_callback == false); + REQUIRE(frame_from_queue); +} + TEST_CASE("Syncer sanity with software-device device", "[live][software-device]") { rs2::context ctx; if (make_context(SECTION_FROM_TEST_NAME, &ctx)) diff --git a/wrappers/csharp/Intel.RealSense/NativeMethods.cs b/wrappers/csharp/Intel.RealSense/NativeMethods.cs index 4a8c6f035b..1b0b8dc3bb 100644 --- a/wrappers/csharp/Intel.RealSense/NativeMethods.cs +++ b/wrappers/csharp/Intel.RealSense/NativeMethods.cs @@ -744,6 +744,19 @@ internal static extern int rs2_pipeline_poll_for_frames(IntPtr pipe, [DllImport(dllName, CallingConvention = CallingConvention.Cdecl)] internal static extern IntPtr rs2_pipeline_start_with_config(IntPtr pipe, IntPtr config, [MarshalAs(UnmanagedType.CustomMarshaler, MarshalTypeRef = typeof(Helpers.ErrorMarshaler))] out object error); + [DllImport(dllName, CallingConvention = CallingConvention.Cdecl)] + internal static extern IntPtr rs2_pipeline_start_with_callback(IntPtr pipe, + [MarshalAs(UnmanagedType.FunctionPtr)] frame_callback on_frame, + IntPtr user, [MarshalAs(UnmanagedType.CustomMarshaler, + MarshalTypeRef = typeof(Helpers.ErrorMarshaler))] out object error); + + + [DllImport(dllName, CallingConvention = CallingConvention.Cdecl)] + internal static extern IntPtr rs2_pipeline_start_with_config_and_callback(IntPtr pipe, IntPtr config, + [MarshalAs(UnmanagedType.FunctionPtr)] frame_callback on_frame, + IntPtr user, [MarshalAs(UnmanagedType.CustomMarshaler, + MarshalTypeRef = typeof(Helpers.ErrorMarshaler))] out object error); + [DllImport(dllName, CallingConvention = CallingConvention.Cdecl)] internal static extern IntPtr rs2_pipeline_get_active_profile(IntPtr pipe, [MarshalAs(UnmanagedType.CustomMarshaler, MarshalTypeRef = typeof(Helpers.ErrorMarshaler))] out object error); diff --git a/wrappers/csharp/Intel.RealSense/Pipeline.cs b/wrappers/csharp/Intel.RealSense/Pipeline.cs index f0bb9e26b1..4569f94d87 100644 --- a/wrappers/csharp/Intel.RealSense/Pipeline.cs +++ b/wrappers/csharp/Intel.RealSense/Pipeline.cs @@ -9,6 +9,10 @@ public class Pipeline : IDisposable, IEnumerable { internal HandleRef m_instance; + //public delegate void FrameCallback(Frame frame); + public delegate void FrameCallback(Frame frame); + private frame_callback m_callback; + public Pipeline(Context ctx) { object error; @@ -38,6 +42,34 @@ public PipelineProfile Start(Config cfg) return prof; } + public PipelineProfile Start(FrameCallback cb) + { + object error; + frame_callback cb2 = (IntPtr f, IntPtr u) => + { + using (var frame = new Frame(f)) + cb(frame); + }; + m_callback = cb2; + var res = NativeMethods.rs2_pipeline_start_with_callback(m_instance.Handle, cb2, IntPtr.Zero, out error); + var prof = new PipelineProfile(res); + return prof; + } + + public PipelineProfile Start(Config cfg, FrameCallback cb) + { + object error; + frame_callback cb2 = (IntPtr f, IntPtr u) => + { + using (var frame = new Frame(f)) + cb(frame); + }; + m_callback = cb2; + var res = NativeMethods.rs2_pipeline_start_with_config_and_callback(m_instance.Handle, cfg.m_instance.Handle, cb2, IntPtr.Zero, out error); + var prof = new PipelineProfile(res); + return prof; + } + public void Stop() { object error; diff --git a/wrappers/csharp/cs-tutorial-3-processing/Window.xaml.cs b/wrappers/csharp/cs-tutorial-3-processing/Window.xaml.cs index 563ca8d7b1..e87f405c95 100644 --- a/wrappers/csharp/cs-tutorial-3-processing/Window.xaml.cs +++ b/wrappers/csharp/cs-tutorial-3-processing/Window.xaml.cs @@ -60,13 +60,15 @@ public ProcessingWindow() cfg.EnableStream(Stream.Color, Format.Rgb8); var pp = pipeline.Start(cfg); - using (var p = pp.GetStream(Stream.Depth) as VideoStreamProfile) - imgDepth.Source = new WriteableBitmap(p.Width, p.Height, 96d, 96d, PixelFormats.Rgb24, null); - var updateDepth = UpdateImage(imgDepth); - + // Allocate bitmaps for rendring. + // Since the sample aligns the depth frames to the color frames, both of the images will have the color resolution using (var p = pp.GetStream(Stream.Color) as VideoStreamProfile) + { imgColor.Source = new WriteableBitmap(p.Width, p.Height, 96d, 96d, PixelFormats.Rgb24, null); + imgDepth.Source = new WriteableBitmap(p.Width, p.Height, 96d, 96d, PixelFormats.Rgb24, null); + } var updateColor = UpdateImage(imgColor); + var updateDepth = UpdateImage(imgDepth); // Create custom processing block // For demonstration purposes it will: