-
Couldn't load subscription status.
- Fork 4.9k
Hdr with split as select #7257
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Hdr with split as select #7257
Changes from all commits
cad9e88
c4ab14a
fe79a4c
f374b18
b44048e
89f0875
88823e4
84662d4
52b9fd2
6110a8a
7f4d0d0
b92a499
7687262
5c312dc
afdc3b8
1d33791
19a7219
28ec0ce
53f58f8
64294dc
7c0a270
90337dd
0b282af
9ad60ae
d24187a
25937a6
a56a926
7d37d56
8099473
447be06
02c9fe1
17175f6
73e13f6
3d36e3f
2547082
d270542
329a9bd
44ba744
6a292e1
bcc8d24
08b1a88
083fa13
75ecd7e
e6603ba
cc8c6e1
6c0f1c5
f86b801
048490c
ff3f40d
78070dc
6262b9c
76427b1
f9454ee
f97fad1
4b95c6c
8e8032e
f698f66
922c1d0
7cc3b03
11a0d36
891396e
2394c3a
275d054
f22eb79
c17341a
e51e2a9
35605d9
4b81db9
6120055
baead1a
ff35136
66c67d3
9c900ae
4a96675
509d552
956e82b
8de082c
2ca312c
b2aab6f
a828c0c
0fc2a25
8a5cd4f
78ee0f0
030de64
7326f76
6810980
6dfc450
1be63cd
e5c05db
e19d3ba
5f84733
f83f85a
187f504
0bbd3b3
153cc0f
66c3465
17f7397
be6fad4
12594e7
3b822c3
81b29aa
c3a15e7
2b7de4d
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,16 @@ | ||
| # License: Apache 2.0. See LICENSE file in root directory. | ||
| # Copyright(c) 2020 Intel Corporation. All Rights Reserved. | ||
| # minimum required cmake version: 3.1.0 | ||
| cmake_minimum_required(VERSION 3.1.0) | ||
|
|
||
| project(RealsenseExamplesHdr) | ||
|
|
||
| if(BUILD_GRAPHICAL_EXAMPLES) | ||
| add_executable(rs-hdr rs-hdr.cpp ../example.hpp) | ||
| set_property(TARGET rs-hdr PROPERTY CXX_STANDARD 11) | ||
| target_link_libraries(rs-hdr ${DEPENDENCIES}) | ||
| include_directories(rs-hdr ../ ../../third-party/tclap/include) | ||
| set_target_properties (rs-hdr PROPERTIES FOLDER "Examples") | ||
|
|
||
| install(TARGETS rs-hdr RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}) | ||
| endif() |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,114 @@ | ||
| # rs-hdr Sample | ||
|
|
||
| ## Overview | ||
|
|
||
| This sample demonstrates how to configure the camera for streaming and rendering Depth & Infrared data to the screen, using the High Dynamic Range (HDR) feature. | ||
| For explanations on the streaming and rendering, please refer to the rs-capture sample. | ||
|
|
||
| ## Code Overview | ||
|
|
||
| ### Finidng device | ||
| The HDR feature is available only for D400 Product line Devices. Finiding this device and getting its depth sensor: | ||
| ```cpp | ||
| // finding a device of D400 product line for working with HDR feature | ||
| if (dev.supports(RS2_CAMERA_INFO_PRODUCT_LINE) && | ||
| std::string(dev.get_info(RS2_CAMERA_INFO_PRODUCT_LINE)) == "D400") | ||
| { | ||
| device = dev; | ||
| } | ||
| rs2::depth_sensor depth_sensor = device.query_sensors().front(); | ||
| ``` | ||
|
|
||
|
|
||
| ### HDR Configuration | ||
| Before starting the configuration, we need to disable the Auto Exposure option: | ||
| ```cpp | ||
| // disable auto exposure before sending HDR configuration | ||
| if (depth_sensor.get_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE)) | ||
| depth_sensor.set_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, 0); | ||
| ``` | ||
|
|
||
| Next, we start to configure the HDR, by setting the size of the HDR sequence: | ||
| ```cpp | ||
| // setting the HDR sequence size to 2 frames | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_SIZE, 2); | ||
| ``` | ||
| Choosing an ID for this HDR configuration. The configuration will not be saved in the firmware, but this ID can help users that configure another HDR configuration to know when the new HDR is streaming, by checking this value via the metadata: | ||
| ```cpp | ||
| // configuring identifier for this hdr config (value must be in range [0,3]) | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_NAME, 1); | ||
| ``` | ||
|
|
||
| Configuring the first HDR sequence ID: | ||
| ```cpp | ||
| // configuration for the first HDR sequence ID | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_ID, 1); | ||
| depth_sensor.set_option(RS2_OPTION_EXPOSURE, 8500.f); | ||
| depth_sensor.set_option(RS2_OPTION_GAIN, 16.f); | ||
| ``` | ||
| Configuring the second HDR sequence ID: | ||
| ```cpp | ||
| // configuration for the second HDR sequence ID | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_ID, 2); | ||
| depth_sensor.set_option(RS2_OPTION_EXPOSURE, 150.f); | ||
| depth_sensor.set_option(RS2_OPTION_GAIN, 16.f); | ||
| ``` | ||
|
|
||
| Resetting the sequence ID to 0. This action permits the next setting of the exposure and gain option to be targetted to the normal UVC option, instead of being targetted to the HDR configuration (this call could have been omitted in this specific example): | ||
| ```cpp | ||
| // after setting the HDR sequence ID option to 0, setting exposure or gain | ||
| // will be targetted to the normal (UVC) exposure and gain options (not HDR configuration) | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_ID, 0); | ||
| ``` | ||
|
|
||
| Activating the HDR configuration in order to get the resulting streaming: | ||
| ```cpp | ||
| // turning ON the HDR with the above configuration | ||
| depth_sensor.set_option(RS2_OPTION_HDR_ENABLED, 1); | ||
| ``` | ||
|
|
||
| Then, the pipe is configured with depth and infrared streams. | ||
| In HDR mode the Infrared stream is used as an auxiliary invalidation filter to handle outlier Depth pixels and therefore, to enhance the outcome. The merging algorithm can also work without the infrared stream (if it is not activated by the user), but it workds better with the infrared. | ||
| ```cpp | ||
| // Start streaming with depth and infrared configuration | ||
| // The HDR merging algorithm can work with both depth and infrared,or only with depth, | ||
| // but the resulting stream is better when both depth and infrared are used. | ||
| rs2::config cfg; | ||
| cfg.enable_stream(RS2_STREAM_DEPTH); | ||
| cfg.enable_stream(RS2_STREAM_INFRARED, 1); | ||
| pipe.start(cfg); | ||
| ``` | ||
|
|
||
| ### Using Merging Filter | ||
| Initializing the merging filter - will be further used in order to merge frames from both HDR sequence IDs that have been configured: | ||
| ```cpp | ||
| // initializing the merging filter | ||
| rs2::depth_merge merging_filter; | ||
| ``` | ||
| After getting the frames, by using the wait_for_frames method, the merging filter is used: | ||
| ```cpp | ||
| // merging the frames from the different HDR sequence IDs | ||
| auto merged_frameset = merging_filter.process(data). | ||
| apply_filter(color_map); // Find and colorize the depth data; | ||
| app.show(merged_frameset); | ||
|
|
||
| ``` | ||
|
|
||
| ### Using Spliting Filter | ||
| Initializing also the spliting filter, with the requested sequence ID as 2: | ||
| ```cpp | ||
| // initializing the spliting filter | ||
| rs2::depth_split spliting_filter; | ||
| // setting the required sequence ID to be shown | ||
| spliting_filter.set_option(RS2_OPTION_SELECT_ID, 2); | ||
| ``` | ||
|
|
||
| After getting the frames, by using the wait_for_frames method, the spliting filter is used: | ||
| ```cpp | ||
| // getting frames only with the requested sequence ID | ||
| auto split_frameset = spliting_filter.process(data). | ||
| apply_filter(color_map); // Find and colorize the depth data; | ||
| app.show(split_frameset); | ||
|
|
||
| ``` | ||
|
|
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,166 @@ | ||
| // License: Apache 2.0. See LICENSE file in root directory. | ||
| // Copyright(c) 2020 Intel Corporation. All Rights Reserved. | ||
|
|
||
| #include <librealsense2/rs.hpp> // Include RealSense Cross Platform API | ||
| #include "example.hpp" // Include short list of convenience functions for rendering | ||
| #include <iostream> | ||
|
|
||
| // HDR Example demonstrates how to | ||
| // use the HDR feature - only for D400 product line devices | ||
| int main(int argc, char * argv[]) try | ||
| { | ||
| rs2::context ctx; | ||
|
|
||
| rs2::device_list devices_list = ctx.query_devices(); | ||
|
|
||
| size_t device_count = devices_list.size(); | ||
| if (!device_count) | ||
| { | ||
| std::cout << "No device detected. Is it plugged in?\n"; | ||
| return EXIT_SUCCESS; | ||
| } | ||
|
|
||
| rs2::device device; | ||
| bool device_found = false; | ||
| for (auto&& dev : devices_list) | ||
| { | ||
| // finding a device of D400 product line for working with HDR feature | ||
| if (dev.supports(RS2_CAMERA_INFO_PRODUCT_LINE) && | ||
| std::string(dev.get_info(RS2_CAMERA_INFO_PRODUCT_LINE)) == "D400") | ||
| { | ||
| device = dev; | ||
| device_found = true; | ||
| break; | ||
| } | ||
| } | ||
|
|
||
| if (!device_found) | ||
| { | ||
| std::cout << "No device from D400 product line detected. Is it plugged in?\n"; | ||
| return EXIT_SUCCESS; | ||
| } | ||
|
|
||
| rs2::depth_sensor depth_sensor = device.query_sensors().front(); | ||
|
|
||
| // disable auto exposure before sending HDR configuration | ||
| if (depth_sensor.get_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE)) | ||
| depth_sensor.set_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, 0); | ||
|
|
||
| // setting the HDR sequence size to 2 frames | ||
| if (depth_sensor.supports(RS2_OPTION_SEQUENCE_SIZE)) | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_SIZE, 2); | ||
| else | ||
| { | ||
| std::cout << "Firmware and/or SDK versions must be updated for the HDR feature to be supported.\n"; | ||
| return EXIT_SUCCESS; | ||
| } | ||
|
|
||
| // configuring id for this hdr config (value must be in range [0,3]) | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_NAME, 0); | ||
|
|
||
| // configuration for the first HDR sequence ID | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_ID, 1); | ||
| depth_sensor.set_option(RS2_OPTION_EXPOSURE, 8500); | ||
| depth_sensor.set_option(RS2_OPTION_GAIN, 16.f); | ||
|
|
||
| // configuration for the second HDR sequence ID | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_ID, 2); | ||
| depth_sensor.set_option(RS2_OPTION_EXPOSURE, 150); | ||
| depth_sensor.set_option(RS2_OPTION_GAIN, 16.f); | ||
|
|
||
| // after setting the HDR sequence ID opotion to 0, setting exposure or gain | ||
| // will be targetted to the normal (UVC) exposure and gain options (not HDR configuration) | ||
| depth_sensor.set_option(RS2_OPTION_SEQUENCE_ID, 0); | ||
|
|
||
| // turning ON the HDR with the above configuration | ||
| depth_sensor.set_option(RS2_OPTION_HDR_ENABLED, 1); | ||
|
|
||
| // Create a simple OpenGL window for rendering: | ||
| window app(1280, 720, "RealSense Capture Example"); | ||
|
|
||
| // 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 | ||
| rs2::config cfg; | ||
| cfg.enable_stream(RS2_STREAM_DEPTH); | ||
| cfg.enable_stream(RS2_STREAM_INFRARED, 1); | ||
| pipe.start(cfg); | ||
|
|
||
| // initializing the merging filter | ||
| rs2::hdr_merge merging_filter; | ||
|
|
||
| // initializing the spliting filter | ||
| rs2::sequence_id_filter spliting_filter; | ||
|
|
||
| // setting the required sequence ID to be shown | ||
| spliting_filter.set_option(RS2_OPTION_SEQUENCE_ID, 2); | ||
|
|
||
| // flag used to see the original stream or the merged one | ||
| bool true_for_merge_false_for_split = true; | ||
| int frames_without_hdr_metadata_params = 0; | ||
| while (app) // Application still alive? | ||
| { | ||
| 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 | ||
|
|
||
| auto depth_frame = data.get_depth_frame(); | ||
|
|
||
| if (!depth_frame.supports_frame_metadata(RS2_FRAME_METADATA_SUBPRESET_SEQUENCE_SIZE) || | ||
| !depth_frame.supports_frame_metadata(RS2_FRAME_METADATA_SUBPRESET_SEQUENCE_ID)) | ||
| { | ||
| ++frames_without_hdr_metadata_params; | ||
| if (frames_without_hdr_metadata_params > 20) | ||
| { | ||
| std::cout << "Firmware and/or SDK versions must be updated for the HDR feature to be supported.\n"; | ||
| return EXIT_SUCCESS; | ||
| } | ||
| data = data.apply_filter(color_map); | ||
| app.show(data); | ||
| continue; | ||
| } | ||
|
|
||
| auto hdr_id = depth_frame.get_frame_metadata(RS2_FRAME_METADATA_SUBPRESET_ID); | ||
| auto hdr_seq_size = depth_frame.get_frame_metadata(RS2_FRAME_METADATA_SUBPRESET_SEQUENCE_SIZE); | ||
| auto hdr_seq_id = depth_frame.get_frame_metadata(RS2_FRAME_METADATA_SUBPRESET_SEQUENCE_ID); | ||
| auto exp = depth_frame.get_frame_metadata(RS2_FRAME_METADATA_ACTUAL_EXPOSURE); | ||
|
|
||
| std::cout << "frame hdr metadata: hdr_seq_id = "<< hdr_seq_id << ", exposure = " << exp << std::endl; | ||
| // 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 | ||
| if (true_for_merge_false_for_split) | ||
| { | ||
| // merging the frames from the different HDR sequence IDs | ||
| auto merged_frameset = merging_filter.process(data). // merging frames with both hdr sequence IDs | ||
| apply_filter(color_map); // Find and colorize the depth data; | ||
| rs2_format format = merged_frameset.as<rs2::frameset>().get_depth_frame().get_profile().format(); | ||
| std::cout << ", after merge format = " << rs2_format_to_string(format) << std::endl; | ||
| app.show(merged_frameset); | ||
| } | ||
| else | ||
| { | ||
| auto split_frameset = spliting_filter.process(data) . // getting frames only with the requested sequence ID | ||
| apply_filter(color_map); // Find and colorize the depth data; | ||
| app.show(split_frameset); | ||
| } | ||
| } | ||
|
|
||
| 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; | ||
| } | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -62,6 +62,9 @@ typedef enum rs2_frame_metadata_value | |
| RS2_FRAME_METADATA_FRAME_LED_POWER , /**< Led power value 0-360. */ | ||
| RS2_FRAME_METADATA_RAW_FRAME_SIZE , /**< The number of transmitted payload bytes, not including metadata */ | ||
| RS2_FRAME_METADATA_GPIO_INPUT_DATA , /**< GPIO input data */ | ||
| RS2_FRAME_METADATA_SUBPRESET_ID , /**< sub-preset id */ | ||
|
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The options and metadata attributes should be added to wrappers: C#, Java, Matlab, NodeJs There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Will do There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. C# and Java - Done |
||
| RS2_FRAME_METADATA_SUBPRESET_SEQUENCE_ID , /**< sub-preset sequence id */ | ||
| RS2_FRAME_METADATA_SUBPRESET_SEQUENCE_SIZE , /**< sub-preset sequence size */ | ||
| RS2_FRAME_METADATA_COUNT | ||
| } rs2_frame_metadata_value; | ||
| const char* rs2_frame_metadata_to_string(rs2_frame_metadata_value metadata); | ||
|
|
||
Uh oh!
There was an error while loading. Please reload this page.