realsense-viewer.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 
5 #include <librealsense2/rs.hpp>
6 #ifdef NETWORK_DEVICE
8 #endif
9 #include "viewer.h"
10 #include "os.h"
11 #include "ux-window.h"
12 #include "fw-update-helper.h"
13 
14 #include <cstdarg>
15 #include <thread>
16 #include <iostream>
17 #include <algorithm>
18 #include <iomanip>
19 #include <map>
20 #include <sstream>
21 #include <array>
22 #include <mutex>
23 #include <set>
24 #include <regex>
25 
26 #include <imgui_internal.h>
27 
28 #ifdef INTERNAL_FW
29 #include "common/fw/D4XX_FW_Image.h"
30 #include "common/fw/SR3XX_FW_Image.h"
31 #include "common/fw/L5XX_FW_Image.h"
32 #else
33 #define FW_D4XX_FW_IMAGE_VERSION ""
34 #define FW_SR3XX_FW_IMAGE_VERSION ""
35 #define FW_L5XX_FW_IMAGE_VERSION ""
36 #endif // INTERNAL_FW
37 
38 #ifdef BUILD_EASYLOGGINGPP
39 #include <easylogging++.h>
40 #ifdef BUILD_SHARED_LIBS
41 // With static linkage, ELPP is initialized by librealsense, so doing it here will
42 // create errors. When we're using the shared .so/.dll, the two are separate and we have
43 // to initialize ours if we want to use the APIs!
45 #endif
46 #endif
47 
48 using namespace rs2;
49 using namespace rs400;
50 
51 #define MIN_IP_SIZE 7 //TODO: Ester - update size when host name is supported
52 
54 {
55  // Hide options from the Viewer application
57 }
58 
60 {
61 #ifdef NETWORK_DEVICE
62  rs2::net_device dev(address);
63  dev.add_to(ctx);
64  return true; // NEtwork device exists
65 #else
66  return false;
67 #endif
68 }
69 
71  std::string& error_message, viewer_model& viewer_model, const std::string& file)
72 {
73  bool was_loaded = false;
74  bool failed = false;
75  try
76  {
77  auto dev = ctx.load_device(file);
78  was_loaded = true;
79  device_models.emplace_back(new device_model(dev, error_message, viewer_model)); //Will cause the new device to appear in the left panel
80  if (auto p = dev.as<playback>())
81  {
82  auto filename = p.file_name();
83  p.set_status_changed_callback([&viewer_model, &device_models, filename](rs2_playback_status status)
84  {
85  if (status == RS2_PLAYBACK_STATUS_STOPPED)
86  {
87  auto it = std::find_if(device_models.begin(), device_models.end(),
88  [&](const std::unique_ptr<device_model>& dm) {
89  if (auto p = dm->dev.as<playback>())
90  return p.file_name() == filename;
91  return false;
92  });
93  if (it != device_models.end())
94  {
95  auto subs = (*it)->subdevices;
96  if ((*it)->_playback_repeat)
97  {
98  //Calling from different since playback callback is from reading thread
99  std::thread{ [subs, &viewer_model, it]()
100  {
101  if (!(*it)->dev_syncer)
102  (*it)->dev_syncer = viewer_model.syncer->create_syncer();
103 
104  for (auto&& sub : subs)
105  {
106  if (sub->streaming)
107  {
108  auto profiles = sub->get_selected_profiles();
109 
110  sub->play(profiles, viewer_model, (*it)->dev_syncer);
111  }
112  }
113  } }.detach();
114  }
115  else
116  {
117  for (auto&& sub : subs)
118  {
119  if (sub->streaming)
120  {
121  sub->stop(viewer_model.not_model);
122  }
123  }
124  }
125  }
126  }
127  });
128  }
129  }
130  catch (const error& e)
131  {
132  error_message = to_string() << "Failed to load file " << file << ". Reason: " << error_to_string(e);
133  failed = true;
134  }
135  catch (const std::exception& e)
136  {
137  error_message = to_string() << "Failed to load file " << file << ". Reason: " << e.what();
138  failed = true;
139  }
140  if (failed && was_loaded)
141  {
142  try { ctx.unload_device(file); }
143  catch (...) {}
144  }
145 }
146 
147 // This function is called every frame
148 // If between the frames there was an asyncronous connect/disconnect event
149 // the function will pick up on this and add the device to the viewer
150 bool refresh_devices(std::mutex& m,
151  context& ctx,
152  device_changes& devices_connection_changes,
153  std::vector<device>& current_connected_devices,
154  std::vector<std::pair<std::string, std::string>>& device_names,
155  device_models_list& device_models,
157  std::string& error_message)
158 {
159  event_information info({}, {});
160  if (!devices_connection_changes.try_get_next_changes(info))
161  return false;
162  try
163  {
164  //Remove disconnected
165  auto dev_itr = begin(current_connected_devices);
166  while (dev_itr != end(current_connected_devices))
167  {
168  auto dev = *dev_itr;
169  if (info.was_removed(dev))
170  {
171  //Notify change
172  viewer_model.not_model->add_notification({ get_device_name(dev).first + " Disconnected\n",
174 
175  //Remove from devices
176  auto dev_model_itr = std::find_if(begin(device_models), end(device_models),
177  [&](const std::unique_ptr<device_model>& other) { return get_device_name(other->dev) == get_device_name(dev); });
178 
179  if (dev_model_itr != end(device_models))
180  {
181  for (auto&& s : (*dev_model_itr)->subdevices)
182  s->streaming = false;
183 
184  dev_model_itr->reset();
185  device_models.erase(dev_model_itr);
186 
187  if (device_models.size() == 0)
188  {
189  viewer_model.ppf.depth_stream_active = false;
190 
191  // Stopping post processing filter rendering thread in case of disconnection
192  viewer_model.ppf.stop();
193  }
194  }
195  auto dev_name_itr = std::find(begin(device_names), end(device_names), get_device_name(dev));
196  if (dev_name_itr != end(device_names))
197  device_names.erase(dev_name_itr);
198 
199  dev_itr = current_connected_devices.erase(dev_itr);
200  continue;
201  }
202  ++dev_itr;
203  }
204 
205  //Add connected
206  static bool initial_refresh = true;
207  try
208  {
209  for (auto dev : info.get_new_devices())
210  {
211  auto dev_descriptor = get_device_name(dev);
212  device_names.push_back(dev_descriptor);
213 
214  bool added = false;
215  if (device_models.size() == 0 &&
216  dev.supports(RS2_CAMERA_INFO_NAME) && std::string(dev.get_info(RS2_CAMERA_INFO_NAME)) != "Platform Camera" && std::string(dev.get_info(RS2_CAMERA_INFO_NAME)).find("IP Device") == std::string::npos)
217  {
218  device_models.emplace_back(new device_model(dev, error_message, viewer_model));
219  viewer_model.not_model->add_log(to_string() << (*device_models.rbegin())->dev.get_info(RS2_CAMERA_INFO_NAME) << " was selected as a default device");
220  added = true;
221  }
222 
223  if (!initial_refresh)
224  {
225  if (added || dev.is<playback>())
226  viewer_model.not_model->add_notification({ dev_descriptor.first + " Connected\n",
227  RS2_LOG_SEVERITY_INFO, RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR });
228  else if (added || dev.supports(RS2_CAMERA_INFO_IP_ADDRESS))
229  viewer_model.not_model->add_notification({ dev_descriptor.first + " Connected\n",
230  RS2_LOG_SEVERITY_INFO, RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR });
231  else
232  viewer_model.not_model->add_notification({ dev_descriptor.first + " Connected\n",
234  [&device_models, &viewer_model, &error_message, dev] {
235  auto device = dev;
236  device_models.emplace_back(
237  new device_model(device, error_message, viewer_model));
238  });
239  }
240 
241  current_connected_devices.push_back(dev);
242  for (auto&& s : dev.query_sensors())
243  {
244  s.set_notifications_callback([&, dev_descriptor](const notification& n)
245  {
247  {
248  auto data = n.get_serialized_data();
249  if (!data.empty())
250  {
251  auto dev_model_itr = std::find_if(begin(device_models), end(device_models),
252  [&](const std::unique_ptr<device_model>& other)
253  { return get_device_name(other->dev) == dev_descriptor; });
254 
255  if (dev_model_itr == end(device_models))
256  return;
257 
258  (*dev_model_itr)->handle_hardware_events(data);
259  }
260  }
261  viewer_model.not_model->add_notification({ n.get_description(), n.get_severity(), n.get_category() });
262  });
263  }
264 
265 
266  }
267  }
268  catch (std::exception& e) {
269  std::stringstream s;
270  s << "Couldn't refresh devices - " << e.what();
271  log(RS2_LOG_SEVERITY_WARN, s.str().c_str());
272  }
273  initial_refresh = false;
274  }
275  catch (const error& e)
276  {
277  error_message = error_to_string(e);
278  }
279  catch (const std::exception& e)
280  {
281  error_message = e.what();
282  }
283  catch (...)
284  {
285  error_message = "Unknown error";
286  }
287  return true;
288 }
289 
290 
291 int main(int argc, const char** argv) try
292 {
293 
294 #ifdef BUILD_EASYLOGGINGPP
296 #endif
297 
298  context ctx;
299  ux_window window("Intel RealSense Viewer", ctx);
300 
301  // Create RealSense Context
302  device_changes devices_connection_changes(ctx);
303  std::vector<std::pair<std::string, std::string>> device_names;
304 
305  std::string error_message{ "" };
306  std::string label{ "" };
307 
308  std::shared_ptr<device_models_list> device_models = std::make_shared<device_models_list>();
309  device_model* device_to_remove = nullptr;
310  bool is_ip_device_connected = false;
311  std::string ip_address;
312 
314 
315  update_viewer_configuration(viewer_model);
316 
317  std::vector<device> connected_devs;
318  std::mutex m;
319 
320 #ifdef BUILD_EASYLOGGINGPP
321  std::weak_ptr<notifications_model> notifications = viewer_model.not_model;
323  [notifications]( rs2_log_severity severity, rs2::log_message const& msg )
324  {
325  if (auto not_model = notifications.lock())
326  {
327  not_model->output.add_log(severity, msg.filename(), (int)(msg.line_number()), msg.raw());
328  }
329  });
330 #endif
331 
332  window.on_file_drop = [&](std::string filename)
333  {
334  add_playback_device(ctx, *device_models, error_message, viewer_model, filename);
335  if (!error_message.empty())
336  {
337  viewer_model.not_model->add_notification({ error_message,
339  }
340  };
341 
342  for (int i = 1; i < argc; i++)
343  {
344  try
345  {
346  const char* arg = argv[i];
347  std::ifstream file(arg);
348  if (!file.good())
349  continue;
350 
351  add_playback_device(ctx, *device_models, error_message, viewer_model, arg);
352  }
353  catch (const rs2::error& e)
354  {
355  error_message = error_to_string(e);
356  }
357  catch (const std::exception& e)
358  {
359  error_message = e.what();
360  }
361  }
362 
363  window.on_load = [&]()
364  {
365  refresh_devices(m, ctx, devices_connection_changes, connected_devs,
366  device_names, *device_models, viewer_model, error_message);
367  return true;
368  };
369 
370  if (argc == 2)
371  {
372  try
373  {
374  is_ip_device_connected = add_remote_device(ctx, argv[1]);;
375  }
376  catch (std::runtime_error e)
377  {
378  error_message = e.what();
379  }
380  }
381 
382  // Closing the window
383  while (window)
384  {
385  auto device_changed = refresh_devices(m, ctx, devices_connection_changes, connected_devs,
386  device_names, *device_models, viewer_model, error_message);
387 
388  auto output_height = viewer_model.get_output_height();
389 
390  rect viewer_rect = { viewer_model.panel_width,
391  viewer_model.panel_y, window.width() -
392  viewer_model.panel_width,
393  window.height() - viewer_model.panel_y - output_height };
394 
395  // Flags for pop-up window - no window resize, move or collaps
399 
400  ImGui::SetNextWindowPos({ 0, 0 });
401  ImGui::SetNextWindowSize({ viewer_model.panel_width, viewer_model.panel_y });
402 
404  ImGui::Begin("Add Device Panel", nullptr, flags);
405 
407  ImGui::PushStyleColor(ImGuiCol_PopupBg, from_rgba(230, 230, 230, 255));
411  ImGui::SetNextWindowPos({ 0, viewer_model.panel_y });
412 
413  std::string add_source_button_text = to_string() << " " << textual_icons::plus_circle << " Add Source\t\t\t\t\t\t\t\t\t\t\t";
414  if (ImGui::Button(add_source_button_text.c_str(), { viewer_model.panel_width - 1, viewer_model.panel_y }))
415  ImGui::OpenPopup("select");
416 
417  auto new_devices_count = device_names.size() + 1;
418 
419  for (auto&& dev_model : *device_models)
420  {
421  auto connected_devs_itr = std::find_if(begin(connected_devs), end(connected_devs),
422  [&](const device& d) { return get_device_name(d) == get_device_name(dev_model->dev); });
423 
424  if (connected_devs_itr != end(connected_devs) || dev_model->dev.is<playback>())
425  new_devices_count--;
426  }
427 
428 
429  ImGui::PushFont(window.get_font());
430 
431  int multiline_devices_names = 0;
432  for (size_t i = 0; i < device_names.size(); i++)
433  {
434  if (device_names[i].first.find("\n") != std::string::npos)
435  {
436  bool show_device_in_list = true;
437  for (auto&& dev_model : *device_models)
438  {
439  if (get_device_name(dev_model->dev) == device_names[i])
440  {
441  show_device_in_list = false;
442  break;
443  }
444  }
445  if (show_device_in_list)
446  {
447  multiline_devices_names++;
448  }
449  }
450  }
451 
452  ImGui::SetNextWindowSize({ viewer_model.panel_width, 20.f * (new_devices_count + multiline_devices_names) + 8 + (is_ip_device_connected ? 0 : 20) });
453  if (ImGui::BeginPopup("select"))
454  {
456  ImGui::Columns(2, "DevicesList", false);
457  for (size_t i = 0; i < device_names.size(); i++)
458  {
459  bool skip = false;
460  for (auto&& dev_model : *device_models)
461  if (get_device_name(dev_model->dev) == device_names[i]) skip = true;
462  if (skip) continue;
463 
464  if (ImGui::Selectable(device_names[i].first.c_str(), false, ImGuiSelectableFlags_SpanAllColumns)/* || switch_to_newly_loaded_device*/)
465  {
466  try
467  {
468  auto dev = connected_devs[i];
469  device_models->emplace_back(new device_model(dev, error_message, viewer_model));
470  }
471  catch (const error& e)
472  {
473  error_message = error_to_string(e);
474  }
475  catch (const std::exception& e)
476  {
477  error_message = e.what();
478  }
479  }
480 
481  if (ImGui::IsItemHovered())
482  {
483  ImGui::PushStyleColor(ImGuiCol_Text, from_rgba(255, 255, 255, 255));
485  ImGui::Text("S/N: %s", device_names[i].second.c_str());
488  }
489  else
490  {
492  ImGui::Text("S/N: %s", device_names[i].second.c_str());
494  }
495 
496  }
497 
498  if (new_devices_count > 1) ImGui::Separator();
499 
500  if (ImGui::Selectable("Load Recorded Sequence", false, ImGuiSelectableFlags_SpanAllColumns))
501  {
502  if (auto ret = file_dialog_open(open_file, "ROS-bag\0*.bag\0", NULL, NULL))
503  {
504  add_playback_device(ctx, *device_models, error_message, viewer_model, ret);
505  }
506  }
508  ImGui::Text("%s", "");
510 
511  bool close_ip_popup = false;
512 
513  if (!is_ip_device_connected)
514  {
515  //ImGui::Separator();
517  {
518 #ifdef NETWORK_DEVICE
520  ImGui::OpenPopup("Network Device");
521 #else
522  error_message = "To enable RealSense device over network, please build the SDK with CMake flag -DBUILD_NETWORK_DEVICE=ON.\nThis binary distribution was built with network features disabled.";
523 #endif
524  }
525 
526  float width = 300;
527  float height = 125;
528  float posx = window.width() * 0.5f - width * 0.5f;
529  float posy = window.height() * 0.5f - height * 0.5f;
530  ImGui::SetNextWindowPos({ posx, posy });
531  ImGui::SetNextWindowSize({ width, height });
536 
538  {
541  ImGui::Text("Connect to a Linux system running rs-server");
542 
544 
545  static char ip_input[255];
546  std::copy(ip_address.begin(), ip_address.end(), ip_input);
547  ip_input[ip_address.size()] = '\0';
550  ImGui::Text("Device IP: ");
551  ImGui::SameLine();
552  //ImGui::SetCursorPosY(ImGui::GetCursorPosY() - 1);
555  {
557  }
559 
561  if (ImGui::InputText("##ip", ip_input, 255))
562  {
563  ip_address = ip_input;
564  }
566 
568 
570  ImGui::SetCursorPosX(width / 2 - 105);
571 
573  {
574  try
575  {
576  is_ip_device_connected = add_remote_device(ctx, ip_address);;
577  refresh_devices(m, ctx, devices_connection_changes, connected_devs, device_names, *device_models, viewer_model, error_message);
578  auto dev = connected_devs[connected_devs.size() - 1];
579  device_models->emplace_back(new device_model(dev, error_message, viewer_model));
581  }
582  catch (std::runtime_error e)
583  {
584  error_message = e.what();
585  }
586  ip_address = "";
587  close_ip_popup = true;
589  }
590  ImGui::SameLine();
591  ImGui::SetCursorPosX(width / 2 + 5);
592  if (ImGui::Button("Cancel", { 100.f, 25.f }) || ImGui::IsKeyDown(GLFW_KEY_ESCAPE))
593  {
594  ip_address = "";
595  close_ip_popup = true;
597  }
598  ImGui::EndPopup();
599  }
602 
604  ImGui::Text("%s", "");
606  }
607 
608  if (close_ip_popup)
609  {
611  close_ip_popup = false;
612  }
614  ImGui::EndPopup();
615  }
616  ImGui::PopFont();
621  ImGui::PopFont();
622 
623  ImGui::End();
625 
626 
627  viewer_model.show_top_bar(window, viewer_rect, *device_models);
628 
629  auto output_rect = rect{ viewer_model.panel_width,
630  window.height() - viewer_model.get_output_height(),
631  window.width() - viewer_model.panel_width, viewer_model.get_output_height() };
632 
633  viewer_model.not_model->output.draw(window, output_rect, *device_models);
634 
635  // Set window position and size
636  ImGui::SetNextWindowPos({ 0, viewer_model.panel_y });
637  ImGui::SetNextWindowSize({ viewer_model.panel_width, window.height() - viewer_model.panel_y });
640 
641  // *********************
642  // Creating window menus
643  // *********************
644  ImGui::Begin("Control Panel", nullptr, flags | ImGuiWindowFlags_AlwaysVerticalScrollbar);
645 
646  if (device_models->size() > 0)
647  {
648  std::vector<std::function<void()>> draw_later;
649  auto windows_width = ImGui::GetContentRegionMax().x;
650 
651  for (auto&& dev_model : *device_models)
652  {
653  dev_model->draw_controls(viewer_model.panel_width, viewer_model.panel_y,
654  window, error_message, device_to_remove, viewer_model, windows_width, draw_later);
655  }
656  if (viewer_model.ppf.is_rendering())
657  {
658  if (!std::any_of(device_models->begin(), device_models->end(),
659  [](const std::unique_ptr<device_model>& dm)
660  {
661  return dm->is_streaming();
662  }))
663  {
664  // Stopping post processing filter rendering thread
665  viewer_model.ppf.stop();
666  }
667  }
668 
669  ImGui::SetContentRegionWidth(windows_width);
670 
672  auto h = ImGui::GetWindowHeight();
673  if (h > pos.y - viewer_model.panel_y)
674  {
675  ImGui::GetWindowDrawList()->AddLine({ pos.x,pos.y }, { pos.x + viewer_model.panel_width,pos.y }, ImColor(from_rgba(0, 0, 0, 0xff)));
678  }
679 
680  for (auto&& lambda : draw_later)
681  {
682  try
683  {
684  lambda();
685  }
686  catch (const error& e)
687  {
688  error_message = error_to_string(e);
689  }
690  catch (const std::exception& e)
691  {
692  error_message = e.what();
693  }
694  }
695 
696  if (device_to_remove)
697  {
698  if (auto p = device_to_remove->dev.as<playback>())
699  {
700  ctx.unload_device(p.file_name());
701  }
702  viewer_model.syncer->remove_syncer(device_to_remove->dev_syncer);
703  auto it = std::find_if(begin(*device_models), end(*device_models),
704  [&](const std::unique_ptr<device_model>& other)
705  { return get_device_name(other->dev) == get_device_name(device_to_remove->dev); });
706 
707  if (it != device_models->end())
708  {
709  it->reset();
710  device_models->erase(it);
711  }
712 
713  device_to_remove = nullptr;
714  }
715  }
716  else
717  {
721 
722  viewer_model.show_no_device_overlay(window.get_large_font(), 50, static_cast<int>(viewer_model.panel_y + 50));
723  }
724 
725  ImGui::End();
728 
729  // Fetch and process frames from queue
730  viewer_model.handle_ready_frames(viewer_rect, window, static_cast<int>(device_models->size()), error_message);
731  }
732 
733  // Stopping post processing filter rendering thread
734  viewer_model.ppf.stop();
735 
736  // Stop all subdevices
737  for (auto&& device_model : *device_models)
738  for (auto&& sub : device_model->subdevices)
739  {
740  if (sub->streaming)
741  sub->stop(viewer_model.not_model);
742  }
743 
744  return EXIT_SUCCESS;
745 }
746 catch (const error & e)
747 {
748  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
749  return EXIT_FAILURE;
750 }
751 catch (const std::exception& e)
752 {
753  std::cerr << e.what() << std::endl;
754  return EXIT_FAILURE;
755 }
IMGUI_API void PushStyleVar(ImGuiStyleVar idx, float val)
Definition: imgui.cpp:4650
void add_to(context &ctx)
Definition: rs_net.hpp:26
static const ImVec4 white
Definition: model-views.h:45
IMGUI_API float GetCursorPosX()
Definition: imgui.cpp:5082
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
GLuint GLuint end
rs2::frame handle_ready_frames(const rect &viewer_rect, ux_window &window, int devices, std::string &error_message)
Definition: viewer.cpp:1335
GLenum GLuint GLenum severity
static bool GetWindowIsFocused()
Definition: imgui.h:519
ImVec2 GetBR() const
std::string get_serialized_data() const
Definition: rs_sensor.hpp:73
void unload_device(const std::string &file)
Definition: rs_context.hpp:195
ImVec4 from_rgba(uint8_t r, uint8_t g, uint8_t b, uint8_t a, bool consistent_color)
void log_to_callback(rs2_log_severity min_severity, S callback)
Definition: rs.hpp:139
std::atomic< bool > depth_stream_active
Definition: model-views.h:930
GLdouble s
static const char * last_ip
Definition: model-views.h:172
GLfloat GLfloat p
Definition: glext.h:12687
const GLfloat * m
Definition: glext.h:6814
std::function< bool()> on_load
Definition: ux-window.h:36
static const ImVec4 light_grey
Definition: model-views.h:40
static GLFWwindow * window
Definition: joysticks.c:55
Definition: imgui.h:88
static config_file & instance()
Definition: rs-config.cpp:80
playback load_device(const std::string &file)
Definition: rs_context.hpp:184
static const ImVec4 light_blue
Definition: model-views.h:38
float get_output_height() const
Definition: viewer.h:66
rs2_log_severity get_severity() const
Definition: rs_sensor.hpp:64
std::unordered_set< int > _hidden_options
Definition: viewer.h:195
IMGUI_API void SetNextWindowPos(const ImVec2 &pos, ImGuiSetCond cond=0)
Definition: imgui.cpp:4923
void log(rs2_log_severity severity, const char *message)
Definition: rs.hpp:149
static const ImVec4 dark_window_background
Definition: model-views.h:41
Definition: cah-model.h:10
GLsizei const GLchar *const * string
const char * filename() const
Definition: rs.hpp:74
d
Definition: rmse.py:171
std::string get_description() const
Definition: rs_sensor.hpp:46
static const textual_icon plus_circle
Definition: model-views.h:227
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
Definition: arg_fwd.hpp:23
GLdouble n
Definition: glext.h:1966
void show_no_device_overlay(ImFont *font, int min_x, int min_y)
Definition: viewer.cpp:1233
e
Definition: rmse.py:177
IMGUI_API void AddLine(const ImVec2 &a, const ImVec2 &b, ImU32 col, float thickness=1.0f)
Definition: imgui_draw.cpp:796
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 ImVec2 GetContentRegionMax()
Definition: imgui.cpp:4981
status
Defines return codes that SDK interfaces use. Negative values indicate errors, a zero value indicates...
std::shared_ptr< notifications_model > not_model
Definition: viewer.h:133
const float panel_y
Definition: viewer.h:64
ImFont * get_font() const
Definition: ux-window.h:64
T get_or_default(const char *key, T def) const
Definition: rs-config.h:65
def info(name, value, persistent=False)
Definition: test.py:301
size_t line_number() const
Definition: rs.hpp:66
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
IMGUI_API bool BeginPopup(const char *str_id)
Definition: imgui.cpp:3455
not_this_one begin(...)
IMGUI_API void SameLine(float pos_x=0.0f, float spacing_w=-1.0f)
Definition: imgui.cpp:9246
std::string error_to_string(const error &e)
Definition: rendering.h:1583
IMGUI_API ImVec2 GetContentRegionAvail()
Definition: imgui.cpp:4997
IMGUI_API ImDrawList * GetWindowDrawList()
Definition: imgui.cpp:5045
IMGUI_API bool Begin(const char *name, bool *p_open=NULL, ImGuiWindowFlags flags=0)
Definition: imgui.cpp:3772
IMGUI_API void PopStyleVar(int count=1)
Definition: imgui.cpp:4675
#define INITIALIZE_EASYLOGGINGPP
const float panel_width
Definition: viewer.h:63
bool add_remote_device(context &ctx, std::string address)
bool refresh_devices(std::mutex &m, context &ctx, device_changes &devices_connection_changes, std::vector< device > &current_connected_devices, std::vector< std::pair< std::string, std::string >> &device_names, device_models_list &device_models, viewer_model &viewer_model, std::string &error_message)
bool try_get_next_changes(event_information &removed_and_connected)
const char * raw() const
Definition: rs.hpp:82
#define GLFW_KEY_ESCAPE
Definition: glfw3.h:412
GLint GLsizei GLsizei height
IMGUI_API void SetNextWindowSize(const ImVec2 &size, ImGuiSetCond cond=0)
Definition: imgui.cpp:4937
rs2_playback_status
static const ImVec4 sensor_bg
Definition: model-views.h:51
GLbitfield flags
def find(dir, mask)
Definition: file.py:25
IMGUI_API void SetCursorPosX(float x)
Definition: imgui.cpp:5101
void update_viewer_configuration(viewer_model &viewer_model)
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
const char * file_dialog_open(file_dialog_mode flags, const char *filters, const char *default_path, const char *default_name)
Definition: os.cpp:169
GLint first
IMGUI_API void Separator()
Definition: imgui.cpp:9127
IMGUI_API void End()
Definition: imgui.cpp:4330
#define GLFW_KEY_ENTER
Definition: glfw3.h:413
ImVec2 GetTL() const
std::function< void(std::string)> on_file_drop
Definition: ux-window.h:35
static const ImVec4 dark_grey
Definition: model-views.h:49
IMGUI_API void EndPopup()
Definition: imgui.cpp:3489
IMGUI_API void NextColumn()
Definition: imgui.cpp:9280
IMGUI_API void PushStyleColor(ImGuiCol idx, const ImVec4 &col)
Definition: imgui.cpp:4599
IMGUI_API float GetWindowHeight()
Definition: imgui.cpp:4779
IMGUI_API bool ButtonEx(const char *label, const ImVec2 &size_arg=ImVec2(0, 0), ImGuiButtonFlags flags=0)
Definition: imgui.cpp:5523
rs2_notification_category get_category() const
Definition: rs_sensor.hpp:38
IMGUI_API void PushFont(ImFont *font)
Definition: imgui.cpp:4539
post_processing_filters ppf
Definition: viewer.h:130
float y
Definition: imgui.h:90
int main(int argc, const char **argv)
void log_to_console(rs2_log_severity min_severity)
Definition: rs.hpp:19
std::pair< std::string, std::string > get_device_name(const device &dev)
IMGUI_API ImVec2 GetCursorScreenPos()
Definition: imgui.cpp:5121
void set(const char *key, const char *value)
Definition: rs-config.cpp:15
IMGUI_API void PopItemWidth()
Definition: imgui.cpp:4507
#define GLFW_KEY_KP_ENTER
Definition: glfw3.h:471
static auto it
GLuint GLsizei const GLchar * label
IMGUI_API bool BeginPopupModal(const char *name, bool *p_open=NULL, ImGuiWindowFlags extra_flags=0)
Definition: imgui.cpp:3465
IMGUI_API bool Selectable(const char *label, bool selected=false, ImGuiSelectableFlags flags=0, const ImVec2 &size=ImVec2(0, 0))
Definition: imgui.cpp:8550
GLuint GLuint64EXT address
Definition: glext.h:11417
void add_playback_device(context &ctx, device_models_list &device_models, std::string &error_message, viewer_model &viewer_model, const std::string &file)
float width() const
Definition: ux-window.h:41
std::vector< std::unique_ptr< device_model > > device_models_list
Definition: model-views.h:96
std::ostream & cerr()
float rs2_vector::* pos
std::vector< std::shared_ptr< subdevice_model > > subdevices
Definition: model-views.h:794
IMGUI_API void SetContentRegionWidth(float y)
Definition: imgui.cpp:4990
#define NULL
Definition: tinycthread.c:47
int i
IMGUI_API void CloseCurrentPopup()
Definition: imgui.cpp:3408
IMGUI_API bool IsKeyDown(int key_index)
Definition: imgui.cpp:3061
ImFont * get_large_font() const
Definition: ux-window.h:62
void show_top_bar(ux_window &window, const rect &viewer_rect, const device_models_list &devices)
Definition: viewer.cpp:2314
IMGUI_API void OpenPopup(const char *str_id)
Definition: imgui.cpp:3343
IMGUI_API void SetCursorPosY(float y)
Definition: imgui.cpp:5108
std::shared_ptr< syncer_model > syncer
Definition: viewer.h:129
rs2_log_severity
Severity of the librealsense logger.
Definition: rs_types.h:153
IMGUI_API void Columns(int count=1, const char *id=NULL, bool border=true)
Definition: imgui.cpp:9398
IMGUI_API bool IsAnyItemActive()
Definition: imgui.cpp:3233
IMGUI_API float GetCursorPosY()
Definition: imgui.cpp:5088
IMGUI_API bool IsItemHovered()
Definition: imgui.cpp:3200
IMGUI_API void SetKeyboardFocusHere(int offset=0)
Definition: imgui.cpp:5188
const std::string & get_failed_function() const
Definition: rs_types.hpp:112
Definition: parser.hpp:150
GLint GLsizei width
IMGUI_API void PopFont()
Definition: imgui.cpp:4549
void copy(void *dst, void const *src, size_t size)
Definition: types.cpp:836
float x
Definition: imgui.h:90
IMGUI_API void PopStyleColor(int count=1)
Definition: imgui.cpp:4609
float height() const
Definition: ux-window.h:42
std::string to_string(T value)


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