42 using namespace rs400;
48 if ((width == 240 && height == 320) || (width == 320 && height == 240))
50 else if ((width == 640 && height == 480) || (height == 640 && width == 480))
52 else if ((width == 1024 && height == 768) || (height == 768 && width == 1024))
82 const std::vector< std::pair< int, int > > & res_values )
86 auto iter = std::find_if( res_values.begin(),
94 if( iter != res_values.end() )
96 return static_cast< int >(
std::distance( res_values.begin(), iter ) );
99 throw std::runtime_error(
"cannot convert sensor mode to resolution ID" );
104 return{ c.
y, c.
x, c.
z, c.
w };
109 auto res =
ImVec4(r / (
float)255, g / (
float)255, b / (
float)255, a / (
float)255);
110 #ifdef FLIP_COLOR_SCHEME 111 if (!consistent_color)
return flip(
res);
135 template <
typename T>
147 catch (
const std::exception& e)
153 return "Unknown error occurred";
161 throw std::runtime_error(
to_string() <<
"Invalid binary file specified " << filename <<
" verify the source path and location permissions");
165 std::size_t
size = file.tellg();
167 throw std::runtime_error(
to_string() <<
"Invalid binary file " << filename <<
" provided - zero-size ");
168 file.seekg(0, std::ios_base::beg);
171 std::vector<uint8_t>
v(size);
174 file.read((
char*)&v[0], size);
184 throw std::runtime_error(
to_string() <<
"Invalid binary file specified " << filename <<
" verify the target path and location permissions");
185 file.write((
char*)bytes.data(), bytes.size());
197 static const ImWchar icons_ranges[] = { 0xf000, 0xf999, 0 };
271 std::shared_ptr<rs2::processing_block> pb,
bool enable)
273 for (
auto opt : pb->get_supported_options())
275 auto val = pb->get_option(opt);
278 key += pb->get_option_name(opt);
279 config_file::instance().set(key.c_str(),
val);
284 config_file::instance().set(key.c_str(),
enable);
288 std::shared_ptr<rs2::processing_block> pb,
bool enable =
true)
290 for (
auto opt : pb->get_supported_options())
294 key += pb->get_option_name(opt);
295 if (config_file::instance().
contains(key.c_str()))
297 float val = config_file::instance().get(key.c_str());
300 auto range = pb->get_option_range(opt);
302 pb->set_option(opt, val);
312 if (config_file::instance().
contains(key.c_str()))
314 return config_file::instance().get(key.c_str());
339 std::stringstream ss;
348 for (
auto& dm : devices)
350 for (
auto&
kvp : dm->infos)
352 if (
kvp.first !=
"Recommended Firmware Version" &&
353 kvp.first !=
"Debug Op Code" &&
354 kvp.first !=
"Physical Port" &&
355 kvp.first !=
"Product Id")
356 ss <<
"|**" <<
kvp.first <<
"**|" <<
kvp.second <<
"|\n";
360 ss <<
"\nPlease provide a description of the problem";
368 int x =
std::min(std::max(
int(texcoords.
u*w + .5f), 0), w - 1);
369 int y =
std::min(std::max(
int(texcoords.
v*
h + .5f), 0),
h - 1);
371 const auto texture_data =
reinterpret_cast<const uint8_t*
>(texture.
get_data());
372 return std::tuple<uint8_t, uint8_t, uint8_t>(
373 texture_data[
idx], texture_data[idx + 1], texture_data[idx + 2]);
381 auto n = std::make_shared<export_notification_model>(manager);
385 auto invoke = [
n](std::function<void()>
action) {
388 manager->start(invoke);
398 outfile.write(static_cast<const char*>(
image.get_data()),
image.get_height()*
image.get_stride_in_bytes());
413 std::ofstream csv(filename);
416 csv <<
"Frame Info: " << std::endl <<
"Type," <<
profile.stream_name() << std::endl;
418 csv <<
"Frame Number," <<
image.get_frame_number() << std::endl;
419 csv <<
"Timestamp (ms)," << std::fixed << std::setprecision(2) <<
image.get_timestamp() << std::endl;
420 csv <<
"Resolution x," << (int)
image.get_width() << std::endl;
421 csv <<
"Resolution y," << (int)
image.get_height() << std::endl;
422 csv <<
"Bytes per pixel," << (int)
image.get_bytes_per_pixel() << std::endl;
427 csv << std::endl <<
"Intrinsic:," << std::fixed << std::setprecision(6) << std::endl;
448 units =
"( deg/sec )";
450 units =
"( m/sec^2 )";
451 auto axes = motion.get_motion_data();
452 std::ofstream csv( filename );
455 csv <<
"Frame Info: " << std::endl <<
"Type," <<
profile.stream_name() << std::endl;
458 csv <<
"Timestamp (ms)," << std::fixed << std::setprecision( 2 )
460 csv << std::setprecision( 7 ) <<
"Axes" << units <<
", " <<
axes << std::endl;
473 auto pose_data =
pose.get_pose_data();
474 std::ofstream csv( filename );
477 csv <<
"Frame Info: " << std::endl <<
"Type," <<
profile.stream_name() << std::endl;
480 csv <<
"Timestamp (ms)," << std::fixed << std::setprecision( 2 )
482 csv << std::setprecision( 7 ) <<
"Acceleration( meters/sec^2 ), " 483 << pose_data.acceleration << std::endl;
484 csv << std::setprecision( 7 ) <<
"Angular_acceleration( radians/sec^2 ), " 485 << pose_data.angular_acceleration << std::endl;
486 csv << std::setprecision( 7 ) <<
"Angular_velocity( radians/sec ), " 487 << pose_data.angular_velocity << std::endl;
488 csv << std::setprecision( 7 )
489 <<
"Mapper_confidence( 0x0 - Failed 0x1 - Low 0x2 - Medium 0x3 - High ), " 490 << pose_data.mapper_confidence << std::endl;
491 csv << std::setprecision( 7 )
492 <<
"Rotation( quaternion rotation (relative to initial position) ), " 493 << pose_data.rotation << std::endl;
494 csv << std::setprecision( 7 )
495 <<
"Tracker_confidence( 0x0 - Failed 0x1 - Low 0x2 - Medium 0x3 - High ), " 496 << pose_data.tracker_confidence << std::endl;
497 csv << std::setprecision( 7 ) <<
"Translation( meters ), " << pose_data.translation
499 csv << std::setprecision( 7 ) <<
"Velocity( meters/sec ), " << pose_data.velocity
510 std::vector<const char*>
res;
511 for (
auto&&
s : vec) res.push_back(
s.c_str());
518 std::shared_ptr<options>
options,
519 bool* options_invalidated,
524 std::stringstream ss;
526 ss << opt_base_label <<
"/" << options->get_option_name(opt);
527 option.
id = ss.str();
530 option.
label = options->get_option_name(opt) +
std::string(
"##") + ss.str();
534 option.
supported = options->supports(opt);
539 option.
range = options->get_option_range(opt);
540 option.
read_only = options->is_option_read_only(opt);
541 option.
value = options->get_option(opt);
545 option.
range = { 0, 1, 0, 0 };
556 if (endpoint->supports(opt))
561 use_option_name =
false;
563 auto desc = endpoint->get_option_description(opt);
571 auto bool_value =
value > 0.0f;
574 if (allow_change((bool_value ? 1.0
f : 0.0
f), error_message))
578 << (bool_value?
"1.0" :
"0.0") <<
" (" << (bool_value ?
"ON" :
"OFF") <<
")");
580 set_option(opt, bool_value ? 1.f : 0.f, error_message);
581 *invalidate_flag =
true;
623 if (is_all_integers())
671 float dummy = std::floor(value);
680 strcpy(buff, edit_value.c_str());
687 error_message =
"Invalid numeric input!";
689 else if (new_value < range.min || new_value >
range.max)
692 <<
" is out of bounds [" <<
range.min <<
", " 697 set_option(opt, new_value, error_message);
704 else if (is_all_integers())
706 auto int_value =
static_cast<int>(
value);
709 static_cast<int>(
range.min),
710 static_cast<int>(
range.max),
711 static_cast<int>(
range.step)))
715 set_option(opt, static_cast<float>(int_value), error_message);
716 *invalidate_flag =
true;
722 float tmp_value =
value;
726 auto loffset = std::abs(fmod(tmp_value,
range.step));
727 auto roffset =
range.step - loffset;
729 tmp_value = (loffset < roffset) ? tmp_value - loffset : tmp_value + roffset;
731 tmp_value = (loffset < roffset) ? tmp_value + loffset : tmp_value - roffset;
732 tmp_value = (tmp_value <
range.min) ?
range.min : tmp_value;
733 tmp_value = (tmp_value >
range.max) ?
range.max : tmp_value;
735 set_option(opt, tmp_value, error_message);
736 *invalidate_flag =
true;
748 std::string txt =
to_string() << (use_option_name ? endpoint->get_option_name(opt) : desc) <<
":";
764 std::vector<const char*> labels;
765 auto selected = 0,
counter = 0;
769 labels.push_back(endpoint->get_option_value_description(opt,
i));
775 int tmp_selected = selected;
776 float tmp_value =
value;
778 if (
ImGui::Combo(
id.c_str(), &tmp_selected, labels.data(),
779 static_cast<int>(labels.size())))
781 tmp_value =
range.min +
range.step * tmp_selected;
783 << tmp_value <<
" (" << labels[tmp_selected] <<
")");
784 set_option(opt, tmp_value, error_message);
785 selected = tmp_selected;
786 if (invalidate_flag) *invalidate_flag =
true;
808 if (
index != std::string::npos)
814 if (!
dev->roi_checked)
819 dev->roi_checked =
true;
827 dev->roi_checked =
false;
833 ImGui::SetTooltip(
"Select custom region of interest for the auto-exposure algorithm\nClick the button, then draw a rect on the frame");
844 supported = endpoint->supports(opt);
852 void option_model::update_read_only_status(
std::string& error_message)
856 read_only = endpoint->is_option_read_only(opt);
868 if ((supported = endpoint->supports(opt)))
870 value = endpoint->get_option(opt);
871 range = endpoint->get_option_range(opt);
872 read_only = endpoint->is_option_read_only(opt);
878 model.
add_notification({
to_string() <<
"Could not refresh read-only option " << endpoint->get_option_name(opt) <<
": " << e.what(),
887 bool option_model::is_all_integers()
const 893 bool option_model::is_enum()
const 895 if (
range.step < 0.001f)
return false;
899 if (endpoint->get_option_value_description(opt,
i) ==
nullptr)
905 bool option_model::is_checkbox()
const 907 return range.max == 1.0f &&
918 void subdevice_model::populate_options(std::map<int, option_model>& opt_container,
921 std::shared_ptr<options>
options,
922 bool* options_invalidated,
925 for (
auto&&
i : options->get_supported_options())
929 opt_container[opt] =
create_option_model(opt, opt_base_label, model, options, options_invalidated, error_message);
935 std::stringstream ss;
942 processing_block_model::processing_block_model(
945 std::shared_ptr<rs2::filter> block,
948 : _owner(owner),
_name(name), _block(block), _invoker(
invoker), _enabled(enable)
950 std::stringstream ss;
953 <<
"/" << (
long long)
this;
983 bool* options_invalidated,
986 for (
auto opt :
_block->get_supported_options())
994 std::shared_ptr<sensor>
s,
995 std::shared_ptr< atomic_objects_in_frame > device_detected_objects,
998 bool new_device_connected
1000 : s(s), dev(dev),
tm2(), ui(), last_valid_ui(),
1001 streaming(false), _pause(false),
1015 std::stringstream ss;
1017 <<
"." << device_name
1018 <<
"." << sensor_name;
1019 auto key = ss.str();
1052 auto filters = s->get_recommended_filters();
1063 for (
auto&&
f : s->get_recommended_filters())
1065 auto shared_filter = std::make_shared<filter>(
f);
1066 auto model = std::make_shared<processing_block_model>(
1068 [=](
rs2::frame f) {
return shared_filter->process(
f); }, error_message);
1071 model->visible =
false;
1081 model->enable(
false);
1085 model->enable(
false);
1088 model->enable(
false);
1093 model->enable(
false);
1102 if (device_pid ==
"0B5B")
1127 auto filter = create_filter();
1131 std::shared_ptr< processing_block_model >
model(
1141 auto colorizer = std::make_shared<processing_block_model>(
1143 [=](
rs2::frame f) {
return depth_colorizer->colorize(
f); }, error_message);
1152 if (device_pid ==
"0B5B")
1163 <<
"/" << (
long long)
this;
1172 static bool showed_metadata_prompt =
false;
1174 if (!has_metadata && !showed_metadata_prompt)
1176 auto n = std::make_shared<metadata_warning_model>();
1178 showed_metadata_prompt =
true;
1184 auto sensor_profiles = s->get_stream_profiles();
1185 reverse(
begin(sensor_profiles),
end(sensor_profiles));
1187 auto default_resolution = std::make_pair(1280, 720);
1188 auto default_fps = 30;
1189 for (
auto&&
profile : sensor_profiles)
1191 std::stringstream
res;
1196 default_resolution = std::pair<int, int>(vid_prof.width(), vid_prof.height());
1199 res << vid_prof.width() <<
" x " << vid_prof.height();
1204 std::stringstream
fps;
1226 if (!any_stream_enabled)
1228 if (sensor_profiles.size() > 0)
1241 int selection_index{};
1245 for (
auto fps_array : fps_values_per_stream)
1271 if (new_device_connected)
1287 catch( not_implemented_error
const &)
1313 std::vector<int> first_fps_group;
1314 size_t group_index = 0;
1327 if (fps_group.empty())
1330 for (
auto& fps1 : first_fps_group)
1334 [&](
const int& fps2)
1336 return fps2 == fps1;
1355 auto streaming_tooltip = [&]() {
1368 if (res_chars.size() > 0)
1371 streaming_tooltip();
1380 streaming_tooltip();
1387 if (
ImGui::Combo(label.c_str(), &tmp_selected_res_id, res_chars.data(),
1388 static_cast<int>(res_chars.size())))
1415 static_cast< rs2_sensor_mode >( sensor_mode_val ),
1425 <<
" is not supported on this device";
1446 streaming_tooltip();
1455 streaming_tooltip();
1462 static_cast<int>(fps_chars.size())))
1485 if (
f.second.size() == 0)
1495 streaming_tooltip();
1518 <<
" " <<
f.first <<
" format";
1523 streaming_tooltip();
1530 streaming_tooltip();
1537 static_cast<int>(formats_chars.size()));
1548 streaming_tooltip();
1553 <<
f.first <<
" fps";
1558 streaming_tooltip();
1565 static_cast<int>(fps_chars.size()));
1585 std::vector<stream_profile> results;
1609 if (vid_prof.width() ==
width &&
1610 vid_prof.height() ==
height &&
1611 p.unique_id() == stream &&
1614 results.push_back(
p);
1619 if (
p.fps() ==
fps &&
1620 p.unique_id() == stream &&
1622 results.push_back(
p);
1628 if (results.size() == 0)
1632 return results.size() >=
size_t(std::count_if(
stream_enabled.begin(),
stream_enabled.end(), [](
const std::pair<int, bool>& kpv)->
bool {
return kpv.second ==
true; }));
1637 if (profiles_vec.empty())
1641 for (
auto&
p : profiles_vec)
1643 stream_enabled[
p.unique_id()] =
true;
1646 for (
int i = 0;
i < format_vec.size();
i++)
1648 if (format_vec[
i] ==
p.format())
1676 template<
typename T,
typename V>
1686 if (
s.second ==
true && vid_prof.unique_id() ==
s.first && cond(vid_prof))
1688 profiles_map[
key].insert(std::pair<int, stream_profile>(p.
unique_id(),
p));
1689 if (profiles_map[key].
size() == num_streams)
1692 for (
auto&
it : profiles_map[key])
1693 results.push_back(
it.second);
1696 else if (results.empty() && num_streams > 1 && profiles_map[
key].size() == num_streams - 1)
1698 for (
auto&
it : profiles_map[key])
1699 results.push_back(
it.second);
1702 else if (!def_p.
get() && cond(vid_prof))
1716 int score_a = 0, score_b = 0;
1730 return score_a < score_b;
1731 if (a_vp.width() !=
width || a_vp.height() !=
height)
1735 return score_a < score_b;
1741 std::vector<stream_profile> results;
1745 int num_streams = 0;
1747 if (
s.second ==
true)
1753 std::vector<stream_profile> sorted_profiles =
profiles;
1758 std::map<int, std::map<int, stream_profile>> profiles_by_fps;
1759 for (
auto&&
p : sorted_profiles)
1763 profiles_by_fps, results,
p.fps(), num_streams, def_p))
1770 std::map<std::tuple<int, int>, std::map<int, stream_profile>> profiles_by_res;
1772 for (
auto&&
p : sorted_profiles)
1777 profiles_by_res, results, std::make_tuple(vid_prof.width(), vid_prof.height()), num_streams, def_p))
1784 if (num_streams == 0)
1790 std::vector<stream_profile> matching_profiles;
1791 std::map<std::tuple<int, int, int>, std::map<int, stream_profile>> profiles_by_fps_res;
1797 if (stream_enabled[
it.first])
1803 stream_id =
it.first;
1807 for (
auto&&
p : sorted_profiles)
1810 if (
p.unique_id() == stream_id &&
p.format() ==
format)
1812 profiles_by_fps_res[std::make_tuple(
p.fps(), vid_prof.width(), vid_prof.height())].insert(std::pair<int, stream_profile>(
p.unique_id(),
p));
1813 matching_profiles.push_back(
p);
1819 for (
auto&&
p : sorted_profiles)
1826 profiles_by_fps_res, results, std::make_tuple(
p.fps(), vid_prof.width(), vid_prof.height()), num_streams, def_p))
1833 if (num_streams == 0)
1836 std::vector<stream_profile> matching_profiles;
1837 std::map<rs2_format, std::map<int, stream_profile>> profiles_by_format;
1839 for (
auto&&
p : sorted_profiles)
1844 profiles_by_format, results,
p.format(), num_streams, def_p))
1847 if (results.size() < num_streams)
1850 std::map<std::tuple<int, int, int>, std::map<int, stream_profile>> profiles_by_fps_res;
1851 for (
auto&&
p : sorted_profiles)
1857 std::make_tuple(
p.fps(), vid_prof.width(), vid_prof.height()), num_streams, def_p))
1863 if (results.empty())
1864 results.push_back(def_p);
1871 std::vector<stream_profile> results;
1873 std::stringstream error_message;
1874 error_message <<
"The profile ";
1902 if (vid_prof.width() ==
width &&
1903 vid_prof.height() ==
height &&
1904 p.unique_id() == stream &&
1907 results.push_back(
p);
1915 if (
p.fps() ==
fps &&
1916 p.unique_id() == stream &&
1918 results.push_back(
p);
1923 if (results.size() == 0)
1925 error_message <<
" is unsupported!";
1926 throw std::runtime_error(error_message.str());
1934 not_model->add_log(
"Stopping streaming");
1938 if (
"Pose" ==
kvp.second)
1940 this->
tm2.reset_trajectory();
1941 this->
tm2.record_trajectory(
false);
1994 throw std::runtime_error(
to_string() <<
"Zero order filter requires both IR and Depth streams turned on.\nPlease rectify the configuration and rerun");
2016 std::stringstream ss;
2017 ss <<
"Starting streaming of ";
2018 for (
size_t i = 0;
i < profiles.size();
i++)
2020 ss << profiles[
i].stream_type();
2021 if (
i < profiles.size() - 1) ss <<
", ";
2029 if (
"Pose" ==
kvp.second)
2031 this->
tm2.record_trajectory(
true);
2087 opt_md.update_all_fields(error_message, notifications);
2103 roi_rect.
w =
static_cast<float>(
r.max_x -
r.min_x);
2104 roi_rect.
h =
static_cast<float>(
r.max_y -
r.min_y);
2116 opt_md.dev->depth_units = opt_md.value;
2120 opt_md.dev->stereo_baseline = opt_md.value;
2128 bool update_read_only_options,
std::string& error_message,
2131 for (
auto& opt : drawing_order)
2133 draw_option(opt, update_read_only_options, error_message, notifications);
2140 if (
std::find(drawing_order.begin(), drawing_order.end(), opt) == drawing_order.end())
2142 draw_option(opt, update_read_only_options, error_message, notifications);
2152 [&](
const std::pair<int, option_model>&
p) {
return p.second.supported && !
viewer.
is_option_skipped(p.second.opt); });
2159 if (update_read_only_options)
2161 update_supported(error_message);
2162 if (supported && is_streaming)
2164 update_read_only_status(error_message);
2167 update_all_fields(error_message, model);
2171 if (custom_draw_method)
2172 return custom_draw_method(*
this, error_message, model);
2174 return draw(error_message, model);
2181 endpoint->set_option(opt, req_value);
2188 try {
value = endpoint->get_option(opt); }
2194 _stream_not_alive(
std::
chrono::milliseconds(1500)),
2195 _stabilized_reflectivity(10)
2205 if (
dev &&
dev->is_paused())
return nullptr;
2278 (
dev->is_paused() ||
2290 (
dev->is_paused() ||
2300 auto ms = duration_cast<milliseconds>(diff).
count();
2311 texture->colorize = d->depth_colorizer;
2312 texture->yuy2rgb = d->yuy2rgb;
2313 texture->depth_decode = d->depth_decoder;
2318 static_cast<float>(vd.width()),
2319 static_cast<float>(vd.height()) };
2322 static_cast<float>(vd.width()),
2323 static_cast<float>(vd.height()) };
2346 const std::map< int, stream_model > &
streams,
2347 std::stringstream & ss,
2350 bool reflectivity_valid =
false;
2352 static const int MAX_PIXEL_MOVEMENT_TOLERANCE = 0;
2365 = std::find_if( streams.cbegin(),
2367 [](
const std::pair< const int, stream_model > &
stream ) {
2373 = std::find_if( streams.cbegin(),
2375 [](
const std::pair< const int, stream_model > &
stream ) {
2379 if ((ir_stream != streams.end()) && (depth_stream != streams.end()))
2381 auto depth_val = 0.0f;
2383 depth_stream->second.texture->try_pick( x, y, &depth_val );
2384 ir_stream->second.texture->try_pick( x, y, &ir_val );
2393 reflectivity_valid =
true;
2403 ref_str =
to_string() << std::dec << round( stabilized_pixel_ref * 100 ) <<
"%";
2408 int dots_count =
static_cast<int>(
_reflectivity->get_samples_ratio() * 7);
2409 ref_str =
"calculating...";
2418 ss <<
", Reflectivity: " << ref_str;
2420 ss <<
"\nReflectivity: " << ref_str;
2424 return reflectivity_valid;
2429 if (
dev->roi_checked)
2469 roi.max_x =
static_cast<int>(std::max(
r.x,
r.x +
r.w));
2470 roi.min_y =
static_cast<int>(
std::min(
r.y,
r.y +
r.h));
2471 roi.max_y =
static_cast<int>(std::max(
r.y,
r.y +
r.h));
2491 auto x_margin = (int)
size.x / 8;
2492 auto y_margin = (
int)
size.y / 8;
2498 (int)
size.x - x_margin - 1,
2499 (
int)
size.y - y_margin - 1 });
2503 dev->roi_rect = { 0, 0, 0, 0 };
2511 dev->roi_checked =
false;
2522 auto r =
dev->roi_rect;
2536 return ImGui::Combo(
id.c_str(), &new_index, device_names_chars.data(),
static_cast<int>(device_names.size()));
2541 const auto top_bar_height = 32.f;
2542 auto num_of_buttons = 5;
2545 if (viewer.
streams.size() > 1) ++num_of_buttons;
2562 if (
dev->_is_being_recorded) offset += 23;
2578 tooltip =
to_string() << dev_name <<
" s.n:" << dev_serial <<
" | " << sensor_name <<
", " << stream_name <<
" stream";
2579 const auto approx_char_width = 12;
2580 if (stream_rect.
w - 32 * num_of_buttons >= (dev_name.size() + dev_serial.size() + sensor_name.size() + stream_name.size()) * approx_char_width)
2586 auto short_sn = dev_serial;
2587 short_sn.erase(0, dev_serial.size() - 5).replace(0, 2,
"..");
2589 auto label_length = stream_rect.
w - 32 * num_of_buttons;
2591 if (label_length >= (short_name.size() + dev_serial.size() + sensor_name.size() + stream_name.size()) * approx_char_width)
2592 label =
to_string() << short_name <<
" s.n:" << dev_serial <<
" | " << sensor_name <<
" " << stream_name <<
" stream";
2593 else if (label_length >= (short_name.size() + short_sn.size() + stream_name.size()) * approx_char_width)
2594 label =
to_string() << short_name <<
" s.n:" << short_sn <<
" " << stream_name <<
" stream";
2595 else if (label_length >= short_name.size() * approx_char_width)
2596 label =
to_string() << short_name <<
" " << stream_name;
2768 if (viewer.
streams.size() > 1)
2828 static const auto y_offset_info_rect = 0.f;
2829 static const auto x_offset_info_rect = 0.f;
2830 auto width_info_rect = stream_rect.
w - 2.f * x_offset_info_rect;
2833 stream_rect.
y + y_offset_info_rect,
2873 ImGui::TextUnformatted(
"Timestamp Domain: System Time. Hardware Timestamps unavailable!\nPlease refer to frame_metadata.md for more information");
2906 label =
to_string() <<
"FPS: " << std::setprecision(2) << std::setw(7) << std::fixed <<
fps.
get_fps();
2910 ImGui::SetTooltip(
"%s",
"FPS is calculated based on timestamps and not viewer time");
2921 std::vector<attribute> stream_details;
2925 stream_details.push_back({
"Frame Timestamp",
2927 "Frame Timestamp is normalized represetation of when the frame was taken.\n" 2928 "It's a property of every frame, so when exact creation time is not provided by the hardware, an approximation will be used.\n" 2929 "Clock Domain feilds helps to interpret the meaning of timestamp\n" 2930 "Timestamp is measured in milliseconds, and is allowed to roll-over (reset to zero) in some situations" });
2931 stream_details.push_back({
"Clock Domain",
2933 "Clock Domain describes the format of Timestamp field. It can be one of the following:\n" 2934 "1. System Time - When no hardware timestamp is available, system time of arrival will be used.\n" 2935 " System time benefits from being comparable between device, but suffers from not being able to approximate latency.\n" 2936 "2. Hardware Clock - Hardware timestamp is attached to the frame by the device, and is consistent accross device sensors.\n" 2937 " Hardware timestamp encodes precisely when frame was captured, but cannot be compared across devices\n" 2938 "3. Global Time - Global time is provided when the device can both offer hardware timestamp and implements Global Timestamp Protocol.\n" 2939 " Global timestamps encode exact time of capture and at the same time are comparable accross devices." });
2940 stream_details.push_back({
"Frame Number",
2942 "Most devices do not guarantee consequitive frames to have conseuquitive frame numbers\n" 2943 "But it is true most of the time" });
2947 stream_details.push_back({
"Hardware Size",
2950 stream_details.push_back({
"Display Size",
2952 "When Post-Processing is enabled, the actual display size of the frame may differ from original capture size" });
2954 stream_details.push_back({
"Pixel Format",
2957 stream_details.push_back({
"Hardware FPS",
2959 "Hardware FPS captures the number of frames per second produced by the device.\n" 2960 "It is possible and likely that not all of these frames will make it to the application." });
2962 stream_details.push_back({
"Viewer FPS",
2964 "Viewer FPS captures how many frames the application manages to render.\n" 2965 "Frame drops can occur for variety of reasons." });
2967 stream_details.push_back({
"",
"",
"" });
2974 stream_details.push_back({ no_md,
"",
"" });
2977 std::map<rs2_frame_metadata_value, std::string> descriptions = {
2983 "When AE is set On, the value is controlled by firmware. Integer value" },
2991 {
RS2_FRAME_METADATA_EXPOSURE_PRIORITY ,
"Exposure priority. When enabled Auto-exposure algorithm is allowed to reduce requested FPS to sufficiently increase exposure time (an get enough light)" },
3003 if (descriptions.find(
val) != descriptions.end()) desc = descriptions[
val];
3008 float max_text_width = 0.;
3009 for (
auto&&
kvp : stream_details)
3012 for (
auto&& at : stream_details)
3018 if (at.name == no_md)
3020 auto text =
"Per-frame metadata is not enabled at the OS level!\nPlease follow the installation guide for the details";
3023 for (
int i = 3;
i > 0;
i -= 1)
3037 if (at.name !=
"") text =
to_string() << at.name <<
":";
3040 for (
int i = 3;
i > 0;
i -= 1)
3048 if (at.description !=
"")
3059 for (
int i = 3; i > 0; i -= 1)
3074 (
char*)text.c_str(),
3098 std::stringstream ss;
3100 auto ts = cursor_rect.normalize(stream_rect);
3105 ss << std::fixed << std::setprecision(0) <<
x <<
", " <<
y;
3110 ss <<
" 0x" << std::hex << static_cast< int >( round(
val ) );
3113 bool show_max_range =
false;
3114 bool show_reflectivity =
false;
3124 static bool display_in_mm =
false;
3125 if (!display_in_mm && meters > 0.
f && meters < 0.2
f)
3127 display_in_mm =
true;
3129 else if (display_in_mm && meters > 0.3
f)
3131 display_in_mm =
false;
3134 ss << std::dec <<
" = " << std::setprecision(3) << meters * 1000 <<
" millimeters";
3136 ss << std::dec <<
" = " << std::setprecision(3) << meters <<
" meters";
3139 ss << std::dec <<
" = " << std::setprecision(3) << meters /
FEET_TO_METER <<
" feet";
3151 show_max_range =
true;
3153 const float MIN_RANGE = 1.5f;
3154 const float MAX_RANGE = 9.0f;
3159 auto max_usable_range_rounded =
static_cast<int>(max_usable_range_limited / 1.5f) * 1.5
f;
3162 ss << std::dec <<
"\nMax usable range: " << std::setprecision(1) << max_usable_range_rounded <<
" meters";
3164 ss << std::dec <<
"\nMax usable range: " << std::setprecision(1) << max_usable_range_rounded /
FEET_TO_METER <<
" feet";
3186 bool lf_exist =
texture->get_last_frame();
3192 bool lf_exist =
texture->get_last_frame();
3209 auto new_line_start_idx = msg.find_first_of(
'\n');
3210 int footer_vertical_size = 35;
3211 auto width = float(msg.size() * 8);
3214 if (show_max_range || show_reflectivity)
3216 footer_vertical_size = 50;
3217 auto first_line_size = msg.find_first_of(
'\n') + 1;
3218 auto second_line_size = msg.substr(new_line_start_idx).size();
3219 width = std::max(first_line_size, second_line_size) * 8.0f;
3225 ImVec2 pos{ stream_rect.
x + 5, stream_rect.
y + stream_rect.
h - footer_vertical_size };
3271 ImVec2 pos{ stream_rect.
x, stream_rect.
y + y_offset };
3274 struct motion_data {
3284 float norm = std::sqrt((axis.
x*axis.
x) + (axis.
y*axis.
y) + (axis.
z*axis.
z));
3287 std::vector<motion_data> motion_vector = { {
"X", axis.
x, motion_unit[stream_type].c_str(),
"Vector X",
from_rgba(233, 0, 0, 255,
true) ,
from_rgba(233, 0, 0, 255,
true), 0},
3288 {
"Y", axis.
y, motion_unit[stream_type].c_str(),
"Vector Y",
from_rgba(0, 255, 0, 255,
true) ,
from_rgba(2, 100, 2, 255,
true), 0},
3289 {
"Z", axis.
z, motion_unit[stream_type].c_str(),
"Vector Z",
from_rgba(85, 89, 245, 255,
true) ,
from_rgba(0, 0, 245, 255,
true), 0},
3290 {
"N", norm,
"Norm",
"||V|| = SQRT(X^2 + Y^2 + Z^2)",
from_rgba(255, 255, 255, 255,
true) ,
from_rgba(255, 255, 255, 255,
true), 0} };
3293 for (
auto&& motion : motion_vector)
3341 ImVec2 pos{ stream_rect.
x, stream_rect.
y + y_offset };
3344 std::string confidenceName[4] = {
"Failed",
"Low",
"Medium",
"High" };
3354 bool showOnNonFullScreen;
3362 const float feetTranslator = 3.2808f;
3367 velocity.
x *= feetTranslator; velocity.
y *= feetTranslator; velocity.
z *= feetTranslator;
3368 acceleration.
x *= feetTranslator; acceleration.
y *= feetTranslator; acceleration.
z *= feetTranslator;
3369 translation.
x *= feetTranslator; translation.
y *= feetTranslator; translation.
z *= feetTranslator;
3372 std::vector<pose_data> pose_vector = {
3373 {
"Confidence",{ FLT_MAX , FLT_MAX , FLT_MAX , FLT_MAX }, confidenceName[pose_frame.
tracker_confidence], 3,
true,
"",
"Tracker confidence: High=Green, Medium=Yellow, Low=Red, Failed=Grey", 50,
false,
true,
false },
3374 {
"Velocity", {velocity.
x, velocity.
y , velocity.
z , FLT_MAX },
"", 3,
true,
"(" + unit +
"/Sec)",
"Velocity: X, Y, Z values of velocity, in " + unit +
"/Sec", 50,
false,
true,
false},
3375 {
"Angular Velocity",{ pose_frame.
angular_velocity.
x, pose_frame.
angular_velocity.
y , pose_frame.
angular_velocity.
z , FLT_MAX },
"", 3,
true,
"(Radians/Sec)",
"Angular Velocity: X, Y, Z values of angular velocity, in Radians/Sec", 50,
false,
true,
false },
3376 {
"Acceleration",{ acceleration.
x, acceleration.
y , acceleration.
z , FLT_MAX },
"", 3,
true,
"(" + unit +
"/Sec^2)",
"Acceleration: X, Y, Z values of acceleration, in " + unit +
"/Sec^2", 50,
false,
true,
false },
3377 {
"Angular Acceleration",{ pose_frame.
angular_acceleration.
x, pose_frame.
angular_acceleration.
y , pose_frame.
angular_acceleration.
z , FLT_MAX },
"", 3,
true,
"(Radians/Sec^2)",
"Angular Acceleration: X, Y, Z values of angular acceleration, in Radians/Sec^2", 50,
false,
true,
false },
3378 {
"Translation",{ translation.
x, translation.
y , translation.
z , FLT_MAX },
"", 3,
true,
"(" + unit +
")",
"Translation: X, Y, Z values of translation in " + unit +
" (relative to initial position)", 50,
true,
true,
false },
3379 {
"Rotation",{ pose_frame.
rotation.
x, pose_frame.
rotation.
y , pose_frame.
rotation.
z , pose_frame.
rotation.
w },
"", 3,
true,
"(Quaternion)",
"Rotation: Qi, Qj, Qk, Qr components of rotation as represented in quaternion rotation (relative to initial position)", 50,
true,
true,
false },
3388 for (
auto&&
pose : pose_vector)
3390 if ((fullScreen ==
false) && (
pose.showOnNonFullScreen ==
false))
3403 if (
pose.fixedColor ==
false)
3427 if (
pose.strData.empty())
3432 while ((i < 4) && (
pose.floatData[
i] != FLT_MAX))
3435 data +=
to_string() << std::fixed << std::setprecision(
pose.precision) << (
pose.signedNumber ? std::showpos : std::noshowpos) << comma <<
pose.floatData[i];
3443 data =
pose.strData;
3446 auto textSize =
ImGui::CalcTextSize((
char*)data.c_str(), (
char*)data.c_str() + data.size() + 1);
3451 if (
pose.fixedColor ==
false)
3456 if (
pose.fixedPlace ==
true)
3477 std::stringstream ss;
3482 auto loc = filename_base.find_last_of(
".");
3483 if (loc != std::string::npos)
3484 filename_base.erase(loc, std::string::npos);
3490 auto filename_png = filename_base +
"_" + stream_desc +
".png";
3491 save_to_png(filename_png.data(), colorized_frame.get_width(), colorized_frame.get_height(), colorized_frame.get_bytes_per_pixel(),
3492 colorized_frame.get_data(), colorized_frame.get_width() * colorized_frame.get_bytes_per_pixel());
3494 ss <<
"PNG snapshot was saved to " << filename_png << std::endl;
3506 auto filename = filename_base +
"_" + stream_desc +
".raw";
3508 ss <<
"Raw data is captured into " << filename << std::endl;
3514 filename = filename_base +
"_" + stream_desc +
"_metadata.csv";
3519 ss <<
"The frame attributes are saved into " << filename;
3524 catch (std::exception&
e)
3537 auto filename = filename_base +
"_" + stream_desc +
".csv";
3542 ss <<
"The frame attributes are saved into\n" << filename;
3549 catch( std::exception &
e )
3563 auto filename = filename_base +
"_" + stream_desc +
".csv";
3568 ss <<
"The frame attributes are saved into\n" << filename;
3575 catch( std::exception &
e )
3582 if (ss.str().size())
3584 ss.str().c_str(), RS2_LOG_SEVERITY_INFO, RS2_NOTIFICATION_CATEGORY_HARDWARE_EVENT });
3590 rect zoomed_rect =
dev->normalized_zoom.unnormalize(stream_rect);
3593 if (!is_middle_clicked)
3599 .
fit({ 0, 0, 40, 40 })
3600 .enclose_in(zoomed_rect)
3603 else if (zoom_val > 1.
f)
3605 zoomed_rect = zoomed_rect.
zoom(zoom_val).
enclose_in(stream_rect);
3612 if (
dir.length() > 0)
3617 dev->normalized_zoom = zoomed_rect.
normalize(stream_rect);
3619 return dev->normalized_zoom;
3624 auto zoom_val = 1.f;
3627 static const auto wheel_step = 0.1f;
3629 if (mouse_wheel_value > 0)
3630 zoom_val += wheel_step;
3631 else if (mouse_wheel_value < 0)
3632 zoom_val -= wheel_step;
3644 g, is_middle_clicked,
3648 if (
dev &&
dev->show_algo_roi)
3650 rect r{ float(
dev->algo_roi.min_x), float(
dev->algo_roi.min_y),
3651 float(
dev->algo_roi.max_x -
dev->algo_roi.min_x),
3652 float(
dev->algo_roi.max_y -
dev->algo_roi.min_y) };
3660 if (msg_width <
r.w)
3661 draw_text(static_cast<int>(
r.x +
r.w / 2 - msg_width / 2), static_cast<int>(
r.y + 10), message.c_str());
3671 if (is_middle_clicked)
3677 syncer->remove_syncer(dev_syncer);
3678 subdevices.resize(0);
3691 std::stringstream
s;
3697 s <<
"Playback device: ";
3698 name += (
to_string() <<
" (File: " << playback_dev.file_name() <<
")");
3701 return std::make_pair(s.str(), serial);
3706 for (
auto&&
n : related_notifications)
n->dismiss(
false);
3708 _updates->set_device_status(*_updates_profile,
false);
3730 std::shared_ptr< firmware_update_manager > manager =
nullptr;
3734 recommended = available;
3738 manager = std::make_shared< firmware_update_manager >( not_model,
3749 std::stringstream msg;
3750 msg << dev_name.first <<
" (S/N " << dev_name.second <<
")\n" 3751 <<
"Current Version: " << fw <<
"\n";
3754 msg <<
"Release Candidate: " << recommended <<
" Pre-Release";
3756 msg <<
"Recommended Version: " << recommended;
3758 auto n = std::make_shared< fw_update_notification_model >( msg.str(),
3761 n->delay_id =
"dfu." + dev_name.second;
3762 n->enable_complex_dismiss =
true;
3763 if( !
n->is_delayed() )
3765 not_model->add_notification(
n );
3766 related_notifications.push_back(
n );
3774 for (
auto&&
n : related_notifications)
n->dismiss(
false);
3780 check_for_device_updates(viewer);
3784 for (
auto&&
model : subdevices)
3786 if (
model->supports_on_chip_calib())
3795 << name.first <<
" (S/N " << name.second <<
")";
3796 auto manager = std::make_shared<on_chip_calib_manager>(viewer,
model, *
this,
dev);
3797 auto n = std::make_shared<autocalib_notification_model>(
3798 msg, manager,
false);
3801 if (rawtime - last_time < 60)
3819 _update_readonly_options_timer(
std::
chrono::seconds(6)),
3821 _updates(viewer.updates),
3823 _allow_remove(remove)
3832 id =
to_string() << name.first <<
", " << name.second;
3836 auto s = std::make_shared<sensor>(sub);
3837 auto objects = std::make_shared< atomic_objects_in_frame >();
3841 auto model = std::make_shared<subdevice_model>(
dev, std::make_shared<sensor>(sub), objects, error_message, viewer, new_device_connected);
3870 for (
auto&&
p : sub->profiles)
3872 sub->stream_enabled[
p.unique_id()] =
true;
3886 if (!sub->streaming)
3888 std::vector<rs2::stream_profile>
profiles;
3891 profiles = sub->get_selected_profiles();
3898 if (profiles.empty())
3902 if ((friendly_name.find(
"Tracking") != std::string::npos) ||
3903 (friendly_name.find(
"Motion") != std::string::npos))
3910 for (
auto&&
profile : profiles)
3920 std::vector<rs2::frame>
frames;
3923 for (
auto&& f : composite)
3924 frames.push_back(f);
3927 frames.push_back(f);
3933 std::set<std::shared_ptr<subdevice_model>>
subdevices;
3934 for (
auto f : frames)
3936 auto sub = get_frame_origin(f);
3938 subdevices.insert(sub);
3941 for (
auto sub : subdevices)
3943 if (!sub->post_processing_enabled)
3946 for (
auto&& pp : sub->post_processing)
3947 if (pp->is_enabled())
3956 for (
auto&&
s : viewer.streams)
3960 auto dev =
s.second.dev;
3976 switch (stream_type)
3981 memset(rgb_stream, 0, 3);
3990 memset(ir_stream, 0, 2);
4004 map_id_frameset_to_frameset(new_set, old_set);
4008 map_id_frameset_to_frame(new_set, old_frame);
4013 map_id_frameset_to_frame(old_set, new_frame);
4016 map_id_frame_to_frame(new_frame, old_frame);
4023 auto first_uid =
f.get_profile().unique_id();
4026 viewer.streams_origin[first_uid] = second_uid;
4027 viewer.streams_origin[second_uid] = first_uid;
4033 for (
auto&&
f : first)
4035 auto first_uid =
f.get_profile().unique_id();
4038 auto second_uid = second_f.get_profile().unique_id();
4040 viewer.streams_origin[first_uid] = second_uid;
4041 viewer.streams_origin[second_uid] = first_uid;
4053 viewer.streams_origin[first_uid] = second_uid;
4054 viewer.streams_origin[second_uid] = first_uid;
4061 std::vector<rs2::frame>
res;
4063 if (uploader) f = uploader->process(f);
4065 auto filtered = apply_filters(f, source);
4067 map_id(filtered, f);
4071 for (
auto&&
frame : composite)
4073 res.push_back(
frame);
4077 res.push_back(filtered);
4079 if (viewer.is_3d_view)
4081 if (
auto depth = viewer.get_3d_depth_source(filtered))
4083 switch (
depth.get_profile().format())
4091 viewer.occlusion_invalidation ? 2.f : 1.f);
4092 res.push_back(
pc->calculate(
depth));
4094 if (
auto texture = viewer.get_3d_texture_source(filtered))
4107 std::vector<frame> results;
4109 auto res = handle_frame(f, source);
4119 if (render_thread_active.exchange(
true) ==
false)
4121 viewer.syncer->start();
4128 if (render_thread_active.exchange(
false) ==
true)
4130 viewer.syncer->stop();
4131 render_thread->join();
4132 render_thread.reset();
4137 while (render_thread_active)
4141 if (viewer.synchronization_enable)
4143 auto frames = viewer.syncer->try_wait_for_frames();
4151 std::map<int, rs2::frame_queue> frames_queue_local;
4153 std::lock_guard<std::mutex>
lock(viewer.streams_mutex);
4154 frames_queue_local = frames_queue;
4156 for (
auto&&
q : frames_queue_local)
4159 if (
q.second.try_wait_for_frame(&frm, 30))
4180 if (compression_mode == 2)
4187 sub_dev_model->_is_being_recorded =
true;
4195 catch (
const std::exception& e)
4197 error_message = e.what();
4203 auto saved_to_filename =
_recorder->filename();
4207 sub_dev_model->_is_being_recorded =
false;
4231 const int playback_control_height = 35;
4232 const float combo_box_width = 90.f;
4233 const float icon_width = 28;
4234 const float line_width = 255;
4236 const int num_icons_in_line = 6;
4237 const int num_combo_boxes_in_line = 1;
4238 const int num_spaces_in_line = num_icons_in_line + num_combo_boxes_in_line + 1;
4239 const float required_row_width = (num_combo_boxes_in_line * combo_box_width) + (num_icons_in_line * icon_width);
4240 float space_width = std::max(line_width - required_row_width, 0.
f) / num_spaces_in_line;
4241 ImVec2 button_dim = { icon_width, icon_width };
4255 if (
s.second.profile.fps() >
fps)
4256 fps =
s.second.profile.fps();
4258 auto curr_frame =
p.get_position();
4260 if (curr_frame >= step)
4267 std::string tooltip =
to_string() <<
"Step Backwards" << (supports_playback_step ?
"" :
"(Not available)");
4308 syncer->on_frame = [] {};
4311 s->on_frame = [] {};
4358 if (
s.second.profile.fps() >
fps)
4359 fps =
s.second.profile.fps();
4361 auto curr_frame =
p.get_position();
4367 std::string tooltip =
to_string() <<
"Step Forward" << (supports_playback_step ?
"" :
"(Not available)");
4405 const float speed_combo_box_v_alignment = 3.f;
4418 case 0: speed = 0.25f;
break;
4419 case 1: speed = 0.5f;
break;
4420 case 2: speed = 1.0f;
break;
4421 case 3: speed = 1.5f;
break;
4422 case 4: speed = 2.0f;
break;
4426 p.set_playback_speed(speed);
4446 return playback_control_height;
4452 auto hhh = duration_cast<hours>(duration);
4454 auto mm = duration_cast<minutes>(duration);
4456 auto ss = duration_cast<seconds>(duration);
4458 auto ms = duration_cast<milliseconds>(duration);
4460 std::ostringstream
stream;
4461 stream << std::setfill(
'0') << std::setw(hhh.count() >= 10 ? 2 : 1) << hhh.count() <<
':' <<
4462 std::setfill(
'0') << std::setw(2) << mm.count() <<
':' <<
4463 std::setfill(
'0') << std::setw(2) << ss.count() <<
'.' <<
4464 std::setfill(
'0') << std::setw(3) << ms.count();
4465 return stream.str();
4476 double part = (1.0 *
progress) / playback_total_duration;
4478 auto playback_status =
p.current_status();
4483 float seek_bar_width = 300.f;
4491 auto duration_db = std::chrono::duration_cast<std::chrono::duration<double, std::nano>>(
p.get_duration());
4492 auto single_percent = duration_db.count() / 100;
4493 auto seek_time = std::chrono::duration<double, std::nano>(
seek_pos * single_percent);
4494 p.seek(std::chrono::duration_cast<std::chrono::nanoseconds>(seek_time));
4523 float seek_bar_left_alignment = 4.f;
4529 return controls_height + seek_bar_height;
4535 std::vector<std::string>
res;
4545 && !include_location)
continue;
4550 res.push_back(
value);
4558 std::vector<std::pair<std::string, std::string>> device_names;
4569 device_names.push_back(std::pair<std::string, std::string>(
to_string() <<
"Unknown Device #" <<
i,
""));
4572 return device_names;
4586 auto clicked =
false;
4661 auto close_clicked =
false;
4684 auto future_window_width = std::max(process_status_text_size, window_width);
4687 ImGui::Text(
"Status: %s", process_status_text.c_str());
4697 close_clicked =
true;
4703 return close_clicked;
4708 bool keep_showing =
true;
4709 bool yes_was_chosen =
false;
4710 if (
yes_no_dialog(
"Advanced Mode", message_text, yes_was_chosen, window, error_message))
4716 view.
not_model->add_log(enable_advanced_mode ?
"Turning on advanced mode..." :
"Turning off advanced mode...");
4718 keep_showing =
false;
4720 return keep_showing;
4726 bool was_set =
false;
4736 if (advanced.is_enabled())
4744 static bool show_yes_no_modal =
false;
4747 show_yes_no_modal =
true;
4751 ImGui::SetTooltip(
"Advanced mode is a persistent camera state unlocking calibration formats and depth generation controls\nYou can always reset the camera to factory defaults by disabling advanced mode");
4753 if (show_yes_no_modal)
4759 catch (
const std::exception& ex)
4761 error_message = ex.what();
4793 std::vector<uint8_t>
data;
4800 data = std::vector<uint8_t>((std::istreambuf_iterator<char>(file)),
4801 std::istreambuf_iterator<char>());
4805 error_message =
to_string() <<
"Could not open file '" << ret <<
"'";
4812 auto manager = std::make_shared<firmware_update_manager>(viewer.
not_model, *
this,
dev, viewer.
ctx,
data,
false);
4814 auto n = std::make_shared<fw_update_notification_model>(
4815 "Manual Update requested", manager,
true);
4819 if (dynamic_cast<fw_update_notification_model*>(n.get()))
4822 auto invoke = [
n](std::function<void()>
action) {
4825 manager->start(invoke);
4831 catch (
const std::exception& e)
4833 error_message = e.what();
4841 if (data.size() == 0)
4849 data = std::vector<uint8_t>((std::istreambuf_iterator<char>(file)),
4850 std::istreambuf_iterator<char>());
4854 error_message =
to_string() <<
"Could not open file '" << ret <<
"'";
4861 auto manager = std::make_shared<firmware_update_manager>(viewer.
not_model, *
this,
dev, viewer.
ctx,
data,
true);
4863 auto n = std::make_shared<fw_update_notification_model>(
4864 "Manual Update requested", manager,
true);
4870 auto invoke = [
n](std::function<void()>
action) {
4874 manager->start(invoke);
4880 catch (
const std::exception& e)
4882 error_message = e.what();
4887 std::weak_ptr< updates_model > updates_model_protected( viewer.
updates );
4888 std::weak_ptr< dev_updates_profile::update_profile > update_profile_protected(
4890 std::weak_ptr< notifications_model > notification_model_protected( viewer.
not_model );
4892 std::thread check_for_device_updates_thread( [ctx,
4893 updates_model_protected,
4894 notification_model_protected,
4896 update_profile_protected]() {
4899 bool need_to_check_bundle =
true;
4902 bool use_local_file =
false;
4907 if( server_url.find( local_file_prefix ) == 0 )
4909 use_local_file =
true;
4910 server_url.erase( 0, local_file_prefix.length() );
4917 if (sw_online_update_available || fw_online_update_available)
4919 if (
auto update_profile = update_profile_protected.lock())
4930 if (
auto viewer_updates = updates_model_protected.lock())
4932 viewer_updates->add_profile(updates_profile_model);
4933 need_to_check_bundle =
false;
4938 if (
auto viewer_updates = updates_model_protected.lock())
4941 if (viewer_updates->has_updates())
4943 need_to_check_bundle =
false;
4947 if (sw_online_update_available)
4949 if (
auto nm = notification_model_protected.lock())
4954 if (fw_online_update_available)
4956 if (
auto nm = notification_model_protected.lock())
4964 if (
auto viewer_updates = updates_model_protected.lock())
4966 viewer_updates->update_profile(updates_profile_model);
4971 else if(
auto nm = notification_model_protected.lock() )
4973 nm->add_log(
"No online SW / FW updates available" );
4977 if( need_to_check_bundle
4980 if(
auto nm = notification_model_protected.lock() )
4986 catch(
const std::exception &
e )
4988 auto error = e.what();
4992 check_for_device_updates_thread.detach();
5026 const float device_panel_height = 60.0f;
5044 return sm->streaming;
5047 const float icons_width = 78.0f;
5048 const ImVec2 device_panel_icons_size{ icons_width, 25 };
5064 if (!
ends_with(default_path,
"/") && !
ends_with(default_path,
"\\")) default_path +=
"/";
5066 if (recording_setting == 0 && default_path.size() > 1 )
5068 path = default_path + default_filename;
5073 default_path.c_str(), default_filename.c_str()))
5085 std::string record_button_hover_text = (!is_streaming ?
"Start streaming to enable recording" : (
is_recording ?
"Stop Recording" :
"Start Recording"));
5096 bool is_sync_enabled =
false;
5102 is_sync_enabled = !is_sync_enabled;
5106 ImGui::SetTooltip(
"%s", is_sync_enabled ?
"Disable streams synchronization" :
"Enable streams synchronization");
5121 if (
ImGui::Button(bars_button_name.c_str(), device_panel_icons_size))
5132 static bool keep_showing_advanced_mode_modal =
false;
5133 bool open_calibration_ui =
false;
5137 bool something_to_show =
false;
5141 something_to_show =
true;
5148 tm2_extensions.enable_loopback(ret);
5151 if (tm2_extensions.is_loopback_enabled() &&
ImGui::Selectable(
"Disable loopback...",
false, is_streaming ? ImGuiSelectableFlags_Disabled : 0))
5153 tm2_extensions.disable_loopback();
5160 ImGui::SetTooltip(
"Enter the device to loopback mode (inject frames from file to FW)");
5171 std::stringstream ss;
5172 ss <<
"Exporting localization map to " << target_path <<
" ... ";
5187 if (
ImGui::Selectable(
"Import Localization map",
false, is_streaming ? ImGuiSelectableFlags_Disabled : 0))
5193 std::stringstream ss;
5194 ss <<
"Importing localization map from " << source_path <<
" ... ";
5215 catch (
const std::exception& e)
5217 error_message = e.what();
5223 something_to_show =
true;
5227 const bool is_advanced_mode_enabled = adv.is_enabled();
5228 bool selected = is_advanced_mode_enabled;
5231 keep_showing_advanced_mode_modal =
true;
5248 catch (
const std::exception& e)
5250 error_message = e.what();
5265 std::string tooltip =
to_string() <<
"Install official signed firmware from file to the device" << (is_streaming ?
" (Disabled while streaming)" :
"");
5280 n->dismiss(
false );
5294 bool is_locked =
true;
5301 bool is_l500_device =
false;
5308 if( ! is_l500_device )
5316 std::string tooltip =
to_string() <<
"Install non official unsigned firmware from file to the device" << (is_streaming ?
" (Disabled while streaming)" :
"");
5323 bool has_autocalib =
false;
5326 if (sub->supports_on_chip_calib() && !has_autocalib)
5328 something_to_show =
true;
5333 auto manager = std::make_shared<on_chip_calib_manager>(viewer, sub, *
this,
dev);
5334 auto n = std::make_shared<autocalib_notification_model>(
"", manager,
false);
5336 viewer.not_model->add_notification(n);
5341 if (dynamic_cast<autocalib_notification_model*>(n.get()))
5344 related_notifications.push_back(n);
5350 catch (
const std::exception& e)
5352 error_message = e.what();
5357 "Point at a scene that normally would have > 50 %% valid depth pixels,\n" 5358 "then press calibrate." 5359 "The health-check will be calculated.\n" 5360 "If >0.25 we recommend applying the new calibration.\n" 5361 "\"White wall\" mode should only be used when pointing at a flat white wall with projector on");
5367 auto manager = std::make_shared<on_chip_calib_manager>(viewer, sub, *
this,
dev);
5368 auto n = std::make_shared<autocalib_notification_model>(
5369 "", manager,
false);
5371 viewer.not_model->add_notification(n);
5376 if (dynamic_cast<autocalib_notification_model*>(n.get()))
5379 related_notifications.push_back(n);
5385 catch (
const std::exception& e)
5387 error_message = e.what();
5391 ImGui::SetTooltip(
"Tare calibration is used to adjust camera absolute distance to flat target.\n" 5392 "User needs either to enter the known ground truth or use the get button\n" 5393 "with specific target to get the ground truth.");
5411 bool has_parser =
false;
5413 std::ifstream
f(hwlogger_xml.c_str());
5419 std::istreambuf_iterator<char>());
5420 fwlogger.init_parser(str);
5423 catch (
const std::exception& ex)
5426 to_string() <<
"Invalid Hardware Logger XML at '" << hwlogger_xml <<
"': " << ex.what() <<
"\nEither configure valid XML or remove it");
5430 auto message = fwlogger.create_message();
5432 while (fwlogger.get_flash_log(
message))
5434 auto parsed = fwlogger.create_parsed_message();
5435 auto parsed_ok =
false;
5439 if (fwlogger.parse_log(
message, parsed))
5444 parsed.file_name(), parsed.line(),
to_string()
5445 <<
"FW-LOG [" << parsed.thread_name() <<
"] " << parsed.message());
5451 std::stringstream ss;
5452 for (
auto& elem :
message.data())
5453 ss << std::setfill(
'0') << std::setw(2) << std::hex << static_cast<int>(elem) <<
" ";
5454 viewer.
not_model->output.add_log(
message.get_severity(), __FILE__, 0, ss.str());
5458 catch(
const std::exception& ex)
5461 to_string() <<
"Failed to fetch firmware logs: " << ex.what());
5465 ImGui::SetTooltip(
"Recovers last set of firmware logs prior to camera shutdown / disconnect");
5468 has_autocalib =
true;
5473 bool selected =
false;
5474 something_to_show =
true;
5479 if (!something_to_show)
5481 ImGui::Text(
"This device has no additional options");
5507 if (keep_showing_advanced_mode_modal)
5510 std::string msg =
to_string() <<
"\t\tAre you sure you want to " << (is_advanced_mode_enabled ?
"turn off Advanced mode" :
"turn on Advanced mode") <<
"\t\t";
5526 const ImVec2 device_panel_icons_text_size = { icons_width, 5 };
5551 return device_panel_height;
5559 bool video_profile_saved =
false;
5560 for (
auto&&
p : sub->get_selected_profiles())
5568 stream_format_key =
"stream-depth-format";
5572 stream_format_key =
"stream-ir-format";
5576 stream_format_value =
"R8L8";
5584 j[stream_format_key] = stream_format_value;
5585 if (!video_profile_saved)
5592 video_profile_saved =
true;
5603 auto n = std::make_shared< sw_recommended_update_alert_model >(
5605 recommended_sw_update_info.
ver,
5608 n->delay_id =
"update_alert." + name.second;
5609 n->enable_complex_dismiss =
true;
5611 if (!
n->is_delayed())
5613 nm->add_notification(
n);
5620 bool fw_update_notification_raised =
false;
5621 std::shared_ptr< firmware_update_manager > manager =
nullptr;
5623 std::vector< uint8_t > fw_data;
5627 int download_retries = 3;
5631 while (download_retries > 0)
5636 download_retries = 0;
5643 if (!fw_data.empty())
5645 manager = std::make_shared< firmware_update_manager >(nm,
5653 std::stringstream msg;
5654 msg << dev_name.first <<
" (S/N " << dev_name.second <<
")\n" 5655 <<
"Current Version: " 5656 <<
std::string(update_profile->firmware_version) <<
"\n";
5658 msg <<
"Recommended Version: " 5661 auto n = std::make_shared< fw_update_notification_model >(
5665 n->delay_id =
"dfu." + dev_name.second;
5666 n->enable_complex_dismiss =
true;
5667 if (!
n->is_delayed())
5669 nm->add_notification(
n);
5671 fw_update_notification_raised =
true;
5680 <<
"Error in downloading FW binary file: " 5683 return fw_update_notification_raised;
5698 std::map<std::pair<rs2_stream, int>, video_stream> requested_streams;
5699 auto it = j.
find(
"stream-depth-format");
5709 if (formatstr == fstr)
5718 throw std::runtime_error(
to_string() <<
"Unsupported stream-depth-format: " << formatstr);
5724 for (
auto&&
profile : sub->profiles)
5728 sub->stream_enabled[
profile.unique_id()] =
false;
5735 it = j.
find(
"stream-ir-format");
5754 if (formatstr ==
"R8L8")
5761 throw std::runtime_error(
to_string() <<
"Unsupported stream-ir-format: " << formatstr);
5768 for (
auto&&
profile : sub->profiles)
5772 sub->stream_enabled[
profile.unique_id()] =
false;
5780 if (!requested_streams.empty())
5790 for (
auto&
kvp : requested_streams)
5797 catch (
const std::exception&
e)
5799 throw std::runtime_error(
to_string() <<
"Error parsing streams from JSON: " << e.what());
5804 for (
auto&&
kvp : requested_streams)
5809 auto itr = std::find_if(sub->stream_display_names.begin(), sub->stream_display_names.end(), [stream_name](
const std::pair<int, std::string>&
p) {
return p.second == stream_name; });
5810 if (itr != sub->stream_display_names.end())
5812 int uid = itr->first;
5813 sub->stream_enabled[
uid] =
true;
5816 size_t format_id = 0;
5818 for (; format_id < sub->format_values[
uid].size(); format_id++)
5820 if (sub->format_values[uid][format_id] == requested_format)
5823 if (format_id == sub->format_values[uid].size())
5825 throw std::runtime_error(
to_string() <<
"No match found for requested format: " << requested_format);
5827 sub->ui.selected_format_id[
uid] = int(format_id);
5830 int requested_fps =
kvp.second.fps;
5832 for (; fps_id < sub->shared_fps_values.size(); fps_id++)
5834 if (sub->shared_fps_values[fps_id] == requested_fps)
5837 if (fps_id == sub->shared_fps_values.size())
5839 throw std::runtime_error(
to_string() <<
"No match found for requested fps: " << requested_fps);
5841 sub->ui.selected_shared_fps_id = int(fps_id);
5844 std::pair<int, int> requested_res{
kvp.second.width,
kvp.second.height };
5846 for (; res_id < sub->res_values.size(); res_id++)
5848 if (sub->res_values[res_id] == requested_res)
5851 if (res_id == sub->res_values.size())
5853 throw std::runtime_error(
to_string() <<
"No match found for requested resolution: " << requested_res.first <<
"x" << requested_res.second);
5855 sub->ui.selected_res_id = int(res_id);
5865 bool update_read_only_options,
5866 bool load_json_if_streaming,
5869 const float panel_height = 40.f;
5882 const auto load_json = [&, serializable](
const std::string f) {
5883 std::ifstream file(
f);
5889 throw std::runtime_error(
to_string() <<
"Failed to read configuration file:\n\"" <<
f <<
"\"\nRemoving it from presets.");
5891 std::string str((std::istreambuf_iterator<char>(file)), std::istreambuf_iterator<char>());
5895 serializable.load_json(str);
5903 if (itr != sub->options_metadata.end())
5918 const auto save_to_json = [&, serializable](
std::string full_filename)
5921 std::ofstream
outfile(full_filename);
5922 json saved_configuraion;
5925 saved_configuraion =
json::parse(serializable.serialize_json());
5928 outfile << saved_configuraion.
dump(4);
5932 viewer.
not_model->add_log(
to_string() <<
"Saved settings to \"" << full_filename <<
"\"...");
5935 static const std::string popup_message =
"\t\tTo use this feature, the device must be in Advanced Mode.\t\t\n\n\t\tWould you like to turn Advanced Mode?\t\t";
5947 bool is_clicked =
false;
5960 std::vector<const char*> labels;
5962 auto selected = 0,
counter = 0;
5972 if (std::fabs(
i - opt_model.
value) < 0.001f)
5976 labels.push_back(opt_model.
endpoint->get_option_value_description(opt_model.
opt,
i));
5977 counters.push_back(
i );
5991 std::vector<std::string> files_labels;
5992 int i =
static_cast<int>(labels.size());
5993 for (
auto&& file : full_files_names)
6002 std::transform(files_labels.begin(), files_labels.end(), std::back_inserter(labels), [](
const std::string&
s) {
return s.c_str(); });
6006 static bool keep_showing_popup =
false;
6008 static_cast<int>(labels.size())))
6014 if (!advanced.is_enabled())
6015 keep_showing_popup =
true;
6017 if (!keep_showing_popup)
6019 if (selected < static_cast<int>(labels.size() - files_labels.size()))
6022 auto new_val = counters[selected];
6024 << new_val <<
" (" << labels[selected] <<
")");
6026 opt_model.
set_option(opt_model.
opt, new_val, error_message);
6035 auto file = selected -
static_cast<int>(labels.size() - files_labels.size());
6036 if (file < 0 || file >= full_files_names.size())
6037 throw std::runtime_error(
"not a valid format");
6038 auto f = full_files_names[file];
6039 error_message =
safe_call([&]() { load_json(
f); });
6044 if (keep_showing_popup)
6067 const ImVec2 icons_size{ 20, 20 };
6069 bool is_streaming = std::any_of(subdevices.begin(), subdevices.end(), [](
const std::shared_ptr<subdevice_model>& sm) {
return sm->streaming; });
6071 static bool require_advanced_mode_enable_prompt =
false;
6073 auto is_advanced_device =
false;
6074 auto is_advanced_mode_enabled =
false;
6077 is_advanced_device =
true;
6081 is_advanced_mode_enabled = advanced_dev.
is_enabled();
6097 if (serializable && (!is_advanced_device || is_advanced_mode_enabled))
6101 for(
auto && sub : subdevices )
6105 sub->_options_invalidated = true;
6111 error_message =
safe_call([&]() { load_json(ret); });
6117 require_advanced_mode_enable_prompt =
true;
6123 std::string tooltip =
to_string() <<
"Load pre-configured stereo module settings" << (is_streaming && !load_json_if_streaming ?
" (Disabled while streaming)" :
"");
6134 if (
ImGui::ButtonEx(save_button_name.c_str(), icons_size, buttons_flags))
6136 if (serializable && (!is_advanced_device || is_advanced_mode_enabled))
6141 error_message =
safe_call([&]() { save_to_json(ret); });
6146 require_advanced_mode_enable_prompt =
true;
6157 if (require_advanced_mode_enable_prompt)
6166 return panel_height;
6177 while ((
end = fw_version.find(delimiter,
start)) != std::string::npos)
6180 start =
start + substr.length() + delimiter.length();
6181 values.push_back(atoi(substr.c_str()));
6183 values.push_back(atoi(fw_version.substr(
start, fw_version.length() -
start).c_str()));
6192 for (
size_t i = 0;
i < curr_values.size();
i++)
6194 if (
i >= min_values.size())
6198 if (curr_values[
i] < min_values[
i])
6202 if (curr_values[i] > min_values[i])
6212 return std::any_of(
subdevices.begin(),
subdevices.end(), [](
const std::shared_ptr<subdevice_model>& sm)
6214 return sm->streaming;
6223 std::vector<std::function<
void()>>& draw_later,
6224 bool load_json_if_streaming,
6226 bool draw_device_outline)
6233 auto header_h = panel_height;
6234 if (is_playback_device || is_ip_device) header_h += 15;
6237 const float left_space = 3.f;
6238 const float upper_space = 3.f;
6245 if (draw_device_outline)
6251 ImGui::GetWindowDrawList()->
AddRectFilled({ initial_screen_pos.
x + 1,initial_screen_pos.
y + upper_space + 1 }, { initial_screen_pos.
x + panel_width, initial_screen_pos.
y + header_h + upper_space }, device_header_background_color);
6263 std::stringstream ss;
6268 ImGui::Text(
" %s", ss.str().substr(0, ss.str().find(
"\n IP Device")).c_str());
6289 ss <<
"The camera was detected by the OS as connected to a USB " << desc <<
" port";
6314 float horizontal_distance_from_right_side_of_panel = 47;
6315 ImGui::SetCursorPos({ panel_width - horizontal_distance_from_right_side_of_panel,
pos.y + 9 + (header_h - panel_height) / 2 });
6317 if (
ImGui::Button(remove_source_button_label.c_str(), { 33,35 }))
6324 device_to_remove =
this;
6329 ImGui::SetTooltip(
"Remove selected device from current view\n(can be restored by clicking Add Source)");
6344 auto full_path =
p.file_name();
6357 if (!is_playback_device)
6360 const float vertical_space_before_device_control = 10.0f;
6361 const float horizontal_space_before_device_control = 3.0f;
6362 auto device_panel_pos =
ImVec2{
pos.
x + horizontal_space_before_device_control,
pos.y + vertical_space_before_device_control };
6364 const float device_panel_height =
draw_device_panel(panel_width, window, error_message, viewer);
6375 const float vertical_space_before_advanced_mode_control = 10.0f;
6376 const float horizontal_space_before_device_control = 3.0f;
6377 auto advanced_mode_pos =
ImVec2{
pos.
x + horizontal_space_before_device_control,
pos.y + vertical_space_before_advanced_mode_control };
6379 const float advanced_mode_panel_height =
draw_preset_panel(panel_width, window, error_message, viewer, update_read_only_options, load_json_if_streaming, json_loading);
6380 ImGui::SetCursorPos({ advanced_mode_pos.x, advanced_mode_pos.y + advanced_mode_panel_height });
6389 float space_before_playback_control = 18.0f;
6390 auto playback_panel_pos =
ImVec2{
pos.
x + 10,
pos.y + space_before_playback_control };
6393 ImGui::SetCursorPos({ playback_panel_pos.x, playback_panel_pos.y + playback_panel_height });
6398 return sm->streaming;
6407 int info_control_panel_height = 0;
6412 info_control_panel_height = (int)
infos.size() * line_h + 5;
6413 for (
auto&& pair :
infos)
6418 if (pair.first ==
"Recommended Firmware Version")
6420 info_category =
"Min FW Version";
6421 min_fw_version = pair.second;
6425 info_category = pair.first.c_str();
6434 if (pair.first ==
"Firmware Version")
6436 fw_version = pair.second;
6440 (
char*)pair.second.data(),
6441 pair.second.size() + 1,
6443 if (pair.first ==
"Firmware Version")
6477 draw_later.push_back([&error_message, windows_width, &window, sub, pos, &viewer,
this]()
6488 if (!sub->streaming)
6495 std::vector<stream_profile>
profiles;
6496 auto is_comb_supported = sub->is_selected_combination_supported();
6497 bool can_stream =
false;
6498 if (is_comb_supported)
6502 profiles = sub->get_supported_profiles();
6503 if (!profiles.empty())
6509 if (std::any_of(sub->stream_enabled.begin(), sub->stream_enabled.end(), [](std::pair<int, bool>
const&
s) {
return s.second; }))
6530 if (profiles.empty())
6531 profiles = sub->get_selected_profiles();
6539 ((friendly_name.find(
"Tracking") != std::string::npos) ||
6540 (friendly_name.find(
"Motion") != std::string::npos)))
6552 catch (
const std::exception& e)
6554 error_message = e.what();
6557 for (
auto&&
profile : profiles)
6579 if ((friendly_name.find(
"Tracking") != std::string::npos) ||
6580 (friendly_name.find(
"Motion") != std::string::npos))
6585 if (!std::any_of(subdevices.begin(), subdevices.end(),
6586 [](
const std::shared_ptr<subdevice_model>& sm)
6588 return sm->streaming;
6591 stop_recording =
true;
6605 for (
auto&& sub : subdevices)
6608 if (sub->is_selected_combination_supported())
6610 auto profiles = sub->get_selected_profiles();
6639 sub->draw_stream_selection(error_message);
6641 static const std::vector<rs2_option> drawing_order = serialize ?
6645 for (
auto& opt : drawing_order)
6647 if (sub->draw_option(opt,
dev.
is<
playback>() || update_read_only_options, error_message, *viewer.
not_model))
6654 if (sub->num_supported_non_default_options())
6659 std::vector<rs2_option> supported_options = sub->s->get_supported_options();
6662 std::vector<rs2_option> color_options = {
6674 std::vector<rs2_option> so_ordered;
6676 for (
auto&&
i : supported_options)
6678 auto it =
find(color_options.begin(), color_options.end(),
i);
6679 if (
it == color_options.end())
6680 so_ordered.push_back(
i);
6683 std::for_each(color_options.begin(), color_options.end(), [&](
rs2_option opt) {
6684 auto it =
std::find(supported_options.begin(), supported_options.end(), opt);
6685 if (
it != supported_options.end())
6686 so_ordered.push_back(opt);
6689 for (
auto&&
i : so_ordered)
6693 if (
std::find(drawing_order.begin(), drawing_order.end(), opt) == drawing_order.end())
6698 if (sub->draw_option(opt,
dev.
is<
playback>() || update_read_only_options, error_message, *viewer.
not_model))
6713 sub->_options_invalidated =
true;
6719 for (
auto&& pb : sub->const_effects)
6723 label =
to_string() << pb->get_name() <<
"##" <<
id;
6730 pb->get_option(opt).draw_option(
6732 false, error_message, *viewer.
not_model);
6749 if (sub->post_processing.size() > 0)
6754 draw_later.push_back([windows_width, &window, sub, pos, &viewer,
this]() {
6761 ImGui::PushFont(window.get_font());
6763 ImGui::PushStyleColor(ImGuiCol_Button, sensor_bg);
6764 ImGui::PushStyleColor(ImGuiCol_ButtonHovered, sensor_bg);
6765 ImGui::PushStyleColor(ImGuiCol_ButtonActive, sensor_bg);
6767 if (!sub->post_processing_enabled)
6769 std::string label = to_string() <<
" " << textual_icons::toggle_off <<
"##" << id <<
"," << sub->s->get_info(RS2_CAMERA_INFO_NAME) <<
",post";
6771 ImGui::PushStyleColor(ImGuiCol_Text, redish);
6772 ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, redish + 0.1f);
6774 if (ImGui::Button(label.c_str(), { 30,24 }))
6776 if (sub->zero_order_artifact_fix && sub->zero_order_artifact_fix->is_enabled())
6777 sub->verify_zero_order_conditions();
6778 sub->post_processing_enabled = true;
6779 config_file::instance().set(get_device_sensor_name(sub.get()).c_str(),
6780 sub->post_processing_enabled);
6781 for (auto&& pb : sub->post_processing)
6785 if (pb->is_enabled())
6786 pb->processing_block_enable_disable(true);
6789 if (ImGui::IsItemHovered())
6791 ImGui::SetTooltip(
"Enable post-processing filters");
6792 window.link_hovered();
6797 std::string label = to_string() <<
" " << textual_icons::toggle_on <<
"##" << id <<
"," << sub->s->get_info(RS2_CAMERA_INFO_NAME) <<
",post";
6798 ImGui::PushStyleColor(ImGuiCol_Text, light_blue);
6799 ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, light_blue + 0.1f);
6801 if (ImGui::Button(label.c_str(), { 30,24 }))
6803 sub->post_processing_enabled =
false;
6805 sub->post_processing_enabled);
6806 for (
auto&& pb : sub->post_processing)
6810 if (pb->is_enabled())
6811 pb->processing_block_enable_disable(
false);
6834 for (
auto&& pb : sub->post_processing)
6836 if (!pb->visible)
continue;
6842 draw_later.push_back([windows_width, &window, sub, pos, &viewer,
this, pb]() {
6843 if (!sub->streaming || !sub->post_processing_enabled)
ImGui::SetCursorPos({ windows_width - 35, pos.y - 3 });
6849 ImGui::PushFont(window.get_font());
6851 ImGui::PushStyleColor(ImGuiCol_Button, sensor_bg);
6852 ImGui::PushStyleColor(ImGuiCol_ButtonHovered, sensor_bg);
6853 ImGui::PushStyleColor(ImGuiCol_ButtonActive, sensor_bg);
6855 if (!sub->post_processing_enabled)
6857 if (!pb->is_enabled())
6859 std::string label = to_string() <<
" " << textual_icons::toggle_off <<
"##" << id <<
"," << sub->s->get_info(RS2_CAMERA_INFO_NAME) <<
"," << pb->get_name();
6861 ImGui::PushStyleColor(ImGuiCol_Text, redish);
6862 ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, redish + 0.1f);
6863 ImGui::ButtonEx(label.c_str(), { 25,24 }, ImGuiButtonFlags_Disabled);
6867 std::string label = to_string() <<
" " << textual_icons::toggle_on <<
"##" << id <<
"," << sub->s->get_info(RS2_CAMERA_INFO_NAME) <<
"," << pb->get_name();
6868 ImGui::PushStyleColor(ImGuiCol_Text, light_blue);
6869 ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, light_blue + 0.1f);
6870 ImGui::ButtonEx(label.c_str(), { 25,24 }, ImGuiButtonFlags_Disabled);
6875 if (!pb->is_enabled())
6877 std::string label = to_string() <<
" " << textual_icons::toggle_off <<
"##" << id <<
"," << sub->s->get_info(RS2_CAMERA_INFO_NAME) <<
"," << pb->get_name();
6879 ImGui::PushStyleColor(ImGuiCol_Text, redish);
6880 ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, redish + 0.1f);
6882 if (ImGui::Button(label.c_str(), { 25,24 }))
6884 if (pb->get_block()->is<zero_order_invalidation>())
6885 sub->verify_zero_order_conditions();
6887 pb->save_to_config_file();
6889 if (ImGui::IsItemHovered())
6891 label = to_string() <<
"Enable " << pb->get_name() <<
" post-processing filter";
6892 ImGui::SetTooltip(
"%s", label.c_str());
6893 window.link_hovered();
6898 std::string label = to_string() <<
" " << textual_icons::toggle_on <<
"##" << id <<
"," << sub->s->get_info(RS2_CAMERA_INFO_NAME) <<
"," << pb->get_name();
6899 ImGui::PushStyleColor(ImGuiCol_Text, light_blue);
6900 ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, light_blue + 0.1f);
6902 if (ImGui::Button(label.c_str(), { 25,24 }))
6905 pb->save_to_config_file();
6909 label =
to_string() <<
"Disable " << pb->get_name() <<
" post-processing filter";
6930 for (
auto&& opt : pb->get_option_list())
6933 pb->get_option(opt).draw_option(
6935 false, error_message, *viewer.
not_model);
6966 sub->update(error_message, *viewer.not_model);
6974 if (draw_device_outline)
6981 const float compenstaion_right = 17.f;;
6984 const float compenstaion_button = 1.0f;
7005 std::lock_guard<std::mutex>
lock(_mtx);
7011 std::lock_guard<std::mutex>
lock(_mtx);
7012 if (_changes.empty())
7015 removed_and_connected =
std::move(_changes.front());
7023 static bool prev_track = track;
7024 if (!_trajectory_tracking)
7036 t.to_column_major((
float*)model);
7038 rs2_vector translation{
t.mat[0][3],
t.mat[1][3],
t.mat[2][3] };
7041 add_to_trajectory(
p);
7049 if (!is_trajectory_button_pressed)
7051 record_trajectory(
false);
7058 for (
auto&&
v : trajectory)
7075 throw std::runtime_error(
"Invalid pose confidence value");
7085 if (trajectory.size() == 0)
7087 trajectory.push_back(p);
7094 if (sqrt(pow((curr.
x - prev.
x), 2) + pow((curr.
y - prev.
y), 2) + pow((curr.
z - prev.
z), 2)) < 0.001)
7097 if (p.second > trajectory.back().second)
7099 trajectory.back() =
p;
7106 trajectory.push_back(p);
void draw_text(int x, int y, const char *text)
subdevice_model(device &dev, std::shared_ptr< sensor > s, std::shared_ptr< atomic_objects_in_frame > objects, std::string &error_message, viewer_model &viewer, bool new_device_connected=true)
std::vector< std::shared_ptr< notification_model > > related_notifications
static const textual_icon lock
IMGUI_API void PushStyleVar(ImGuiStyleVar idx, float val)
static const ImVec4 transparent
device_changes(rs2::context &ctx)
static void populate_options(std::map< int, option_model > &opt_container, const std::string &opt_base_label, subdevice_model *model, std::shared_ptr< options > options, bool *options_invalidated, std::string &error_message)
device_model(device &dev, std::string &error_message, viewer_model &viewer, bool new_device_connected=true, bool allow_remove=true)
void begin_update_unsigned(viewer_model &viewer, std::string &error_message)
#define ImGui_ScopePushStyleVar(idx, val)
GLenum GLuint GLenum GLsizei const GLchar * message
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
static const ImVec4 white
std::map< int, bool > stream_enabled
const char * rs2_format_to_string(rs2_format format)
IMGUI_API float GetCursorPosX()
IMGUI_API void AddRectFilled(const ImVec2 &a, const ImVec2 &b, ImU32 col, float rounding=0.0f, int rounding_corners=0x0F)
std::shared_ptr< recorder > _recorder
static const textual_icon bar_chart
rs2_sensor_mode resolution_from_width_height(int width, int height)
void add_changes(const event_information &c)
GLboolean GLboolean GLboolean b
std::shared_ptr< notification_model > add_notification(const notification_data &n)
bool fw_version_less_than(std::string fw_version, std::string min_fw_version)
void serialize(Stream &stream, const T &t)
Serialize an object. Stream here should normally be a rs2rosinternal::serialization::OStream.
static const textual_icon circle
IMGUI_API ImVec2 GetCursorPos()
std::shared_ptr< texture_buffer > upload_frame(frame &&f)
std::map< int, int > selected_fps_id
std::map< int, std::vector< rs2_format > > format_values
void update_ui(std::vector< stream_profile > profiles_vec)
bool supports_on_chip_calib()
IMGUI_API void SetTooltip(const char *fmt,...) IM_PRINTFARGS(1)
std::string to_lower(std::string x)
std::vector< std::string > shared_fpses
bool motion_data_to_csv(const std::string &filename, rs2::frame frame)
GLuint const GLchar * name
static const ImVec4 almost_white_bg
static const ImVec4 header_window_bg
rs2_vector angular_acceleration
void add_timestamp(double timestamp, unsigned long long frame_counter)
int rs2_get_api_version(rs2_error **error)
std::map< int, int > selected_format_id
bool pose_data_to_csv(const std::string &filename, rs2::frame frame)
std::shared_ptr< rs2::asynchronous_syncer > dev_syncer
std::vector< sensor > query_sensors() const
std::map< int, option_model > options_metadata
std::shared_ptr< atomic_objects_in_frame > _detected_objects
const char * rs2_timestamp_domain_to_string(rs2_timestamp_domain info)
bool is_streaming() const
const char * rs2_frame_metadata_to_string(rs2_frame_metadata_value metadata)
ImVec4 from_rgba(uint8_t r, uint8_t g, uint8_t b, uint8_t a, bool consistent_color)
IMGUI_API void ProgressBar(float fraction, const ImVec2 &size_arg=ImVec2(-1, 0), const char *overlay=NULL)
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
unsigned int tracker_confidence
std::atomic< bool > _pause
bool frame_metadata_to_csv(const std::string &filename, rs2::frame frame)
int selected_shared_fps_id
static const ImVec4 title_color
static basic_json parse(T(&array)[N], const parser_callback_t cb=nullptr)
deserialize from an array
IMGUI_API void SetCursorPos(const ImVec2 &local_pos)
void add_log(std::string message)
static const textual_icon info_circle
bool status_dialog(const std::string &title, const std::string &process_topic_text, const std::string &process_status_text, bool enable_close, ux_window &window)
static const textual_icon question_mark
#define ImGui_ScopePushFont(f)
static const ImVec4 light_grey
static const char * recommend_calibration
def axes(out, pos, rotation=np.eye(3), size=0.075, thickness=2)
static void width_height_from_resolution(rs2_sensor_mode mode, int &width, int &height)
IMGUI_API void PopTextWrapPos()
static config_file & instance()
a class to store JSON values
void update_model_trajectory(const pose_frame &pose, bool track)
GLint GLint GLsizei GLuint * counters
void draw_rect(const rect &r, int line_width)
void verify_zero_order_conditions()
static const ImVec4 light_blue
GLsizei const GLchar *const * path
std::vector< int > shared_fps_values
const char * rs2_distortion_to_string(rs2_distortion distortion)
std::shared_ptr< subdevice_model > dev
std::enable_if< std::is_base_of< rs2::frame, T >::value, bool >::type poll_for_frame(T *output) const
std::list< detected_object::ptr > detected_objects
stream_profile get_profile() const
device_list query_devices() const
std::map< int, stream_model > streams
rect center_at(const float2 &new_center) const
static const textual_icon repeat
IMGUI_API void SetNextWindowPos(const ImVec2 &pos, ImGuiSetCond cond=0)
IMGUI_API void EndTooltip()
static const char * post_processing
rect pan(const float2 &p) const
int get_bytes_per_pixel() const
std::shared_ptr< subdevice_model > get_frame_origin(const rs2::frame &f)
std::shared_ptr< texture_buffer > texture
const float SHORT_RANGE_MIN_DISTANCE
void imgui_easy_theming(ImFont *&font_14, ImFont *&font_18, ImFont *&monofont)
const std::string & get_name() const
std::string get_timestamped_file_name()
GLint GLint GLsizei GLsizei GLsizei depth
int draw_playback_controls(ux_window &window, ImFont *font, viewer_model &view)
bool post_processing_enabled
std::unique_ptr< reflectivity > _reflectivity
const void * get_data() const
static const ImVec4 dark_window_background
IMGUI_API void BeginTooltip()
bool download_to_bytes_vector(const std::string &url, std::vector< uint8_t > &output, user_callback_func_type user_callback_func=user_callback_func_type())
IMGUI_API bool TreeNodeEx(const char *label, ImGuiTreeNodeFlags flags=0)
void save_to_config_file()
void hyperlink(ux_window &window, const char *title, const char *link)
GLdouble GLdouble GLdouble w
option_model & get_option(rs2_option opt)
GLsizei const GLchar *const * string
std::tuple< uint8_t, uint8_t, uint8_t > get_texcolor(video_frame texture, texture_coordinate texcoords)
void begin_update(std::vector< uint8_t > data, viewer_model &viewer, std::string &error_message)
void map_id_frameset_to_frameset(rs2::frameset first, rs2::frameset second)
std::atomic< bool > synchronization_enable
void load_viewer_configurations(const std::string &json_str)
IMGUI_API void PushTextWrapPos(float wrap_pos_x=0.0f)
void handle_hardware_events(const std::string &serialized_data)
void stop(std::shared_ptr< notifications_model > not_model)
static const unsigned int monospace_compressed_size
std::vector< stream_profile > get_supported_profiles()
GLfloat GLfloat GLfloat GLfloat h
std::vector< std::string > split_string(std::string &input, char delim)
rect unnormalize(const rect &unnormalize_to) const
rs2_vector angular_velocity
bool get_default_selection_index(const std::vector< T > &values, const T &def, int *index)
calibration_model _calib_model
GLsizei GLsizei GLfloat distance
static const char * hwlogger_xml
IMGUI_API void AddLine(const ImVec2 &a, const ImVec2 &b, ImU32 col, float thickness=1.0f)
static const unsigned int font_awesome_compressed_data[196000/4]
static const textual_icon stop
void populate_options(const std::string &opt_base_label, subdevice_model *model, bool *options_invalidated, std::string &error_message)
IMGUI_API void TextDisabled(const char *fmt,...) IM_PRINTFARGS(1)
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
IMGUI_API bool InputText(const char *label, char *buf, size_t buf_size, ImGuiInputTextFlags flags=0, ImGuiTextEditCallback callback=NULL, void *user_data=NULL)
std::string get_device_sensor_name(subdevice_model *sub)
GLint GLint GLint GLint GLint GLint GLint GLbitfield GLenum filter
IMGUI_API ImFont * AddFontFromMemoryCompressedTTF(const void *compressed_ttf_data, int compressed_ttf_size, float size_pixels, const ImFontConfig *font_cfg=NULL, const ImWchar *glyph_ranges=NULL)
void draw_trajectory(bool is_trajectory_button_pressed)
IMGUI_API float GetWindowWidth()
void frame_ready(frame result) const
bool ends_with(const std::string &s, const std::string &suffix)
std::atomic< int > zo_sensors
IMGUI_API bool TreeNode(const char *label)
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
std::string truncate_string(const std::string &str, size_t width)
GLenum GLenum GLsizei void * image
bool is_synchronized_frame(viewer_model &viewer, const frame &f)
iterator end() noexcept
returns an iterator to one past the last element
std::shared_ptr< notifications_model > not_model
std::map< int, std::string > stream_display_names
void show_stream_pose(ImFont *font, const rect &stream_rect, const rs2_pose &pose_data, rs2_stream stream_type, bool fullScreen, float y_offset, viewer_model &viewer)
bool show_trigger_camera_accuracy_health_popup
frame first_or_default(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
bool _support_ir_reflectivity
void zero_first_pixel(const rs2::frame &f)
GLboolean GLboolean GLboolean GLboolean a
ImFont * get_font() const
void get_sorted_profiles(std::vector< stream_profile > &profiles)
std::pair< int, std::string > kvp
T get_or_default(const char *key, T def) const
static const textual_icon usb_type
std::vector< const char * > get_string_pointers(const std::vector< std::string > &vec)
static const unsigned int monospace_compressed_data[65328/4]
def info(name, value, persistent=False)
std::function< void(std::function< void()>)> invoker
std::vector< std::string > restarting_device_info
void map_id_frame_to_frame(rs2::frame first, rs2::frame second)
IMGUI_API bool BeginPopup(const char *str_id)
std::shared_ptr< atomic_objects_in_frame > detected_objects
IMGUI_API void SameLine(float pos_x=0.0f, float spacing_w=-1.0f)
std::string error_to_string(const error &e)
bool draw_option(bool update_read_only_options, bool is_streaming, std::string &error_message, notifications_model &model)
rs2::frame process(rs2::frame frame) const override
std::vector< std::shared_ptr< processing_block_model > > const_effects
bool draw_combo_box(const std::string &id, const std::vector< std::string > &device_names, int &new_index)
void draw_options(const std::vector< rs2_option > &drawing_order, bool update_read_only_options, std::string &error_message, notifications_model &model)
bool contains(const std::shared_ptr< librealsense::device_info > &first, const std::shared_ptr< librealsense::device_info > &second)
static const unsigned int font_awesome_compressed_size
IMGUI_API ImDrawList * GetWindowDrawList()
IMGUI_API void PopStyleVar(int count=1)
std::vector< int > fw_version_to_int_vec(std::string fw_version)
IMGUI_API ImVec2 CalcTextSize(const char *text, const char *text_end=NULL, bool hide_text_after_double_hash=false, float wrap_width=-1.0f)
static const float FEET_TO_METER
void save_viewer_configurations(std::ofstream &outfile, nlohmann::json &j)
IMGUI_API void Dummy(const ImVec2 &size)
static const textual_icon refresh
static const char * show_stream_details
bool draw_stream_selection(std::string &error_message)
rs2_timestamp_domain timestamp_domain
static const ImVec4 regular_blue
ImVec4 operator+(const ImVec4 &c, float v)
static const textual_icon download
bool try_get_next_changes(event_information &removed_and_connected)
GLenum GLint GLint * precision
void check_for_bundled_fw_update(const rs2::context &ctx, std::shared_ptr< notifications_model > not_model)
void play_defaults(viewer_model &view)
temporal_event _stream_not_alive
IMGUI_API void TextUnformatted(const char *text, const char *text_end=NULL)
std::function< void()> on_frame
static const textual_icon play
static const textual_icon link
void push_back_if_not_exists(std::vector< T > &vec, T value)
iterator find(typename object_t::key_type key)
find an element in a JSON object
bool check_profile(stream_profile p, T cond, std::map< V, std::map< int, stream_profile >> &profiles_map, std::vector< stream_profile > &results, V key, int num_streams, stream_profile &def_p)
void open_url(const char *url)
std::vector< uint8_t > bytes_from_bin_file(const std::string &filename)
bool show_single_fps_list
std::string safe_call(T t)
void draw_advanced_mode_controls(rs400::advanced_mode &advanced, advanced_mode_control &amc, bool &get_curr_advanced_controls, bool &was_set, std::string &error_message)
void upload(const rs2::video_frame &frame)
uint64_t num_supported_non_default_options() const
std::vector< std::pair< std::string, std::string > > infos
bool restore_processing_block(const char *name, std::shared_ptr< rs2::processing_block > pb, bool enable=true)
double get_timestamp() const
static const unsigned int karla_regular_compressed_size
rect get_normalized_zoom(const rect &stream_rect, const mouse_info &g, bool is_middle_clicked, float zoom_val)
void show_frame(const rect &stream_rect, const mouse_info &g, std::string &error_message)
T get(float stabilization_percent=0.75f) const
#define RS2_PRODUCT_LINE_D400
std::string get(const char *key, const char *def) const
static const textual_icon step_forward
static const ImVec4 scrollbar_bg
animated< float > _info_height
std::vector< std::string > get_device_info(const device &dev, bool include_location)
std::string url_encode(const std::string &value)
std::vector< rs2_option > supported_options
bool is_option_skipped(rs2_option opt) const
bool draw_reflectivity(int x, int y, rs2::depth_sensor ds, const std::map< int, stream_model > &streams, std::stringstream &ss, bool same_line=false)
bool allow_change_resolution_while_streaming
const char * get_info(rs2_camera_info info) const
bool allow_change_fps_while_streaming
void play(const std::vector< stream_profile > &profiles, viewer_model &viewer, std::shared_ptr< rs2::asynchronous_syncer >)
rect get_original_stream_bounds() const
static const textual_icon upload
IMGUI_API ImGuiIO & GetIO()
GLint GLsizei GLsizei height
namespace for Niels Lohmann
static const textual_icon edit
IMGUI_API bool SeekSlider(const char *label, int *v, const char *display_format="%.0f%%")
static const char * sw_updates_url
frame allocate_composite_frame(std::vector< frame > frames) const
std::map< int, std::vector< std::string > > fpses_per_stream
GLint GLint GLsizei GLint GLenum format
static int get_resolution_id_from_sensor_mode(rs2_sensor_mode sensor_mode, const rs2::sensor &s, const std::vector< std::pair< int, int > > &res_values)
std::set< std::string > advanced_mode_settings_file_names
std::chrono::high_resolution_clock::time_point last_frame
static const char * compression_mode
static const ImVec4 sensor_bg
void sort_together(std::vector< T > &vec, std::vector< std::string > &names)
stream_model * selected_stream
void export_frame(const std::string &fname, std::unique_ptr< rs2::filter > exporter, notifications_model &ns, frame data, bool notify)
float max_usable_range(float nest)
unsigned __int64 uint64_t
int draw_playback_panel(ux_window &window, ImFont *font, viewer_model &view)
IMGUI_API void SetCursorPosX(float x)
std::shared_ptr< options > endpoint
stream_profile original_profile
void snapshot_frame(const char *filename, viewer_model &viewer) const
std::shared_ptr< updates_model > updates
bool contains(const char *key) const
float draw_device_panel(float panel_width, ux_window &window, std::string &error_message, viewer_model &viewer)
static const char * last_calib_notice
std::shared_ptr< sensor > s
advanced_mode_control amc
static const textual_icon file_movie
static const ImVec4 sensor_header_light_blue
IMGUI_API void PushItemWidth(float item_width)
bool string_to_int(const std::string &str, float &result)
bool yes_no_dialog(const std::string &title, const std::string &message_text, bool &approved, ux_window &window, const std::string &error_message, bool disabled, const std::string &disabled_reason)
IMGUI_API void Text(const char *fmt,...) IM_PRINTFARGS(1)
IMGUI_API bool Button(const char *label, const ImVec2 &size=ImVec2(0, 0))
rs2_format
A stream's format identifies how binary data is encoded within a frame.
void outline_rect(const rect &r)
const char * file_dialog_open(file_dialog_mode flags, const char *filters, const char *default_path, const char *default_name)
bool draw_option(rs2_option opt, bool update_read_only_options, std::string &error_message, notifications_model &model)
IMGUI_API void Separator()
static const ImVec4 button_color
void begin_stream(std::shared_ptr< subdevice_model > d, rs2::stream_profile p)
const base::type::char_t * unit
std::unique_ptr< cah_model > _accuracy_health_model
IMGUI_API bool DragFloat(const char *label, float *v, float v_speed=1.0f, float v_min=0.0f, float v_max=0.0f, const char *display_format="%.3f", float power=1.0f)
GLint GLint GLsizei GLint GLenum GLenum const void * pixels
static const ImVec4 dark_grey
std::string selected_file_preset
IMGUI_API void EndPopup()
static const ImVec4 header_color
int save_to_png(const char *filename, size_t pixel_width, size_t pixels_height, size_t bytes_per_pixel, const void *raster_data, size_t stride_bytes)
std::vector< std::pair< int, int > > res_values
ImVec4 alpha(const ImVec4 &v, float a)
rect get_stream_bounds() const
rs2_stream
Streams are different types of data provided by RealSense devices.
std::vector< stream_profile > get_selected_profiles()
void begin_stream(std::shared_ptr< subdevice_model > d, rs2::stream_profile p, const viewer_model &viewer)
rect cut_by(const rect &r) const
static const textual_icon window_restore
IMGUI_API void PushStyleColor(ImGuiCol idx, const ImVec4 &col)
static const ImVec4 black
void map_id(rs2::frame new_frame, rs2::frame old_frame)
bool supports(rs2_camera_info info) const
IMGUI_API bool ButtonEx(const char *label, const ImVec2 &size_arg=ImVec2(0, 0), ImGuiButtonFlags flags=0)
std::chrono::duration< uint64_t, std::nano > nanoseconds
void handle_online_sw_update(std::shared_ptr< notifications_model > nm, std::shared_ptr< sw_update::dev_updates_profile::update_profile > update_profile)
void open_issue(const device_models_list &devices)
IMGUI_API bool Combo(const char *label, int *current_item, const char **items, int items_count, int height_in_items=-1, bool show_arrow_down=true)
static const textual_icon times
IMGUI_API void PushFont(ImFont *font)
std::shared_ptr< processing_block_model > zero_order_artifact_fix
post_processing_filters ppf
std::map< int, option_model > options_metadata
rs2_sensor_mode
For setting the camera_mode option.
void save_processing_block_to_config_file(const char *name, std::shared_ptr< rs2::processing_block > pb, bool enable)
bool can_enable_zero_order()
void stop_recording(viewer_model &viewer)
GLenum GLenum GLsizei void * table
#define RS2_PRODUCT_LINE_ANY
static const textual_icon toggle_off
GLsizei const GLfloat * values
static const textual_icon toggle_on
std::map< int, bool > prev_stream_enabled
std::map< int, std::vector< uint8_t > > create_default_fw_table()
void next(auto_any_t cur, type2type< T, C > *)
std::pair< std::string, std::string > get_device_name(const device &dev)
ImVec4 Colors[ImGuiCol_COUNT]
IMGUI_API bool SliderIntWithSteps(const char *label, int *v, int v_min, int v_max, int v_step=1, const char *display_format="%.3f")
rs2_format format() const
const char * rs2_camera_info_to_string(rs2_camera_info info)
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)
void refresh_notifications(viewer_model &viewer)
3D vector in Euclidean coordinate space
IMGUI_API ImVec2 GetCursorScreenPos()
int parse_product_line(std::string id)
bool val_in_range(const T &val, const std::initializer_list< T > &list)
std::string get_file_name(const std::string &path)
std::vector< std::pair< std::string, std::string > > get_devices_names(const device_list &list)
GLdouble GLdouble GLdouble q
static const textual_icon window_maximize
void set(const char *key, const char *value)
subdevice_ui_selection ui
void check_for_device_updates(viewer_model &viewer)
IMGUI_API void PopItemWidth()
const char * rs2_stream_to_string(rs2_stream stream)
static const textual_icon step_backward
std::vector< std::shared_ptr< processing_block_model > > post_processing
static int stb_easy_font_width(char *text)
static const ImVec4 scrollbar_grab
rs2_playback_status current_status() const
const float SHORT_RANGE_MAX_DISTANCE
bool show_stream_selection
void show(const rect &r, float alpha=1.f) const
bool is_there_common_fps()
bool prompt_toggle_advanced_mode(bool enable_advanced_mode, const std::string &message_text, std::vector< std::string > &restarting_device_info, viewer_model &view, ux_window &window, const std::string &error_message)
void update_ae_roi_rect(const rect &stream_rect, const mouse_info &mouse, std::string &error_message)
float draw_preset_panel(float panel_width, ux_window &window, std::string &error_message, viewer_model &viewer, bool update_read_only_options, bool load_json_if_streaming, json_loading_func json_loading)
GLuint GLsizei const GLchar * label
IMGUI_API float GetTextLineHeight()
void draw_controls(float panel_width, float panel_height, ux_window &window, std::string &error_message, device_model *&device_to_remove, viewer_model &viewer, float windows_width, std::vector< std::function< void()>> &draw_later, bool load_json_if_streaming=false, json_loading_func json_loading=[](std::function< void()> load){load();}, bool draw_device_outline=true)
const GLuint GLenum const void * binary
std::function< void(std::function< void()> load)> json_loading_func
bool get_curr_advanced_controls
std::chrono::nanoseconds get_duration() const
const rs2_stream_profile * get() const
#define RS2_API_FULL_VERSION_STR
void invoke(frame f) const
static const textual_icon camera
IMGUI_API bool MenuItem(const char *label, const char *shortcut=NULL, bool selected=false, bool enabled=true)
void bin_file_from_bytes(const std::string &filename, const std::vector< uint8_t > bytes)
void map_id_frameset_to_frame(rs2::frameset first, rs2::frame second)
static const textual_icon bars
string_t dump(const int indent=-1) const
serialization
bool contains(const float2 &p) const
std::shared_ptr< rs2::filter > _block
IMGUI_API bool Selectable(const char *label, bool selected=false, ImGuiSelectableFlags flags=0, const ImVec2 &size=ImVec2(0, 0))
std::atomic< bool > synchronization_enable_prev_state
bool is_3d_depth_source(frame f)
static const textual_icon metadata
IMGUI_API bool Checkbox(const char *label, bool *v)
utilities::number::stabilized_value< float > _stabilized_reflectivity
bool auto_exposure_enabled
std::string download_link
bool save_frame_raw_data(const std::string &filename, rs2::frame frame)
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
std::vector< std::unique_ptr< device_model > > device_models_list
GLsizei GLsizei GLchar * source
IMGUI_API ImU32 GetColorU32(ImGuiCol idx, float alpha_mul=1.0f)
rect enclose_in(rect in_rect) const
void set_devices_changed_callback(T callback)
std::shared_ptr< rs2::yuy_decoder > yuy2rgb
bool starts_with(const std::string &s, const std::string &prefix)
rect normalize(const rect &normalize_to) const
std::vector< std::shared_ptr< subdevice_model > > subdevices
std::map< int, std::vector< int > > fps_values_per_stream
utilities::time::periodic_timer _update_readonly_options_timer
IMGUI_API void SetCursorScreenPos(const ImVec2 &pos)
void update(ux_window &window, std::string &error_message)
int stoi(const std::string &value)
bool handle_online_fw_update(const context &ctx, std::shared_ptr< notifications_model > nm, std::shared_ptr< sw_update::dev_updates_profile::update_profile > update_profile)
static const ImVec4 redish
bool _options_invalidated
IMGUI_API void SetContentRegionWidth(float y)
bool is_3d_texture_source(frame f) const
std::map< int, rs2::frame_queue > frames_queue
void add_to_trajectory(tracked_point &p)
static const char * show_map_ruler
static const textual_icon pause
IMGUI_API ImGuiStyle & GetStyle()
static const textual_icon exclamation_triangle
void show_stream_header(ImFont *font, const rect &stream_rect, viewer_model &viewer)
std::string get_available_firmware_version(int product_line)
GLuint GLenum GLenum transform
ImVec4 flip(const ImVec4 &c)
IMGUI_API void CloseCurrentPopup()
static const ImVec4 yellow
ImFont * get_large_font() const
std::map< int, std::vector< std::string > > formats
std::vector< stream_profile > profiles
IMGUI_API void OpenPopup(const char *str_id)
std::string api_version_to_string(int version)
bool draw_advanced_controls(viewer_model &view, ux_window &window, std::string &error_message)
std::vector< std::string > resolutions
bool is_upgradeable(const std::string &curr, const std::string &available)
std::string get_os_name()
static const char * recommend_updates
bool is_selected_combination_supported()
IMGUI_API void SetCursorPosY(float y)
void draw_info_icon(ux_window &window, ImFont *font, const ImVec2 &size)
std::shared_ptr< syncer_model > syncer
option_model create_option_model(rs2_option opt, const std::string &opt_base_label, subdevice_model *model, std::shared_ptr< options > options, bool *options_invalidated, std::string &error_message)
unsigned long long get_frame_number() const
bool show_reset_camera_accuracy_health_popup
void show_stream_footer(ImFont *font, const rect &stream_rect, const mouse_info &mouse, const std::map< int, stream_model > &streams, viewer_model &viewer)
matrix4 tm2_pose_to_world_transformation(const rs2_pose &pose)
int get_stride_in_bytes() const
rs2_stream stream_type() const
void start_recording(const std::string &path, std::string &error_message)
void set_option(rs2_option option, float value) const
bool retrieve_updates(component_part_type comp)
IMGUI_API void Columns(int count=1, const char *id=NULL, bool border=true)
IMGUI_API void SetWindowFontScale(float scale)
std::string pretty_time(std::chrono::nanoseconds duration)
void process(rs2::frame f, const rs2::frame_source &source)
float get_option(rs2_option option) const
void update(std::string &error_message, notifications_model &model)
rect zoom(float zoom_factor) const
static const char * default_path
static const ImVec4 dark_sensor_bg
GeneratorWrapper< T > map(Func &&function, GeneratorWrapper< U > &&generator)
unsigned long long frame_number
IMGUI_API float GetCursorPosY()
IMGUI_API bool IsItemHovered()
std::shared_ptr< sw_update::dev_updates_profile::update_profile > _updates_profile
std::shared_ptr< sensor > sensor_from_frame(frame f)
static const unsigned int karla_regular_compressed_data[12720/4]
update_profile & get_update_profile()
subdevice_ui_selection last_valid_ui
static const char * file_save_mode
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
static const char * allow_rc_firmware
std::shared_ptr< rs2::colorizer > depth_colorizer
void set_option(rs2_option opt, float value, std::string &error_message)
void show_stream_imu(ImFont *font, const rect &stream_rect, const rs2_vector &axis, const mouse_info &mouse)
IMGUI_API ImVec4 ColorConvertU32ToFloat4(ImU32 in)
IMGUI_API void PopStyleColor(int count=1)
#define ImGui_ScopePushStyleColor(idx, col)
std::string to_string(T value)
IMGUI_API void TextColored(const ImVec4 &col, const char *fmt,...) IM_PRINTFARGS(2)
rs2::frame apply_filters(rs2::frame f, const rs2::frame_source &source)
bool draw_streams_selector
std::vector< rs2::frame > handle_frame(rs2::frame f, const rs2::frame_source &source)