25 void virtual show()=0;
41 rs2_option option,
rs2::option_range range,
ImVec2 position,
ImVec2 size) :
slider(name, seq_id, init_value, range.
min, range.max, position, size),
42 _sensor(sensor), _option(option), _range(range){}
56 _sensor.set_option(_option,
_value);
80 void show(
const char* text)
115 _exposure_slider_seq_1(
"Exposure", 1, 8000,
117 _exposure_slider_seq_2(
"Exposure", 2, 18,
119 _gain_slider_seq_1(
"Gain", 1, 25,
121 _gain_slider_seq_2(
"Gain", 2, 16,
123 _text_box_hdr_explain(
"HDR Tutorial", { 120, 20 }, { 1000, 140 }),
124 _text_box_first_frame(
"frame 1", { 200, 150 }, { 170, 40 }),
125 _text_box_second_frame(
"frame 2", { 460, 150 }, { 170, 40 }),
126 _text_box_hdr_frame(
"hdr", { 850, 280 }, { 170, 40 })
151 _exposure_slider_seq_2.show();
152 _exposure_slider_seq_1.show();
153 _gain_slider_seq_2.show();
154 _gain_slider_seq_1.show();
156 _text_box_first_frame.remove_title_bar();
157 _text_box_first_frame.show(
"Sequence 1");
159 _text_box_second_frame.remove_title_bar();
160 _text_box_second_frame.show(
"Sequence 2");
162 _text_box_hdr_frame.remove_title_bar();
163 _text_box_hdr_frame.show(
"HDR Stream");
164 _text_box_hdr_explain.show(
"This demo provides a quick overview of the High Dynamic Range (HDR) feature.\nThe HDR configures and operates on sequences of two frames configurations, for which separate exposure and gain values are defined.\nBoth configurations are streamed and the HDR feature uses both frames in order to provide the best depth image.\nChange the values of the sliders to see the impact on the HDR Depth Image.");
180 int infrared_index = int(hdr_seq_id);
181 int depth_index = int(hdr_seq_id + hdr_seq_size);
182 int hdr_index = int(hdr_seq_id + hdr_seq_size + 1);
186 if (hdr_seq_size > 0) {
187 _frames_map[infrared_index].first = infrared_frame;
189 _frames_map[hdr_index].first = hdr_frame;
GLuint const GLchar * name
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
IMGUI_API void SetNextWindowPos(const ImVec2 &pos, ImGuiSetCond cond=0)
GLsizei const GLchar *const * string
text_box(const char *name, ImVec2 position, ImVec2 size)
IMGUI_API bool Begin(const char *name, bool *p_open=NULL, ImGuiWindowFlags flags=0)
slider(const char *name, int seq_id, float init_value, float min_value, float max_value, ImVec2 position, ImVec2 size)
std::map< int, frame_and_tile_property > frames_mosaic
IMGUI_API void SetNextWindowSize(const ImVec2 &size, ImGuiSetCond cond=0)
std::pair< rs2::frame, tile_properties > frame_and_tile_property
IMGUI_API void Text(const char *fmt,...) IM_PRINTFARGS(1)
void show(const char *text)
void ImGui_ImplGlfw_NewFrame(float scale_factor)
IMGUI_API bool SliderFloat(const char *label, float *v, float v_min, float v_max, const char *display_format="%.3f", float power=1.0f, bool render_bg=false)
long long rs2_metadata_type
hdr_slider(const char *name, int seq_id, float init_value, rs2::sensor &sensor, rs2_option option, rs2::option_range range, ImVec2 position, ImVec2 size)
std::string to_string(T value)