on-chip-calib.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2017 Intel Corporation. All Rights Reserved.
3 
4 #include <glad/glad.h>
5 #include "on-chip-calib.h"
6 
7 #include <map>
8 #include <vector>
9 #include <string>
10 #include <thread>
11 #include <condition_variable>
12 #include <model-views.h>
13 #include <viewer.h>
14 
15 #include "../tools/depth-quality/depth-metrics.h"
16 
17 namespace rs2
18 {
20  {
21  try
22  {
23  auto profiles = _sub->get_selected_profiles();
24 
25  invoke([&](){
26  // Stop viewer UI
27  _sub->stop(_viewer.not_model);
28  });
29 
30  // Wait until frames from all active profiles stop arriving
31  bool frame_arrived = false;
32  while (frame_arrived && _viewer.streams.size())
33  {
34  for (auto&& stream : _viewer.streams)
35  {
36  if (std::find(profiles.begin(), profiles.end(),
37  stream.second.original_profile) != profiles.end())
38  {
40  if (now - stream.second.last_frame > std::chrono::milliseconds(200))
41  frame_arrived = false;
42  }
43  else frame_arrived = false;
44  }
45  std::this_thread::sleep_for(std::chrono::milliseconds(10));
46  }
47  }
48  catch (...) {}
49  }
50 
51  // Wait for next depth frame and return it
53  {
54  auto profiles = _sub->get_selected_profiles();
55  bool frame_arrived = false;
57  while (!frame_arrived)
58  {
59  for (auto&& stream : _viewer.streams)
60  {
61  if (std::find(profiles.begin(), profiles.end(),
62  stream.second.original_profile) != profiles.end())
63  {
65  if (now - stream.second.last_frame < std::chrono::milliseconds(100))
66  {
67  if (auto f = stream.second.texture->get_last_frame(false).as<rs2::depth_frame>())
68  {
69  frame_arrived = true;
70  res = f;
71  }
72  }
73  }
74  }
75  std::this_thread::sleep_for(std::chrono::milliseconds(10));
76  }
77  return res;
78  }
79 
80  bool on_chip_calib_manager::start_viewer(int w, int h, int fps, invoker invoke)
81  {
82  bool frame_arrived = false;
83  try
84  {
86  {
87  _uid = 1;
88  for (const auto& format : _sub->formats)
89  {
90  if (format.second[0] == "Y8")
91  {
92  _uid = format.first;
93  break;
94  }
95  }
96  if (_sub->s->supports(RS2_OPTION_EMITTER_ENABLED))
97  _sub->s->set_option(RS2_OPTION_EMITTER_ENABLED, 0.0f);
98  }
99  else
100  {
101  _uid = 0;
102  for (const auto & format : _sub->formats)
103  {
104  if (format.second[0] == "Z16")
105  {
106  _uid = format.first;
107  break;
108  }
109  }
110  }
111 
112  // Select stream
113  _sub->stream_enabled.clear();
114  _sub->stream_enabled[_uid] = true;
115 
116  _sub->ui.selected_format_id.clear();
117  _sub->ui.selected_format_id[_uid] = 0;
118 
119  // Select FPS value
120  for (int i = 0; i < _sub->shared_fps_values.size(); i++)
121  {
122  if (_sub->shared_fps_values[i] == fps)
123  _sub->ui.selected_shared_fps_id = i;
124  }
125 
126  // Select Resolution
127  for (int i = 0; i < _sub->res_values.size(); i++)
128  {
129  auto kvp = _sub->res_values[i];
130  if (kvp.first == w && kvp.second == h)
131  _sub->ui.selected_res_id = i;
132  }
133 
134  // If not supported, try WxHx30
135  if (!_sub->is_selected_combination_supported())
136  {
137  for (int i = 0; i < _sub->shared_fps_values.size(); i++)
138  {
139  //if (_sub->shared_fps_values[i] == 30)
140  _sub->ui.selected_shared_fps_id = i;
141  if (_sub->is_selected_combination_supported()) break;
142  }
143 
144  // If still not supported, try VGA30
145  if (!_sub->is_selected_combination_supported())
146  {
147  for (int i = 0; i < _sub->res_values.size(); i++)
148  {
149  auto kvp = _sub->res_values[i];
150  if (kvp.first == 640 && kvp.second == 480)
151  _sub->ui.selected_res_id = i;
152  }
153  }
154  }
155 
156  auto profiles = _sub->get_selected_profiles();
157 
158  invoke([&](){
159  if (!_model.dev_syncer)
160  _model.dev_syncer = _viewer.syncer->create_syncer();
161 
162  // Start streaming
164  for (auto&& profile : profiles)
165  {
167  }
168  });
169 
170  // Wait for frames to arrive
171  int count = 0;
172  while (!frame_arrived && count++ < 200)
173  {
174  for (auto&& stream : _viewer.streams)
175  {
176  if (std::find(profiles.begin(), profiles.end(),
177  stream.second.original_profile) != profiles.end())
178  {
180  if (now - stream.second.last_frame < std::chrono::milliseconds(100))
181  frame_arrived = true;
182  }
183  }
184  std::this_thread::sleep_for(std::chrono::milliseconds(10));
185  }
186  }
187  catch (...) {}
188 
189  return frame_arrived;
190  }
191 
192  std::pair<float, float> on_chip_calib_manager::get_metric(bool use_new)
193  {
194  return _metrics[use_new ? 1 : 0];
195  }
196 
198  {
199  bool started = start_viewer(w, h, fps, invoke);
200  if (!started)
201  {
202  std::this_thread::sleep_for(std::chrono::milliseconds(600));
203  started = start_viewer(w, h, fps, invoke);
204  }
205 
206  if (!started)
207  {
208  stop_viewer(invoke);
209  log(to_string() << "Failed to start streaming");
210  throw std::runtime_error(to_string() << "Failed to start streaming (" << w << ", " << h << ", " << fps << ")!");
211  }
212  }
213 
214  std::pair<float, float> on_chip_calib_manager::get_depth_metrics(invoker invoke)
215  {
216  using namespace depth_quality;
217 
218  auto f = fetch_depth_frame(invoke);
219  auto sensor = _sub->s->as<rs2::depth_stereo_sensor>();
220  auto intr = f.get_profile().as<rs2::video_stream_profile>().get_intrinsics();
221  rs2::region_of_interest roi { (int)(f.get_width() * 0.45f), (int)(f.get_height() * 0.45f),
222  (int)(f.get_width() * 0.55f), (int)(f.get_height() * 0.55f) };
223  std::vector<single_metric_data> v;
224 
225  std::vector<float> fill_rates;
226  std::vector<float> rmses;
227 
228  auto show_plane = _viewer.draw_plane;
229 
230  auto on_frame = [sensor, &fill_rates, &rmses, this](
231  const std::vector<rs2::float3>& points,
232  const plane p,
233  const rs2::region_of_interest roi,
234  const float baseline_mm,
235  const float focal_length_pixels,
236  const int ground_thruth_mm,
237  const bool plane_fit,
238  const float plane_fit_to_ground_truth_mm,
239  const float distance_mm,
240  bool record,
241  std::vector<single_metric_data>& samples)
242  {
243  static const float TO_MM = 1000.f;
244  static const float TO_PERCENT = 100.f;
245 
246  // Calculate fill rate relative to the ROI
247  auto fill_rate = points.size() / float((roi.max_x - roi.min_x)*(roi.max_y - roi.min_y)) * TO_PERCENT;
248  fill_rates.push_back(fill_rate);
249 
250  if (!plane_fit) return;
251 
252  std::vector<rs2::float3> points_set = points;
253  std::vector<float> distances;
254 
255  // Reserve memory for the data
256  distances.reserve(points.size());
257 
258  // Convert Z values into Depth values by aligning the Fitted plane with the Ground Truth (GT) plane
259  // Calculate distance and disparity of Z values to the fitted plane.
260  // Use the rotated plane fit to calculate GT errors
261  for (auto point : points_set)
262  {
263  // Find distance from point to the reconstructed plane
264  auto dist2plane = p.a*point.x + p.b*point.y + p.c*point.z + p.d;
265 
266  // Store distance, disparity and gt- error
267  distances.push_back(dist2plane * TO_MM);
268  }
269 
270  // Remove outliers [below 1% and above 99%)
271  std::sort(points_set.begin(), points_set.end(), [](const rs2::float3& a, const rs2::float3& b) { return a.z < b.z; });
272  size_t outliers = points_set.size() / 50;
273  points_set.erase(points_set.begin(), points_set.begin() + outliers); // crop min 0.5% of the dataset
274  points_set.resize(points_set.size() - outliers); // crop max 0.5% of the dataset
275 
276  // Calculate Plane Fit RMS (Spatial Noise) mm
277  double plane_fit_err_sqr_sum = std::inner_product(distances.begin(), distances.end(), distances.begin(), 0.);
278  auto rms_error_val = static_cast<float>(std::sqrt(plane_fit_err_sqr_sum / distances.size()));
279  auto rms_error_val_per = TO_PERCENT * (rms_error_val / distance_mm);
280  rmses.push_back(rms_error_val_per);
281  };
282 
283  auto rms_std = 1000.f;
284  auto new_rms_std = rms_std;
285  auto count = 0;
286 
287  // Capture metrics on bundles of 31 frame
288  // Repeat until get "decent" bundle or reach 10 sec
289  do
290  {
291  rms_std = new_rms_std;
292 
293  rmses.clear();
294 
295  for (int i = 0; i < 31; i++)
296  {
297  f = fetch_depth_frame(invoke);
298  auto res = depth_quality::analyze_depth_image(f, sensor.get_depth_scale(), sensor.get_stereo_baseline(),
299  &intr, roi, 0, true, v, false, on_frame);
300 
301  _viewer.draw_plane = true;
302  _viewer.roi_rect = res.plane_corners;
303  }
304 
305  auto rmses_sum_sqr = std::inner_product(rmses.begin(), rmses.end(), rmses.begin(), 0.);
306  new_rms_std = static_cast<float>(std::sqrt(rmses_sum_sqr / rmses.size()));
307  } while ((new_rms_std < rms_std * 0.8f && new_rms_std > 10.f) && count++ < 10);
308 
309  std::sort(fill_rates.begin(), fill_rates.end());
310  std::sort(rmses.begin(), rmses.end());
311 
312  float median_fill_rate, median_rms;
313  if (fill_rates.empty())
314  median_fill_rate = 0;
315  else
316  median_fill_rate = fill_rates[fill_rates.size() / 2];
317  if (rmses.empty())
318  median_rms = 0;
319  else
320  median_rms = rmses[rmses.size() / 2];
321 
322  _viewer.draw_plane = show_plane;
323 
324  return { median_fill_rate, median_rms };
325  }
326 
328  const std::vector<uint8_t>& cmd, const std::string& name)
329  {
330  auto dp = _dev.as<debug_protocol>();
331  if (!dp) throw std::runtime_error("Device does not support debug protocol!");
332 
333  auto res = dp.send_and_receive_raw_data(cmd);
334 
335  if (res.size() < sizeof(int32_t)) throw std::runtime_error(to_string() << "Not enough data from " << name << "!");
336  auto return_code = *((int32_t*)res.data());
337  if (return_code < 0) throw std::runtime_error(to_string() << "Firmware error (" << return_code << ") from " << name << "!");
338 
339  return res;
340  }
341 
343  {
344  time_t rawtime;
345  time(&rawtime);
347  config_file::instance().set(id.c_str(), (long long)rawtime);
348  }
349 
351  {
352  int occ_timeout_ms = 9000;
354  {
355  if (toggle)
356  {
357  occ_timeout_ms = 12000;
358  if (speed_fl == 0)
359  speed_fl = 1;
360  else if (speed_fl == 1)
361  speed_fl = 0;
362  toggle = false;
363  std::this_thread::sleep_for(std::chrono::milliseconds(3000));
364  }
365 
366  if (speed_fl == 0)
367  {
368  speed = 1;
369  fl_step_count = 41;
370  fy_scan_range = 30;
371  white_wall_mode = 0;
372  }
373  else if (speed_fl == 1)
374  {
375  speed = 3;
376  fl_step_count = 51;
377  fy_scan_range = 40;
378  white_wall_mode = 0;
379  }
380  else if (speed_fl == 2)
381  {
382  speed = 4;
383  fl_step_count = 41;
384  fy_scan_range = 30;
385  white_wall_mode = 1;
386  }
387  }
388 
389  std::stringstream ss;
391  {
392  ss << "{\n \"calib type\":" << 1 <<
393  ",\n \"fl step count\":" << fl_step_count <<
394  ",\n \"fy scan range\":" << fy_scan_range <<
395  ",\n \"keep new value after sucessful scan\":" << keep_new_value_after_sucessful_scan <<
396  ",\n \"fl data sampling\":" << fl_data_sampling <<
397  ",\n \"adjust both sides\":" << adjust_both_sides <<
398  ",\n \"fl scan location\":" << fl_scan_location <<
399  ",\n \"fy scan direction\":" << fy_scan_direction <<
400  ",\n \"white wall mode\":" << white_wall_mode << "}";
401  }
403  {
404  ss << "{\n \"calib type\":" << 0 <<
405  ",\n \"speed\":" << speed <<
406  ",\n \"average step count\":" << average_step_count <<
407  ",\n \"scan parameter\":" << (intrinsic_scan ? 0 : 1) <<
408  ",\n \"step count\":" << step_count <<
409  ",\n \"apply preset\":" << (apply_preset ? 1 : 0) <<
410  ",\n \"accuracy\":" << accuracy << "}";
411  }
412  else
413  {
414  ss << "{\n \"calib type\":" << 2 <<
415  ",\n \"fl step count\":" << fl_step_count <<
416  ",\n \"fy scan range\":" << fy_scan_range <<
417  ",\n \"keep new value after sucessful scan\":" << keep_new_value_after_sucessful_scan <<
418  ",\n \"fl data sampling\":" << fl_data_sampling <<
419  ",\n \"adjust both sides\":" << adjust_both_sides <<
420  ",\n \"fl scan location\":" << fl_scan_location <<
421  ",\n \"fy scan direction\":" << fy_scan_direction <<
422  ",\n \"white wall mode\":" << white_wall_mode <<
423  ",\n \"speed\":" << speed <<
424  ",\n \"average step count\":" << average_step_count <<
425  ",\n \"scan parameter\":" << (intrinsic_scan ? 0 : 1) <<
426  ",\n \"step count\":" << step_count <<
427  ",\n \"apply preset\":" << (apply_preset ? 1 : 0) <<
428  ",\n \"accuracy\":" << accuracy << "}";
429  }
430  std::string json = ss.str();
431 
432  auto calib_dev = _dev.as<auto_calibrated_device>();
434  _new_calib = calib_dev.run_tare_calibration(ground_truth, json, [&](const float progress) {_progress = int(progress);}, 5000);
436  _new_calib = calib_dev.run_on_chip_calibration(json, &_health, [&](const float progress) {_progress = int(progress);}, occ_timeout_ms);
437 
439  {
440  int h_both = static_cast<int>(_health);
441  int h_1 = (h_both & 0x00000FFF);
442  int h_2 = (h_both & 0x00FFF000) >> 12;
443  int sign = (h_both & 0x0F000000) >> 24;
444 
445  _health_1 = h_1 / 1000.0f;
446  if (sign & 1)
447  _health_1 = -_health_1;
448 
449  _health_2 = h_2 / 1000.0f;
450  if (sign & 2)
451  _health_2 = -_health_2;
452  }
453  }
454 
456  {
457  try
458  {
459  std::shared_ptr<rect_calculator> gt_calculator;
460  bool created = false;
461 
462  int counter = 0;
464  int step = 100 / rect_calculator::_frame_num;
465 
466  float rect_sides[4] = { 0 };
467  float target_fw = 0;
468  float target_fh = 0;
469 
470  int ret = 0;
471  rs2::frame f;
472  while (counter < limit)
473  {
474  f = _viewer.ppf.frames_queue[_uid].wait_for_frame();
475  if (f)
476  {
477  if (!created)
478  {
480  auto vsp = profile.as<video_stream_profile>();
481 
482  gt_calculator = std::make_shared<rect_calculator>();
484  target_fh = vsp.get_intrinsics().fy * config_file::instance().get_or_default(configurations::viewer::target_height_r, 100.0f);
485  created = true;
486  }
487 
488  ret = gt_calculator->calculate(f.get(), rect_sides);
489  if (ret == 0)
490  ++counter;
491  else if (ret == 1)
492  _progress += step;
493  else if (ret == 2)
494  {
495  _progress += step;
496  break;
497  }
498  }
499  }
500 
501  if (ret != 2)
502  fail("Please adjust the camera position \nand make sure the specific target is \nin the middle of the camera image!");
503  else
504  {
505  float gt[4] = { 0 };
506 
507  if (rect_sides[0] > 0)
508  gt[0] = target_fw / rect_sides[0];
509 
510  if (rect_sides[1] > 0)
511  gt[1] = target_fw / rect_sides[1];
512 
513  if (rect_sides[2] > 0)
514  gt[2] = target_fh / rect_sides[2];
515 
516  if (rect_sides[3] > 0)
517  gt[3] = target_fh / rect_sides[3];
518 
519  if (gt[0] <= 0.1f || gt[1] <= 0.1f || gt[2] <= 0.1f || gt[3] <= 0.1f)
520  fail("Bad target rectangle side sizes returned!");
521 
522  ground_truth = 0.0;
523  for (int i = 0; i < 4; ++i)
524  ground_truth += gt[i];
525  ground_truth /= 4.0;
526 
528  }
529  }
530  catch (const std::runtime_error& error)
531  {
532  fail(error.what());
533  }
534  catch (...)
535  {
536  fail("Getting ground truth failed!");
537  }
538  }
539 
540  void on_chip_calib_manager::process_flow(std::function<void()> cleanup, invoker invoke)
541  {
543 
545  log(to_string() << "Starting focal length calibration");
547  log(to_string() << "Starting OCC Extended");
548  else
549  log(to_string() << "Starting OCC at speed " << speed);
550 
553 
555 
556  auto calib_dev = _dev.as<auto_calibrated_device>();
557  _old_calib = calib_dev.get_calibration_table();
558 
559  _was_streaming = _sub->streaming;
561  _post_processing = _sub->post_processing_enabled;
562  _sub->post_processing_enabled = false;
564 
565  _restored = false;
566 
568  {
569  if (!_was_streaming)
570  try_start_viewer(0, 0, 0, invoke);
571 
572  // Capture metrics before
573  auto metrics_before = get_depth_metrics(invoke);
574  _metrics.push_back(metrics_before);
575  }
576 
577  stop_viewer(invoke);
578 
579  _ui = std::make_shared<subdevice_ui_selection>(_sub->ui);
580  std::this_thread::sleep_for(std::chrono::milliseconds(600));
581 
582  // Switch into special Auto-Calibration mode
583  try_start_viewer(256, 144, 90, invoke);
584 
587  else
588  {
589  try
590  {
591  calibrate();
592  }
593  catch (...)
594  {
595  log(to_string() << "Calibration failed with exception");
596  stop_viewer(invoke);
597  if (_ui.get())
598  _sub->ui = *_ui;
599  if (_was_streaming)
600  start_viewer(0, 0, 0, invoke);
601  throw;
602  }
603  }
604 
606  log(to_string() << "Tare ground truth is got: " << ground_truth);
607  else
608  log(to_string() << "Calibration completed, health factor = " << _health);
609 
610  stop_viewer(invoke);
611  if (_ui.get())
612  _sub->ui = *_ui;
613 
615  {
616  try_start_viewer(0, 0, 0, invoke); // Start with default settings
617 
618  // Make new calibration active
619  apply_calib(true);
620 
621  // Capture metrics after
622  auto metrics_after = get_depth_metrics(invoke);
623  _metrics.push_back(metrics_after);
624  }
625 
626  _progress = 100;
627 
628  _done = true;
629  }
630 
632  {
633  try
634  {
635  if (_restored) return;
636 
638 
641 
643 
644  stop_viewer(invoke);
645 
646  if (_ui.get())
647  {
648  _sub->ui = *_ui;
649  _ui.reset();
650  }
651 
652  _sub->post_processing_enabled = _post_processing;
653 
654  std::this_thread::sleep_for(std::chrono::milliseconds(200));
655 
656  if (_was_streaming) start_viewer(0, 0, 0, invoke);
657 
658  _restored = true;
659  }
660  catch (...) {}
661  }
662 
664  {
665  // Write new calibration using SETINITCAL command
666  auto calib_dev = _dev.as<auto_calibrated_device>();
667  calib_dev.write_calibration();
668  }
669 
671  {
672  auto calib_dev = _dev.as<auto_calibrated_device>();
673  calib_dev.set_calibration_table(use_new ? _new_calib : _old_calib);
674  }
675 
677  {
678  using namespace std;
679  using namespace chrono;
680 
681  auto recommend_keep = false;
683  {
684  float health_1 = get_manager().get_health_1();
685  float health_2 = get_manager().get_health_2();
686  bool recommend_keep_1 = fabs(health_1) < 0.25f;
687  bool recommend_keep_2 = fabs(health_2) < 0.15f;
688  recommend_keep = (recommend_keep_1 && recommend_keep_2);
689  }
690  else if (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_FL_CALIB)
691  recommend_keep = fabs(get_manager().get_health()) < 0.15f;
692  else if (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_CALIB)
693  recommend_keep = fabs(get_manager().get_health()) < 0.25f;
694 
695  if (recommend_keep && update_state == RS2_CALIB_STATE_CALIB_COMPLETE && (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_CALIB || get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_FL_CALIB || get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB))
696  {
697  auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
698 
703  }
704  else
706  }
707 
709  {
710  bool intrinsic = get_manager().intrinsic_scan;
711  bool extrinsic = !intrinsic;
712 
713  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 35 + ImGui::GetTextLineHeightWithSpacing()) });
714 
715  std::string id = to_string() << "##Intrinsic_" << index;
716  if (ImGui::Checkbox("Intrinsic", &intrinsic))
717  {
718  extrinsic = !intrinsic;
719  }
720  if (ImGui::IsItemHovered())
721  {
722  ImGui::SetTooltip("%s", "Calibrate intrinsic parameters of the camera");
723  }
724  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 35 + ImGui::GetTextLineHeightWithSpacing()) });
725 
726  id = to_string() << "##Intrinsic_" << index;
727 
728  if (ImGui::Checkbox("Extrinsic", &extrinsic))
729  {
730  intrinsic = !extrinsic;
731  }
732  if (ImGui::IsItemHovered())
733  {
734  ImGui::SetTooltip("%s", "Calibrate extrinsic parameters between left and right cameras");
735  }
736 
737  get_manager().intrinsic_scan = intrinsic;
738  }
739 
740  void autocalib_notification_model::draw_content(ux_window& win, int x, int y, float t, std::string& error_message)
741  {
742  using namespace std;
743  using namespace chrono;
744 
745  const auto bar_width = width - 115;
746 
747  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 4) });
748 
749  ImVec4 shadow{ 1.f, 1.f, 1.f, 0.1f };
750  ImGui::GetWindowDrawList()->AddRectFilled({ float(x), float(y) },
751  { float(x + width), float(y + 25) }, ImColor(shadow));
752 
753  if (update_state != RS2_CALIB_STATE_COMPLETE)
754  {
755  if (update_state == RS2_CALIB_STATE_INITIAL_PROMPT)
756  ImGui::Text("%s", "Calibration Health-Check");
757  else if (update_state == RS2_CALIB_STATE_CALIB_IN_PROCESS ||
758  update_state == RS2_CALIB_STATE_CALIB_COMPLETE ||
759  update_state == RS2_CALIB_STATE_SELF_INPUT)
760  {
762  ImGui::Text("%s", "On-Chip Calibration Extended");
764  ImGui::Text("%s", "On-Chip Focal Length Calibration");
766  ImGui::Text("%s", "Tare Calibration");
767  else
768  ImGui::Text("%s", "On-Chip Calibration");
769  }
770  else if (update_state == RS2_CALIB_STATE_TARE_INPUT || update_state == RS2_CALIB_STATE_TARE_INPUT_ADVANCED)
771  ImGui::Text("%s", "Tare Calibration");
772  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH || update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_IN_PROCESS || update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_COMPLETE)
773  ImGui::Text("%s", "Get Tare Calibration Ground Truth");
774  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_FAILED)
775  ImGui::Text("%s", "Get Tare Calibration Ground Truth Failed");
776  else if (update_state == RS2_CALIB_STATE_FAILED && !((get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB || get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_FL_CALIB) && get_manager().retry_times < 3))
777  ImGui::Text("%s", "Calibration Failed");
778 
779  if (update_state == RS2_CALIB_STATE_TARE_INPUT || update_state == RS2_CALIB_STATE_TARE_INPUT_ADVANCED)
780  ImGui::SetCursorScreenPos({ float(x + width - 30), float(y) });
781  else if (update_state == RS2_CALIB_STATE_FAILED)
782  ImGui::SetCursorScreenPos({ float(x + 2), float(y + 27) });
783  else
784  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 27) });
785 
787 
788  if (update_state == RS2_CALIB_STATE_INITIAL_PROMPT)
789  {
791 
792  ImGui::Text("%s", "Following devices support On-Chip Calibration:");
793  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 47) });
794 
796  ImGui::Text("%s", message.c_str());
798 
799  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 65) });
800  ImGui::Text("%s", "Run quick calibration Health-Check? (~30 sec)");
801  }
802  else if (update_state == RS2_CALIB_STATE_CALIB_IN_PROCESS)
803  {
804  enable_dismiss = false;
805  ImGui::Text("%s", "Camera is being calibrated...\nKeep the camera stationary pointing at a wall");
806  }
807  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH)
808  {
809  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 33) });
810  ImGui::Text("%s", "Target Width:");
811  if (ImGui::IsItemHovered())
812  {
813  ImGui::SetTooltip("%s", "The width of the rectangle in millimeter inside the specific target");
814  }
815 
816  const int MAX_SIZE = 256;
817  char buff[MAX_SIZE];
818 
819  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 30) });
820  std::string id = to_string() << "##target_width_" << index;
821  ImGui::PushItemWidth(width - 145.0f);
823  std::string tw = to_string() << target_width;
824  memcpy(buff, tw.c_str(), tw.size() + 1);
825  if (ImGui::InputText(id.c_str(), buff, std::max((int)tw.size() + 1, 10)))
826  {
827  std::stringstream ss;
828  ss << buff;
829  ss >> target_width;
831  }
833 
834  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 38 + ImGui::GetTextLineHeightWithSpacing()) });
835  ImGui::Text("%s", "Target Height:");
836  if (ImGui::IsItemHovered())
837  {
838  ImGui::SetTooltip("%s", "The height of the rectangle in millimeter inside the specific target");
839  }
840 
841  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 35 + ImGui::GetTextLineHeightWithSpacing()) });
842  id = to_string() << "##target_height_" << index;
843  ImGui::PushItemWidth(width - 145.0f);
845  std::string th = to_string() << target_height;
846  memcpy(buff, th.c_str(), th.size() + 1);
847  if (ImGui::InputText(id.c_str(), buff, std::max((int)th.size() + 1, 10)))
848  {
849  std::stringstream ss;
850  ss << buff;
851  ss >> target_height;
853  }
855 
856  ImGui::SetCursorScreenPos({ float(x + 9), float(y + height - 25) });
857  auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
860 
861  std::string back_button_name = to_string() << "Back" << "##tare" << index;
862  if (ImGui::Button(back_button_name.c_str(), { float(60), 20.f }))
863  {
865  update_state = update_state_prev;
866  if (get_manager()._sub->s->supports(RS2_OPTION_EMITTER_ENABLED))
867  get_manager()._sub->s->set_option(RS2_OPTION_EMITTER_ENABLED, get_manager().laser_status_prev);
868  }
869 
870  ImGui::SetCursorScreenPos({ float(x + 85), float(y + height - 25) });
871  std::string button_name = to_string() << "Calculate" << "##tare" << index;
872  if (ImGui::Button(button_name.c_str(), { float(bar_width - 70), 20.f }))
873  {
874  get_manager().restore_workspace([this](std::function<void()> a) { a(); });
875  get_manager().reset();
876  get_manager().retry_times = 0;
878  auto _this = shared_from_this();
879  auto invoke = [_this](std::function<void()> action) {
880  _this->invoke(action);
881  };
882  get_manager().start(invoke);
883  update_state = RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_IN_PROCESS;
884  enable_dismiss = false;
885  }
886 
888 
889  if (ImGui::IsItemHovered())
890  {
891  ImGui::SetTooltip("%s", "Begin Calculating Tare Calibration Ground Truth");
892  }
893  }
894  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_IN_PROCESS)
895  {
896  enable_dismiss = false;
897  ImGui::Text("%s", "Calculating ground truth is in process...\nKeep camera stationary pointing at the target");
898  }
899  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_COMPLETE)
900  {
902  update_state = update_state_prev;
903  if (get_manager()._sub->s->supports(RS2_OPTION_EMITTER_ENABLED))
904  get_manager()._sub->s->set_option(RS2_OPTION_EMITTER_ENABLED, get_manager().laser_status_prev);
905  }
906  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_FAILED)
907  {
908  ImGui::Text("%s", _error_message.c_str());
909 
910  auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
911 
914 
915  std::string button_name = to_string() << "Retry" << "##retry" << index;
916 
917  ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) });
918  if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f }))
919  {
920  get_manager().restore_workspace([this](std::function<void()> a) { a(); });
921  get_manager().reset();
922  auto _this = shared_from_this();
923  auto invoke = [_this](std::function<void()> action) {
924  _this->invoke(action);
925  };
926  get_manager().start(invoke);
927  update_state = RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_IN_PROCESS;
928  enable_dismiss = false;
929  }
930 
932 
933  if (ImGui::IsItemHovered())
934  {
935  ImGui::SetTooltip("%s", "Retry calculating ground truth");
936  }
937  }
938  else if (update_state == RS2_CALIB_STATE_TARE_INPUT || update_state == RS2_CALIB_STATE_TARE_INPUT_ADVANCED)
939  {
940  ImGui::PushStyleColor(ImGuiCol_Text, update_state != RS2_CALIB_STATE_TARE_INPUT_ADVANCED ? light_grey : light_blue);
941  ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, update_state != RS2_CALIB_STATE_TARE_INPUT_ADVANCED ? light_grey : light_blue);
942 
943  if (ImGui::Button(u8"\uf0d7"))
944  {
945  if (update_state == RS2_CALIB_STATE_TARE_INPUT_ADVANCED)
946  update_state = RS2_CALIB_STATE_TARE_INPUT;
947  else
948  update_state = RS2_CALIB_STATE_TARE_INPUT_ADVANCED;
949  }
950 
951  if (ImGui::IsItemHovered())
952  {
953  if (update_state == RS2_CALIB_STATE_TARE_INPUT)
954  ImGui::SetTooltip("%s", "More Options...");
955  else
956  ImGui::SetTooltip("%s", "Less Options...");
957  }
958 
960  if (update_state == RS2_CALIB_STATE_TARE_INPUT_ADVANCED)
961  {
962  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 33) });
963  ImGui::Text("%s", "Avg Step Count:");
964  if (ImGui::IsItemHovered())
965  {
966  ImGui::SetTooltip("%s", "Number of frames to average, Min = 1, Max = 30, Default = 20");
967  }
968  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 30) });
969 
970  std::string id = to_string() << "##avg_step_count_" << index;
972  ImGui::SliderInt(id.c_str(), &get_manager().average_step_count, 1, 30);
974 
975  //-------------------------
976 
977  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 38 + ImGui::GetTextLineHeightWithSpacing()) });
978  ImGui::Text("%s", "Step Count:");
979  if (ImGui::IsItemHovered())
980  {
981  ImGui::SetTooltip("%s", "Max iteration steps, Min = 5, Max = 30, Default = 20");
982  }
983  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 35 + ImGui::GetTextLineHeightWithSpacing()) });
984 
985  id = to_string() << "##step_count_" << index;
986 
988  ImGui::SliderInt(id.c_str(), &get_manager().step_count, 1, 30);
990 
991  //-------------------------
992 
993  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 43 + 2 * ImGui::GetTextLineHeightWithSpacing()) });
994  ImGui::Text("%s", "Accuracy:");
995  if (ImGui::IsItemHovered())
996  {
997  ImGui::SetTooltip("%s", "Subpixel accuracy level, Very high = 0 (0.025%), High = 1 (0.05%), Medium = 2 (0.1%), Low = 3 (0.2%), Default = Very high (0.025%)");
998  }
999 
1000  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 40 + 2 * ImGui::GetTextLineHeightWithSpacing()) });
1001 
1002  id = to_string() << "##accuracy_" << index;
1003 
1004  std::vector<std::string> vals{ "Very High", "High", "Medium", "Low" };
1005  std::vector<const char*> vals_cstr;
1006  for (auto&& s : vals) vals_cstr.push_back(s.c_str());
1007 
1008  ImGui::PushItemWidth(width - 145.f);
1009  ImGui::Combo(id.c_str(), &get_manager().accuracy, vals_cstr.data(), int(vals.size()));
1010 
1011  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 35 + ImGui::GetTextLineHeightWithSpacing()) });
1012 
1014 
1015  draw_intrinsic_extrinsic(x, y + 3 * int(ImGui::GetTextLineHeightWithSpacing()) - 10);
1016 
1017  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 52 + 4 * ImGui::GetTextLineHeightWithSpacing()) });
1018  id = to_string() << "Apply High-Accuracy Preset##apply_preset_" << index;
1019  ImGui::Checkbox(id.c_str(), &get_manager().apply_preset);
1020  }
1021 
1022  if (update_state == RS2_CALIB_STATE_TARE_INPUT_ADVANCED)
1023  {
1024  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 60 + 5 * ImGui::GetTextLineHeightWithSpacing()) });
1025  ImGui::Text("%s", "Ground Truth(mm):");
1026  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 58 + 5 * ImGui::GetTextLineHeightWithSpacing()) });
1027  }
1028  else
1029  {
1030  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 33) });
1031  ImGui::Text("%s", "Ground Truth (mm):");
1032  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 30) });
1033  }
1034 
1035  if (ImGui::IsItemHovered())
1036  ImGui::SetTooltip("%s", "Distance in millimeter to the flat wall, between 60 and 10000.");
1037 
1038  std::string id = to_string() << "##ground_truth_for_tare" << index;
1039  get_manager().ground_truth = config_file::instance().get_or_default(configurations::viewer::ground_truth_r, 1200.0f);
1040 
1041  std::string gt = to_string() << get_manager().ground_truth;
1042  const int MAX_SIZE = 256;
1043  char buff[MAX_SIZE];
1044  memcpy(buff, gt.c_str(), gt.size() + 1);
1045 
1046  ImGui::PushItemWidth(width - 196.f);
1047  if (ImGui::InputText(id.c_str(), buff, std::max((int)gt.size() + 1, 10)))
1048  {
1049  std::stringstream ss;
1050  ss << buff;
1051  ss >> get_manager().ground_truth;
1052  }
1054 
1056 
1057  auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
1058 
1061 
1062  std::string get_button_name = to_string() << "Get" << "##tare" << index;
1063  if (update_state == RS2_CALIB_STATE_TARE_INPUT_ADVANCED)
1064  ImGui::SetCursorScreenPos({ float(x + width - 52), float(y + 58 + 5 * ImGui::GetTextLineHeightWithSpacing()) });
1065  else
1066  ImGui::SetCursorScreenPos({ float(x + width - 52), float(y + 30) });
1067 
1068  if (ImGui::Button(get_button_name.c_str(), { 42.0f, 20.f }))
1069  {
1070  if (get_manager()._sub->s->supports(RS2_OPTION_EMITTER_ENABLED))
1071  get_manager().laser_status_prev = get_manager()._sub->s->get_option(RS2_OPTION_EMITTER_ENABLED);
1072 
1073  update_state_prev = update_state;
1074  update_state = RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH;
1075  }
1076 
1077  if (ImGui::IsItemHovered())
1078  ImGui::SetTooltip("%s", "Calculate ground truth for the specific target");
1079 
1080  std::string button_name = to_string() << "Calibrate" << "##tare" << index;
1081 
1082  ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) });
1083  if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f }))
1084  {
1085  get_manager().restore_workspace([](std::function<void()> a) { a(); });
1086  get_manager().reset();
1087  get_manager().retry_times = 0;
1089  auto _this = shared_from_this();
1090  auto invoke = [_this](std::function<void()> action) {
1091  _this->invoke(action);
1092  };
1093  get_manager().start(invoke);
1094  update_state = RS2_CALIB_STATE_CALIB_IN_PROCESS;
1095  enable_dismiss = false;
1096  }
1097 
1099 
1100  if (ImGui::IsItemHovered())
1101  {
1102  ImGui::SetTooltip("%s", "Begin Tare Calibration");
1103  }
1104  }
1105  else if (update_state == RS2_CALIB_STATE_SELF_INPUT)
1106  {
1107  ImGui::SetCursorScreenPos({ float(x + 9), float(y + 33) });
1108  ImGui::Text("%s", "Speed:");
1109 
1110  ImGui::SetCursorScreenPos({ float(x + 135), float(y + 30) });
1111 
1112  std::string id = to_string() << "##speed_" << index;
1113 
1114  std::vector<const char*> vals_cstr;
1116  {
1117  std::vector<std::string> vals{ "Fast", "Slow", "White Wall" };
1118  for (auto&& s : vals) vals_cstr.push_back(s.c_str());
1119 
1120  ImGui::PushItemWidth(width - 145.f);
1121  ImGui::Combo(id.c_str(), &get_manager().speed_fl, vals_cstr.data(), int(vals.size()));
1123 
1124  }
1125  else
1126  {
1127  std::vector<std::string> vals{ "Very Fast", "Fast", "Medium", "Slow", "White Wall" };
1128  for (auto&& s : vals) vals_cstr.push_back(s.c_str());
1129 
1130  ImGui::PushItemWidth(width - 145.f);
1131  ImGui::Combo(id.c_str(), &get_manager().speed, vals_cstr.data(), int(vals.size()));
1133  }
1134 
1136  draw_intrinsic_extrinsic(x, y);
1137 
1139  {
1140  float tmp_y = (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB ?
1141  float(y + 40 + 2 * ImGui::GetTextLineHeightWithSpacing()) : float(y + 35 + ImGui::GetTextLineHeightWithSpacing()));
1142  ImGui::SetCursorScreenPos({ float(x + 9), tmp_y });
1143  id = to_string() << "##restore_" << index;
1144  bool restore = (get_manager().adjust_both_sides == 1);
1145  if (ImGui::Checkbox("Adjust both sides focal length", &restore))
1146  get_manager().adjust_both_sides = (restore ? 1 : 0);
1147  if (ImGui::IsItemHovered())
1148  ImGui::SetTooltip("%s", "check = adjust both sides, uncheck = adjust right side only");
1149  }
1150 
1151  float tmp_y = (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB ?
1152  float(y + 45 + 3 * ImGui::GetTextLineHeightWithSpacing()) : float(y + 40 + 2 * ImGui::GetTextLineHeightWithSpacing()));
1153  ImGui::SetCursorScreenPos({ float(x + 9), tmp_y });
1154  if (ImGui::RadioButton("OCC", (int*)&(get_manager().action), 1))
1156  if (ImGui::IsItemHovered())
1157  ImGui::SetTooltip("%s", "On-Chip Calibration");
1158 
1159  ImGui::SetCursorScreenPos({ float(x + 135), tmp_y });
1160  if (ImGui::RadioButton("OCC Extended", (int *)&(get_manager().action), 0))
1162  if (ImGui::IsItemHovered())
1163  ImGui::SetTooltip("%s", "On-Chip Calibration Extended");
1164 
1165  auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
1168 
1169  std::string button_name = to_string() << "Calibrate" << "##self" << index;
1170 
1171  ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) });
1172  if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f }))
1173  {
1174  get_manager().restore_workspace([this](std::function<void()> a) { a(); });
1175  get_manager().reset();
1176  get_manager().retry_times = 0;
1177  auto _this = shared_from_this();
1178  auto invoke = [_this](std::function<void()> action) {_this->invoke(action);};
1179  get_manager().start(invoke);
1180  update_state = RS2_CALIB_STATE_CALIB_IN_PROCESS;
1181  enable_dismiss = false;
1182  }
1183 
1185 
1186  if (ImGui::IsItemHovered())
1187  ImGui::SetTooltip("%s", "Begin On-Chip Calibration");
1188  }
1189  else if (update_state == RS2_CALIB_STATE_FAILED)
1190  {
1193  {
1194  if (get_manager().retry_times < 3)
1195  {
1196  get_manager().restore_workspace([](std::function<void()> a){ a(); });
1197  get_manager().reset();
1198  ++get_manager().retry_times;
1199  get_manager().toggle = true;
1200 
1201  auto _this = shared_from_this();
1202  auto invoke = [_this](std::function<void()> action) {_this->invoke(action);};
1203  get_manager().start(invoke);
1204  update_state = RS2_CALIB_STATE_CALIB_IN_PROCESS;
1205  enable_dismiss = false;
1206  }
1207  else
1208  {
1209  ImGui::Text("%s", (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_FL_CALIB ? "OCC FL calibraton cannot work with this camera!" : "OCC Extended calibraton cannot work with this camera!"));
1210  }
1211  }
1212  else
1213  {
1214  ImGui::Text("%s", _error_message.c_str());
1215 
1216  auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
1217 
1220 
1221  std::string button_name = to_string() << "Retry" << "##retry" << index;
1222  ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) });
1223  if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f }))
1224  {
1225  get_manager().restore_workspace([](std::function<void()> a) { a(); });
1226  get_manager().reset();
1227  auto _this = shared_from_this();
1228  auto invoke = [_this](std::function<void()> action) {
1229  _this->invoke(action);
1230  };
1231  get_manager().start(invoke);
1232  update_state = RS2_CALIB_STATE_CALIB_IN_PROCESS;
1233  enable_dismiss = false;
1234  }
1235 
1237 
1238  if (ImGui::IsItemHovered())
1239  ImGui::SetTooltip("%s", "Retry on-chip calibration process");
1240  }
1241  }
1242  else if (update_state == RS2_CALIB_STATE_CALIB_COMPLETE)
1243  {
1244  auto health = get_manager().get_health();
1245 
1246  auto recommend_keep = fabs(health) < 0.25f;
1248  recommend_keep = fabs(health) < 0.15f;
1249 
1250  float health_1 = -1.0f;
1251  float health_2 = -1.0f;
1252  bool recommend_keep_1 = false;
1253  bool recommend_keep_2 = false;
1255  {
1256  health_1 = get_manager().get_health_1();
1257  health_2 = get_manager().get_health_2();
1258  recommend_keep_1 = fabs(health_1) < 0.25f;
1259  recommend_keep_2 = fabs(health_2) < 0.15f;
1260  recommend_keep = (recommend_keep_1 && recommend_keep_2);
1261  }
1262 
1263  ImGui::SetCursorScreenPos({ float(x + 10), float(y + 33) });
1264 
1265  if (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_TARE_CALIB)
1266  {
1267  ImGui::Text("%s", "Tare calibration complete:");
1268  }
1270  {
1271  ImGui::Text("%s", "Health-Check: ");
1272 
1273  std::stringstream ss_1;
1274  ss_1 << std::fixed << std::setprecision(2) << health_1;
1275  auto health_str = ss_1.str();
1276 
1277  std::string text_name = to_string() << "##notification_text_1_" << index;
1278 
1279  ImGui::SetCursorScreenPos({ float(x + 125), float(y + 30) });
1287  ImGui::InputTextMultiline(text_name.c_str(), const_cast<char*>(health_str.c_str()), strlen(health_str.c_str()) + 1, { 66, ImGui::GetTextLineHeight() + 6 }, ImGuiInputTextFlags_ReadOnly);
1289 
1290  ImGui::SetCursorScreenPos({ float(x + 177), float(y + 33) });
1291 
1292  if (recommend_keep_1)
1293  {
1295  ImGui::Text("%s", "(Good)");
1296  }
1297  else if (fabs(health_1) < 0.75f)
1298  {
1300  ImGui::Text("%s", "(Can be Improved)");
1301  }
1302  else
1303  {
1305  ImGui::Text("%s", "(Requires Calibration)");
1306  }
1308 
1309  if (ImGui::IsItemHovered())
1310  {
1311  ImGui::SetTooltip("%s", "OCC Health-Check captures how far camera calibration is from the optimal one\n"
1312  "[0, 0.25) - Good\n"
1313  "[0.25, 0.75) - Can be Improved\n"
1314  "[0.75, ) - Requires Calibration");
1315  }
1316 
1317  ImGui::SetCursorScreenPos({ float(x + 10), float(y + 38) + ImGui::GetTextLineHeightWithSpacing() });
1318  ImGui::Text("%s", "FL Health-Check: ");
1319 
1320  std::stringstream ss_2;
1321  ss_2 << std::fixed << std::setprecision(2) << health_2;
1322  health_str = ss_2.str();
1323 
1324  text_name = to_string() << "##notification_text_2_" << index;
1325 
1326  ImGui::SetCursorScreenPos({ float(x + 125), float(y + 35) + ImGui::GetTextLineHeightWithSpacing() });
1334  ImGui::InputTextMultiline(text_name.c_str(), const_cast<char*>(health_str.c_str()), strlen(health_str.c_str()) + 1, { 66, ImGui::GetTextLineHeight() + 6 }, ImGuiInputTextFlags_ReadOnly);
1336 
1337  ImGui::SetCursorScreenPos({ float(x + 175), float(y + 38) + ImGui::GetTextLineHeightWithSpacing() });
1338 
1339  if (recommend_keep_2)
1340  {
1342  ImGui::Text("%s", "(Good)");
1343  }
1344  else if (fabs(health_2) < 0.75f)
1345  {
1347  ImGui::Text("%s", "(Can be Improved)");
1348  }
1349  else
1350  {
1352  ImGui::Text("%s", "(Requires Calibration)");
1353  }
1355 
1356  if (ImGui::IsItemHovered())
1357  {
1358  ImGui::SetTooltip("%s", "OCC-FL Health-Check captures how far camera calibration is from the optimal one\n"
1359  "[0, 0.15) - Good\n"
1360  "[0.15, 0.75) - Can be Improved\n"
1361  "[0.75, ) - Requires Calibration");
1362  }
1363  }
1364  else
1365  {
1366  ImGui::Text("%s", (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_CALIB ? "Health-Check: " : "FL Health-Check: "));
1367 
1368  std::stringstream ss; ss << std::fixed << std::setprecision(2) << health;
1369  auto health_str = ss.str();
1370 
1371  std::string text_name = to_string() << "##notification_text_" << index;
1372 
1373  ImGui::SetCursorScreenPos({ float(x + 125), float(y + 30) });
1381  ImGui::InputTextMultiline(text_name.c_str(), const_cast<char*>(health_str.c_str()), strlen(health_str.c_str()) + 1, { 66, ImGui::GetTextLineHeight() + 6 }, ImGuiInputTextFlags_ReadOnly);
1383 
1384  ImGui::SetCursorScreenPos({ float(x + 177), float(y + 33) });
1385 
1386  if (recommend_keep)
1387  {
1389  ImGui::Text("%s", "(Good)");
1390  }
1391  else if (fabs(health) < 0.75f)
1392  {
1394  ImGui::Text("%s", "(Can be Improved)");
1395  }
1396  else
1397  {
1399  ImGui::Text("%s", "(Requires Calibration)");
1400  }
1402 
1403  if (ImGui::IsItemHovered())
1404  {
1406  {
1407  ImGui::SetTooltip("%s", "Calibration Health-Check captures how far camera calibration is from the optimal one\n"
1408  "[0, 0.25) - Good\n"
1409  "[0.25, 0.75) - Can be Improved\n"
1410  "[0.75, ) - Requires Calibration");
1411  }
1412  else
1413  {
1414  ImGui::SetTooltip("%s", "Calibration Health-Check captures how far camera calibration is from the optimal one\n"
1415  "[0, 0.15) - Good\n"
1416  "[0.15, 0.75) - Can be Improved\n"
1417  "[0.75, ) - Requires Calibration");
1418  }
1419  }
1420  }
1421 
1422  auto old_fr = get_manager().get_metric(false).first;
1423  auto new_fr = get_manager().get_metric(true).first;
1424 
1425  auto old_rms = fabs(get_manager().get_metric(false).second);
1426  auto new_rms = fabs(get_manager().get_metric(true).second);
1427 
1428  auto fr_improvement = 100.f * ((new_fr - old_fr) / old_fr);
1429  auto rms_improvement = 100.f * ((old_rms - new_rms) / old_rms);
1430 
1431  std::string old_units = "mm";
1432  if (old_rms > 10.f)
1433  {
1434  old_rms /= 10.f;
1435  old_units = "cm";
1436  }
1437 
1438  std::string new_units = "mm";
1439  if (new_rms > 10.f)
1440  {
1441  new_rms /= 10.f;
1442  new_units = "cm";
1443  }
1444 
1445  // NOTE: Disabling metrics temporarily
1446  // TODO: Re-enable in future release
1447  if (/* fr_improvement > 1.f || rms_improvement > 1.f */ false)
1448  {
1449  std::string txt = to_string() << " Fill-Rate: " << std::setprecision(1) << std::fixed << new_fr << "%%";
1450  if (!use_new_calib)
1451  txt = to_string() << " Fill-Rate: " << std::setprecision(1) << std::fixed << old_fr << "%%\n";
1452 
1453  ImGui::SetCursorScreenPos({ float(x + 12), float(y + 90) });
1455  ImGui::Text("%s", static_cast<const char *>(textual_icons::check));
1456  ImGui::PopFont();
1457 
1458  ImGui::SetCursorScreenPos({ float(x + 35), float(y + 92) });
1459  ImGui::Text("%s", txt.c_str());
1460 
1461  if (use_new_calib)
1462  {
1463  ImGui::SameLine();
1464 
1466  txt = to_string() << " ( +" << std::fixed << std::setprecision(0) << fr_improvement << "%% )";
1467  ImGui::Text("%s", txt.c_str());
1469  }
1470 
1471  if (rms_improvement > 1.f)
1472  {
1473  if (use_new_calib)
1474  {
1475  txt = to_string() << " Noise Estimate: " << std::setprecision(2) << std::fixed << new_rms << new_units;
1476  }
1477  else
1478  {
1479  txt = to_string() << " Noise Estimate: " << std::setprecision(2) << std::fixed << old_rms << old_units;
1480  }
1481 
1482  ImGui::SetCursorScreenPos({ float(x + 12), float(y + 90 + ImGui::GetTextLineHeight() + 6) });
1484  ImGui::Text("%s", static_cast<const char *>(textual_icons::check));
1485  ImGui::PopFont();
1486 
1487  ImGui::SetCursorScreenPos({ float(x + 35), float(y + 92 + ImGui::GetTextLineHeight() + 6) });
1488  ImGui::Text("%s", txt.c_str());
1489 
1490  if (use_new_calib)
1491  {
1492  ImGui::SameLine();
1493 
1495  txt = to_string() << " ( -" << std::setprecision(0) << std::fixed << rms_improvement << "%% )";
1496  ImGui::Text("%s", txt.c_str());
1498  }
1499  }
1500  }
1501  else
1502  {
1503  ImGui::SetCursorScreenPos({ float(x + 7), (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB ? float(y + 105) + ImGui::GetTextLineHeightWithSpacing() : float(y + 100)) });
1504  ImGui::Text("%s", "Please compare new vs old calibration\nand decide if to keep or discard the result...");
1505  }
1506 
1507  ImGui::SetCursorScreenPos({ float(x + 20), (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB ? float(y + 70) + ImGui::GetTextLineHeightWithSpacing() : float(y + 60)) });
1508 
1509  if (ImGui::RadioButton("New", use_new_calib))
1510  {
1511  use_new_calib = true;
1512  get_manager().apply_calib(true);
1513  }
1514 
1515  ImGui::SetCursorScreenPos({ float(x + 150), (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB ? float(y + 70) + ImGui::GetTextLineHeightWithSpacing() : float(y + 60)) });
1516  if (ImGui::RadioButton("Original", !use_new_calib))
1517  {
1518  use_new_calib = false;
1519  get_manager().apply_calib(false);
1520  }
1521 
1522  auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
1523 
1524  if (!recommend_keep || get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_TARE_CALIB)
1525  {
1528  }
1529 
1530  std::string button_name = to_string() << "Apply New" << "##apply" << index;
1531  if (!use_new_calib) button_name = to_string() << "Keep Original" << "##original" << index;
1532 
1533  ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) });
1534  if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f }))
1535  {
1536  if (use_new_calib)
1537  {
1538  get_manager().keep();
1539  update_state = RS2_CALIB_STATE_COMPLETE;
1540  pinned = false;
1541  enable_dismiss = false;
1542  _progress_bar.last_progress_time = last_interacted = system_clock::now() + milliseconds(500);
1543  }
1544  else
1545  {
1546  dismiss(false);
1547  }
1548 
1549  get_manager().restore_workspace([](std::function<void()> a) { a(); });
1550  }
1551 
1552  if (!recommend_keep || get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_TARE_CALIB)
1554 
1555  if (ImGui::IsItemHovered())
1556  ImGui::SetTooltip("%s", "New calibration values will be saved in device");
1557  }
1558 
1560  }
1561  else
1562  {
1563  ImGui::Text("%s", "Calibration Complete");
1564 
1565  ImGui::SetCursorScreenPos({ float(x + 10), float(y + 35) });
1568  ImGui::Text("%s", txt.c_str());
1569  ImGui::PopFont();
1570 
1571  ImGui::SetCursorScreenPos({ float(x + 40), float(y + 35) });
1572 
1573  ImGui::Text("%s", "Camera Calibration Applied Successfully");
1574  }
1575 
1576  ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) });
1577 
1578  if (update_manager)
1579  {
1580  if (update_state == RS2_CALIB_STATE_INITIAL_PROMPT)
1581  {
1582  auto sat = 1.f + sin(duration_cast<milliseconds>(system_clock::now() - created_time).count() / 700.f) * 0.1f;
1585  std::string button_name = to_string() << "Health-Check" << "##health_check" << index;
1586 
1587  if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f }) || update_manager->started())
1588  {
1589  auto _this = shared_from_this();
1590  auto invoke = [_this](std::function<void()> action) {
1591  _this->invoke(action);
1592  };
1593 
1594  if (!update_manager->started()) update_manager->start(invoke);
1595 
1596  update_state = RS2_CALIB_STATE_CALIB_IN_PROCESS;
1597  enable_dismiss = false;
1598  _progress_bar.last_progress_time = system_clock::now();
1599  }
1601 
1602  if (ImGui::IsItemHovered())
1603  {
1604  ImGui::SetTooltip("%s", "Keep the camera pointing at an object or a wall");
1605  }
1606  }
1607  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_IN_PROCESS)
1608  {
1609  if (update_manager->done())
1610  {
1611  update_state = RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_COMPLETE;
1612  enable_dismiss = true;
1613  }
1614 
1615  if (update_manager->failed())
1616  {
1617  update_manager->check_error(_error_message);
1618  update_state = RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_FAILED;
1619  enable_dismiss = true;
1620  }
1621 
1622  draw_progress_bar(win, bar_width);
1623  }
1624  else if (update_state == RS2_CALIB_STATE_CALIB_IN_PROCESS)
1625  {
1626  if (update_manager->done())
1627  {
1628  update_state = RS2_CALIB_STATE_CALIB_COMPLETE;
1629  enable_dismiss = true;
1630  get_manager().apply_calib(true);
1631  use_new_calib = true;
1632  }
1633 
1634  if (!expanded)
1635  {
1636  if (update_manager->failed())
1637  {
1638  update_manager->check_error(_error_message);
1639  update_state = RS2_CALIB_STATE_FAILED;
1640  enable_dismiss = true;
1641  //pinned = false;
1642  //dismiss(false);
1643  }
1644 
1645  draw_progress_bar(win, bar_width);
1646 
1647  ImGui::SetCursorScreenPos({ float(x + width - 105), float(y + height - 25) });
1648 
1649  string id = to_string() << "Expand" << "##" << index;
1651  if (ImGui::Button(id.c_str(), { 100, 20 }))
1652  {
1653  expanded = true;
1654  }
1655 
1657  }
1658  }
1659  }
1660  }
1661 
1663  {
1664  get_manager().update_last_used();
1665 
1666  if (!use_new_calib && get_manager().done())
1667  get_manager().apply_calib(false);
1668 
1669  get_manager().restore_workspace([](std::function<void()> a){ a(); });
1670 
1671  if (update_state != RS2_CALIB_STATE_TARE_INPUT)
1672  update_state = RS2_CALIB_STATE_INITIAL_PROMPT;
1673  get_manager().reset();
1674 
1676  }
1677 
1679  {
1680  if (update_manager->started() && update_state == RS2_CALIB_STATE_INITIAL_PROMPT)
1681  update_state = RS2_CALIB_STATE_CALIB_IN_PROCESS;
1682 
1686 
1687  ImGui::PushStyleColor(ImGuiCol_WindowBg, { 0, 0, 0, 0 });
1691 
1695 
1696  std::string title;
1698  title = "On-Chip Focal Length Calibration";
1700  title = "On-Chip Calibration Extended";
1701  else
1702  title = "On-Chip Calibration";
1703  if (update_manager->failed()) title += " Failed";
1704 
1705  ImGui::OpenPopup(title.c_str());
1706  if (ImGui::BeginPopupModal(title.c_str(), nullptr, flags))
1707  {
1708  ImGui::SetCursorPosX(200);
1709  std::string progress_str = to_string() << "Progress: " << update_manager->get_progress() << "%";
1710  ImGui::Text("%s", progress_str.c_str());
1711 
1713 
1714  draw_progress_bar(win, 490);
1715 
1717  auto s = update_manager->get_log();
1718  ImGui::InputTextMultiline("##autocalib_log", const_cast<char*>(s.c_str()),
1721 
1722  ImGui::SetCursorPosX(190);
1723  if (visible || update_manager->done() || update_manager->failed())
1724  {
1725  if (ImGui::Button("OK", ImVec2(120, 0)))
1726  {
1727  if (update_manager->failed())
1728  update_state = RS2_CALIB_STATE_FAILED;
1729 
1730  expanded = false;
1732  }
1733  }
1734  else
1735  {
1741  ImGui::Button("OK", ImVec2(120, 0));
1743  }
1744 
1745  ImGui::EndPopup();
1746  }
1747 
1748  ImGui::PopStyleVar(3);
1750 
1751  error_message = "";
1752  }
1753 
1755  {
1756  if (update_state == RS2_CALIB_STATE_COMPLETE) return 65;
1757  else if (update_state == RS2_CALIB_STATE_INITIAL_PROMPT) return 120;
1758  else if (update_state == RS2_CALIB_STATE_CALIB_COMPLETE)
1759  {
1760  if (get_manager().allow_calib_keep()) return (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB ? 190 : 170);
1761  else return 80;
1762  }
1763  else if (update_state == RS2_CALIB_STATE_SELF_INPUT) return (get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB ? 160 : 140);
1764  else if (update_state == RS2_CALIB_STATE_TARE_INPUT) return 85;
1765  else if (update_state == RS2_CALIB_STATE_TARE_INPUT_ADVANCED) return 210;
1766  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH) return 110;
1767  else if (update_state == RS2_CALIB_STATE_GET_TARE_GROUND_TRUTH_FAILED) return 115;
1768  else if (update_state == RS2_CALIB_STATE_FAILED) return ((get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_OB_CALIB || get_manager().action == on_chip_calib_manager::RS2_CALIB_ACTION_ON_CHIP_FL_CALIB) ? (get_manager().retry_times < 3 ? 0 : 80) : 110);
1769  else return 100;
1770  }
1771 
1773  {
1775 
1777 
1778  ImVec4 c;
1779 
1780  if (update_state == RS2_CALIB_STATE_COMPLETE)
1781  {
1782  c = alpha(saturate(light_blue, 0.7f), 1 - t);
1784  }
1785  else if (update_state == RS2_CALIB_STATE_FAILED)
1786  {
1787  c = alpha(dark_red, 1 - t);
1789  }
1790  else
1791  {
1792  c = alpha(sensor_bg, 1 - t);
1794  }
1795  }
1796 
1798  std::shared_ptr<on_chip_calib_manager> manager, bool exp)
1799  : process_notification_model(manager)
1800  {
1801  enable_expand = false;
1802  enable_dismiss = true;
1803  expanded = exp;
1804  if (expanded) visible = false;
1805 
1806  message = name;
1809 
1810  pinned = true;
1811  }
1812 
1813  int rect_calculator::calculate(const rs2_frame* frame_ref, float rect_sides[4])
1814  {
1815  static int reset_counter = 0;
1816  if (reset_counter > _reset_limit)
1817  {
1818  reset_counter = 0;
1819  _rec_idx = 0;
1820  _rec_num = 0;
1821  }
1822 
1823  int ret = 0;
1824  rs2_error* e = nullptr;
1825  rs2_extract_target_dimensions(frame_ref, RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES, _rec_sides[_rec_idx], 4, &e);
1826  if (e == nullptr)
1827  {
1828  ret = 1;
1829  reset_counter = 0;
1830  _rec_idx = (++_rec_idx) % _frame_num;
1831  ++_rec_num;
1832 
1833  if (_rec_num == _frame_num)
1834  {
1835  ret = 2;
1836  calculate_rect_sides(rect_sides);
1837  --_rec_num;
1838  }
1839  }
1840  else
1841  ++reset_counter;
1842 
1843  return ret;
1844  }
1845 
1846  void rect_calculator::calculate_rect_sides(float rect_sides[4])
1847  {
1848  for (int i = 0; i < 4; ++i)
1849  rect_sides[i] = _rec_sides[0][i];
1850 
1851  for (int j = 1; j < _frame_num; ++j)
1852  {
1853  for (int i = 0; i < 4; ++i)
1854  rect_sides[i] += _rec_sides[j][i];
1855  }
1856 
1857  for (int i = 0; i < 4; ++i)
1858  rect_sides[i] /= _frame_num;
1859  }
1860 }
IMGUI_API void PushStyleVar(ImGuiStyleVar idx, float val)
Definition: imgui.cpp:4650
static const ImVec4 transparent
Definition: model-views.h:44
GLenum GLuint GLenum GLsizei const GLchar * message
std::pair< float, float > get_depth_metrics(invoker invoke)
static const ImVec4 white
Definition: model-views.h:45
IMGUI_API void AddRectFilled(const ImVec2 &a, const ImVec2 &b, ImU32 col, float rounding=0.0f, int rounding_corners=0x0F)
Definition: imgui_draw.cpp:814
virtual void set_color_scheme(float t) const
GLboolean GLboolean GLboolean b
GLint y
IMGUI_API bool RadioButton(const char *label, bool active)
Definition: imgui.cpp:7332
int calculate(const rs2_frame *frame_ref, float rect_sides[4])
GLenum GLuint GLenum severity
snapshot_metrics analyze_depth_image(const rs2::video_frame &frame, float units, float baseline_mm, const rs2_intrinsics *intrin, rs2::region_of_interest roi, const int ground_truth_mm, bool plane_fit_present, std::vector< single_metric_data > &samples, bool record, callback_type callback)
IMGUI_API void SetTooltip(const char *fmt,...) IM_PRINTFARGS(1)
Definition: imgui.cpp:3288
void draw_dismiss(ux_window &win, int x, int y) override
rs2_frame * get() const
Definition: rs_frame.hpp:590
GLuint const GLchar * name
ImVec4 saturate(const ImVec4 &a, float f)
std::shared_ptr< rs2::asynchronous_syncer > dev_syncer
Definition: model-views.h:796
void set_color_scheme(float t) const override
GLdouble s
static const char * target_width_r
Definition: model-views.h:149
IMGUI_API bool InputTextMultiline(const char *label, char *buf, size_t buf_size, const ImVec2 &size=ImVec2(0, 0), ImGuiInputTextFlags flags=0, ImGuiTextEditCallback callback=NULL, void *user_data=NULL)
Definition: imgui.cpp:8223
GLfloat GLfloat p
Definition: glext.h:12687
static const ImVec4 light_grey
Definition: model-views.h:40
Definition: imgui.h:88
std::vector< uint8_t > safe_send_command(const std::vector< uint8_t > &cmd, const std::string &name)
void set_calibration_table(const calibration_table &calibration)
Definition: rs_device.hpp:546
static config_file & instance()
Definition: rs-config.cpp:80
a class to store JSON values
Definition: json.hpp:221
static const ImVec4 light_blue
Definition: model-views.h:38
rs2::depth_frame fetch_depth_frame(invoker invoke)
stream_profile get_profile() const
Definition: rs_frame.hpp:557
std::map< int, stream_model > streams
Definition: viewer.h:125
std::function< void(frame_interface *)> on_frame
Definition: streaming.h:164
void apply_calib(bool use_new)
UINT8_TYPE u8
Definition: sqlite3.c:11450
static const textual_icon throphy
Definition: model-views.h:258
def progress(args)
Definition: log.py:43
std::vector< std::pair< float, float > > _metrics
Definition: cah-model.h:10
GLdouble GLdouble GLdouble w
std::vector< uint8_t > _old_calib
GLsizei const GLchar *const * string
std::atomic< bool > synchronization_enable
Definition: viewer.h:158
GLuint GLuint stream
Definition: glext.h:1790
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
GLint limit
Definition: glext.h:9964
void stop_viewer(invoker invoke)
e
Definition: rmse.py:177
point
Definition: rmse.py:166
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)
Definition: imgui.cpp:8216
IMGUI_API bool SliderInt(const char *label, int *v, int v_min, int v_max, const char *display_format="%.0f", bool render_bg=false)
Definition: imgui.cpp:6687
std::shared_ptr< notifications_model > not_model
Definition: viewer.h:133
std::shared_ptr< subdevice_ui_selection > _ui
GLuint index
GLdouble t
GLboolean GLboolean GLboolean GLboolean a
T get_or_default(const char *key, T def) const
Definition: rs-config.h:65
Definition: parser.hpp:154
std::function< void(std::function< void()>)> invoker
std::vector< uint8_t > _new_calib
std::pair< float, float > get_metric(bool use_new)
IMGUI_API void SameLine(float pos_x=0.0f, float spacing_w=-1.0f)
Definition: imgui.cpp:9246
GLdouble f
IMGUI_API ImDrawList * GetWindowDrawList()
Definition: imgui.cpp:5045
IMGUI_API void PopStyleVar(int count=1)
Definition: imgui.cpp:4675
void try_start_viewer(int w, int h, int fps, invoker invoke)
static const ImVec4 regular_blue
Definition: model-views.h:39
const GLubyte * c
Definition: glext.h:12690
GLuint counter
Definition: glext.h:5684
void draw_expanded(ux_window &win, std::string &error_message) override
GLdouble x
unsigned int uint32_t
Definition: stdint.h:80
virtual void dismiss(bool snooze)
Definition: notifications.h:61
GLint GLsizei GLsizei height
autocalib_notification_model(std::string name, std::shared_ptr< on_chip_calib_manager > manager, bool expaned)
GLint GLint GLsizei GLint GLenum format
void draw_content(ux_window &win, int x, int y, float t, std::string &error_message) override
static const ImVec4 sensor_bg
Definition: model-views.h:51
GLbitfield flags
def find(dir, mask)
Definition: file.py:25
static const textual_icon check
Definition: model-views.h:260
IMGUI_API void SetCursorPosX(float x)
Definition: imgui.cpp:5101
static const char * last_calib_notice
Definition: model-views.h:155
GLint j
static const ImVec4 sensor_header_light_blue
Definition: model-views.h:50
IMGUI_API void PushItemWidth(float item_width)
Definition: imgui.cpp:4486
IMGUI_API void Text(const char *fmt,...) IM_PRINTFARGS(1)
Definition: imgui.cpp:5223
IMGUI_API bool Button(const char *label, const ImVec2 &size=ImVec2(0, 0))
Definition: imgui.cpp:5573
static const char * target_height_r
Definition: model-views.h:150
void begin_stream(std::shared_ptr< subdevice_model > d, rs2::stream_profile p)
Definition: viewer.cpp:3228
Definition: imgui.h:98
void log(std::string line)
std::array< float3, 4 > roi_rect
Definition: viewer.h:153
rs2_notification_category category
Definition: notifications.h:74
std::shared_ptr< subdevice_model > _sub
Definition: on-chip-calib.h:90
IMGUI_API void EndPopup()
Definition: imgui.cpp:3489
rs2_intrinsics get_intrinsics() const
Definition: rs_frame.hpp:238
static const ImVec4 dark_red
Definition: model-views.h:54
ImVec4 alpha(const ImVec4 &v, float a)
void rs2_extract_target_dimensions(const rs2_frame *frame, rs2_calib_target_type calib_type, float *target_dims, unsigned int target_dims_size, rs2_error **error)
Definition: rs.cpp:2402
IMGUI_API void PushStyleColor(ImGuiCol idx, const ImVec4 &col)
Definition: imgui.cpp:4599
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)
Definition: imgui.cpp:8418
IMGUI_API void PushFont(ImFont *font)
Definition: imgui.cpp:4539
post_processing_filters ppf
Definition: viewer.h:130
void write_calibration() const
Definition: rs_device.hpp:297
IMGUI_API float GetTextLineHeightWithSpacing()
Definition: imgui.cpp:5033
void draw_intrinsic_extrinsic(int x, int y)
void calculate_rect_sides(float rect_sides[4])
bool started() const
void set(const char *key, const char *value)
Definition: rs-config.cpp:15
IMGUI_API void PopItemWidth()
Definition: imgui.cpp:4507
IMGUI_API float GetTextLineHeight()
Definition: imgui.cpp:5027
GLsizei samples
static const ImVec4 yellowish
Definition: model-views.h:61
GLint GLsizei count
static const char * ground_truth_r
Definition: model-views.h:148
IMGUI_API bool BeginPopupModal(const char *name, bool *p_open=NULL, ImGuiWindowFlags extra_flags=0)
Definition: imgui.cpp:3465
IMGUI_API bool Checkbox(const char *label, bool *v)
Definition: imgui.cpp:7269
static const char * get_button_name(int button)
Definition: events.c:211
uint32_t ground_truth_r
Definition: viewer.h:137
bool start_viewer(int w, int h, int fps, invoker invoke)
bool done() const
IMGUI_API void SetCursorScreenPos(const ImVec2 &pos)
Definition: imgui.cpp:5127
static const ImVec4 redish
Definition: model-views.h:52
std::map< int, rs2::frame_queue > frames_queue
Definition: model-views.h:933
int i
GLuint res
Definition: glext.h:8856
void dismiss(bool snooze) override
void restore_workspace(invoker invoke)
signed int int32_t
Definition: stdint.h:77
IMGUI_API void CloseCurrentPopup()
Definition: imgui.cpp:3408
ImFont * get_large_font() const
Definition: ux-window.h:62
IMGUI_API void OpenPopup(const char *str_id)
Definition: imgui.cpp:3343
virtual void draw_dismiss(ux_window &win, int x, int y)
void fail(std::string error)
IMGUI_API void SetCursorPosY(float y)
Definition: imgui.cpp:5108
std::shared_ptr< syncer_model > syncer
Definition: viewer.h:129
GLdouble v
IMGUI_API float GetCursorPosY()
Definition: imgui.cpp:5088
IMGUI_API bool IsItemHovered()
Definition: imgui.cpp:3200
bool allow_calib_keep() const
Definition: on-chip-calib.h:35
struct rs2_frame rs2_frame
Definition: rs_types.h:261
GLint GLsizei width
GLdouble GLdouble GLint GLint const GLdouble * points
IMGUI_API void PopFont()
Definition: imgui.cpp:4549
static const int _frame_num
IMGUI_API void PopStyleColor(int count=1)
Definition: imgui.cpp:4609
T as() const
Definition: rs_device.hpp:129
auto_calib_action action
Definition: on-chip-calib.h:74
std::string to_string(T value)
void process_flow(std::function< void()> cleanup, invoker invoke) override


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:38