apps/icp-log-viewer/main.cpp
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
6 
14 // The goal is to visualize these guys:
15 #include <mp2p_icp/LogRecord.h>
16 // using this:
17 #include <mrpt/gui/CDisplayWindowGUI.h>
18 
19 // other deps:
20 #include <mrpt/3rdparty/tclap/CmdLine.h>
21 #include <mrpt/config.h>
22 #include <mrpt/config/CConfigFile.h>
23 #include <mrpt/core/round.h>
24 #include <mrpt/opengl/CEllipsoid3D.h>
25 #include <mrpt/opengl/CGridPlaneXY.h>
26 #include <mrpt/opengl/COpenGLScene.h>
27 #include <mrpt/opengl/stock_objects.h>
28 #include <mrpt/poses/CPosePDFGaussian.h>
29 #include <mrpt/poses/Lie/SO.h>
30 #include <mrpt/system/CDirectoryExplorer.h>
31 #include <mrpt/system/filesystem.h>
32 #include <mrpt/system/os.h>
33 #include <mrpt/system/progress.h>
34 #include <mrpt/system/string_utils.h> // unitsFormat()
35 
36 #include <iostream>
37 
38 #include "../libcfgpath/cfgpath.h"
39 
40 constexpr const char* APP_NAME = "icp-log-viewer";
41 constexpr int MID_FONT_SIZE = 14;
42 constexpr int SMALL_FONT_SIZE = 12;
43 constexpr int WINDOW_FIXED_WIDTH = 400;
44 
45 // =========== Declare supported cli switches ===========
46 static TCLAP::CmdLine cmd(APP_NAME);
47 
48 static TCLAP::ValueArg<std::string> argExtension(
49  "e", "file-extension", "Filename extension to look for. Default is `icplog`", false, "icplog",
50  "icplog", cmd);
51 
52 static TCLAP::ValueArg<std::string> argSearchDir(
53  "d", "directory", "Directory in which to search for *.icplog files.", false, ".", ".", cmd);
54 
55 static TCLAP::ValueArg<std::string> argSingleFile(
56  "f", "file", "Load just this one single log *.icplog file.", false, "log.icplog", "log.icplog",
57  cmd);
58 
59 static TCLAP::ValueArg<std::string> arg_plugins(
60  "l", "load-plugins", "One or more (comma separated) *.so files to load as plugins", false,
61  "foobar.so", "foobar.so", cmd);
62 
63 static TCLAP::ValueArg<double> argAutoPlayPeriod(
64  "", "autoplay-period",
65  "The period (in seconds) between timestamps to load and show in autoplay "
66  "mode.",
67  false, 0.1, "period [seconds]", cmd);
68 
69 // =========== Declare global variables ===========
70 #if MRPT_HAS_NANOGUI
71 
72 auto glVizICP = mrpt::opengl::CSetOfObjects::Create();
73 mrpt::gui::CDisplayWindowGUI::Ptr win;
74 
75 nanogui::Slider* slSelectorICP = nullptr;
76 nanogui::Button *btnSelectorBack = nullptr, *btnSelectorForw = nullptr;
77 nanogui::Button* btnSelectorAutoplay = nullptr;
78 bool isAutoPlayActive = false;
79 double lastAutoPlayTime = .0;
80 
81 std::array<nanogui::TextBox*, 5> lbICPStats = {nullptr, nullptr, nullptr, nullptr, nullptr};
82 nanogui::CheckBox* cbShowInitialPose = nullptr;
83 nanogui::Label* lbICPIteration = nullptr;
84 nanogui::Slider* slIterationDetails = nullptr;
85 
86 const size_t MAX_VARIABLE_LIST = 100;
87 std::vector<nanogui::TextBox*> lbDynVariables;
88 
89 nanogui::CheckBox* cbViewOrtho = nullptr;
90 nanogui::CheckBox* cbCameraFollowsLocal = nullptr;
91 nanogui::CheckBox* cbViewVoxelsAsPoints = nullptr;
92 nanogui::CheckBox* cbViewVoxelsFreeSpace = nullptr;
93 nanogui::CheckBox* cbColorizeLocalMap = nullptr;
94 nanogui::CheckBox* cbColorizeGlobalMap = nullptr;
95 
96 nanogui::CheckBox* cbViewPairings = nullptr;
97 
98 nanogui::CheckBox* cbViewPairings_pt2pt = nullptr;
99 nanogui::CheckBox* cbViewPairings_pt2pl = nullptr;
100 nanogui::CheckBox* cbViewPairings_pt2ln = nullptr;
101 
102 nanogui::TextBox *tbLogPose = nullptr, *tbInitialGuess = nullptr, *tbInit2Final = nullptr,
103  *tbCovariance = nullptr, *tbConditionNumber = nullptr, *tbPairings = nullptr;
104 
105 nanogui::Slider* slPairingsPl2PlSize = nullptr;
106 nanogui::Slider* slPairingsPl2LnSize = nullptr;
107 nanogui::Slider* slGlobalPointSize = nullptr;
108 nanogui::Slider* slLocalPointSize = nullptr;
109 nanogui::Slider* slMidDepthField = nullptr;
110 nanogui::Slider* slThicknessDepthField = nullptr;
111 nanogui::Label * lbDepthFieldValues = nullptr, *lbDepthFieldMid = nullptr,
112  *lbDepthFieldThickness = nullptr;
113 
114 nanogui::Slider* slGTPose[6] = {nullptr, nullptr, nullptr, nullptr, nullptr, nullptr};
115 
116 std::vector<std::string> layerNames_global, layerNames_local;
117 
118 std::map<std::string, nanogui::CheckBox*> cbLayersByName_global;
119 std::map<std::string, nanogui::CheckBox*> cbLayersByName_local;
120 
121 class DelayedLoadLog
122 {
123  public:
124  DelayedLoadLog() = default;
125  DelayedLoadLog(const std::string& fileName, const std::string& shortFileName)
126  : filename_(fileName), shortFileName_(shortFileName)
127  {
128  }
129 
131  {
132  if (!log_)
133  {
134  // Load now:
135  log_ = mp2p_icp::LogRecord::LoadFromFile(filename_);
136  }
137 
138  return log_.value();
139  }
140 
141  void dispose() { log_.reset(); }
142 
143  const std::string& filename() const { return filename_; }
144  const std::string& shortFileName() const { return shortFileName_; }
145 
146  private:
147  std::optional<mp2p_icp::LogRecord> log_;
148  std::string filename_, shortFileName_;
149 };
150 
151 std::vector<DelayedLoadLog> logRecords;
152 
153 static void rebuild_3d_view(bool regenerateMaps = true);
154 
155 namespace
156 {
157 void rebuild_3d_view_fast() { rebuild_3d_view(false); }
158 
159 void processAutoPlay()
160 {
161  if (!isAutoPlayActive) return;
162 
163  const double tNow = mrpt::Clock::nowDouble();
164  if (tNow - lastAutoPlayTime < argAutoPlayPeriod.getValue()) return;
165 
166  lastAutoPlayTime = tNow;
167 
168  if (slSelectorICP->value() < slSelectorICP->range().second - 0.01f)
169  {
170  slSelectorICP->setValue(slSelectorICP->value() + 1);
171  rebuild_3d_view();
172  }
173 }
174 
175 void updateMiniCornerView()
176 {
177  auto gl_view = win->background_scene->getViewport("small-view");
178  if (!gl_view) return;
179 
180  mrpt::opengl::CCamera& view_cam = gl_view->getCamera();
181 
182  view_cam.setAzimuthDegrees(win->camera().getAzimuthDegrees());
183  view_cam.setElevationDegrees(win->camera().getElevationDegrees());
184  view_cam.setZoomDistance(5);
185 }
186 
187 void main_show_gui()
188 {
189  using namespace std::string_literals;
190 
191  mrpt::system::CDirectoryExplorer::TFileInfoList files;
192 
193  if (!argSingleFile.isSet())
194  {
195  const std::string searchDir = argSearchDir.getValue();
196  ASSERT_DIRECTORY_EXISTS_(searchDir);
197 
198  std::cout << "Searching in: '" << searchDir << "' for files with extension '"
199  << argExtension.getValue() << "'" << std::endl;
200 
201  mrpt::system::CDirectoryExplorer::explore(searchDir, FILE_ATTRIB_ARCHIVE, files);
202  mrpt::system::CDirectoryExplorer::filterByExtension(files, argExtension.getValue());
203  mrpt::system::CDirectoryExplorer::sortByName(files);
204 
205  std::cout << "Found " << files.size() << " ICP records." << std::endl;
206  }
207  else
208  {
209  // Load one single file:
210  std::cout << "Loading one single log file: " << argSingleFile.getValue() << std::endl;
211 
212  files.resize(1);
213  files[0].wholePath = argSingleFile.getValue();
214  }
215 
216  // load files:
217  for (const auto& file : files) logRecords.emplace_back(file.wholePath, file.name);
218 
219  ASSERT_(!logRecords.empty());
220 
221  // Obtain layer info from first entry:
222  {
223  const auto& lr = logRecords.front().get();
224  if (layerNames_global.empty() && lr.pcGlobal)
225  {
226  for (const auto& layer : lr.pcGlobal->layers)
227  {
228  layerNames_global.push_back(layer.first);
229  std::cout << "Global point cloud: Found point layer='" << layer.first << "'\n";
230  }
231  }
232  if (layerNames_local.empty() && lr.pcLocal)
233  {
234  for (const auto& layer : lr.pcLocal->layers)
235  {
236  layerNames_local.push_back(layer.first);
237  std::cout << "Local point cloud: Found point layer='" << layer.first << "'\n";
238  }
239  }
240  }
241 
242  // Get user app config file
243  char appCfgFile[1024];
244  ::get_user_config_file(appCfgFile, sizeof(appCfgFile), APP_NAME);
245  mrpt::config::CConfigFile appCfg(appCfgFile);
246 
247  /*
248  * -------------------------------------------------------------------
249  * GUI
250  * --------------------------------------------------------------------
251  */
252  nanogui::init();
253 
254  mrpt::gui::CDisplayWindowGUI_Params cp;
255  cp.maximized = true;
256  win = mrpt::gui::CDisplayWindowGUI::Create(APP_NAME, 1024, 800, cp);
257 
258  // Add a background scene:
259  auto scene = mrpt::opengl::COpenGLScene::Create();
260  {
261  auto glGrid = mrpt::opengl::CGridPlaneXY::Create();
262  glGrid->setColor_u8(0xff, 0xff, 0xff, 0x10);
263  scene->insert(glGrid);
264  }
265 
266  auto gl_base = mrpt::opengl::stock_objects::CornerXYZ(1.0f);
267  gl_base->setName("Global");
268  gl_base->enableShowName();
269  scene->insert(gl_base);
270 
271  scene->insert(glVizICP);
272 
273  {
274  std::lock_guard<std::mutex> lck(win->background_scene_mtx);
275  win->background_scene = std::move(scene);
276  }
277 
278  // Control GUI sub-window:
279  auto w = win->createManagedSubWindow("Control");
280  w->setPosition({5, 25});
281  w->requestFocus();
282  w->setLayout(
283  new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 5, 2));
284  w->setFixedWidth(WINDOW_FIXED_WIDTH);
285 
286  cbShowInitialPose = w->add<nanogui::CheckBox>("Show at INITIAL GUESS pose");
287  cbShowInitialPose->setCallback(
288  [=](bool v)
289  {
290  if (slIterationDetails->enabled())
291  {
292  const auto& r = slIterationDetails->range();
293  slIterationDetails->setValue(v ? r.first : r.second);
294  }
295  rebuild_3d_view_fast();
296  });
297  lbICPIteration = w->add<nanogui::Label>("Show ICP iteration:");
298  slIterationDetails = w->add<nanogui::Slider>();
299  slIterationDetails->setRange({.0f, 1.0f});
300  slIterationDetails->setCallback([](float) { rebuild_3d_view_fast(); });
301 
302  //
303  w->add<nanogui::Label>(" "); // separator
304  w->add<nanogui::Label>(mrpt::format(
305  "Select ICP record file (N=%u)", static_cast<unsigned int>(logRecords.size())));
306  slSelectorICP = w->add<nanogui::Slider>();
307  slSelectorICP->setRange({.0f, logRecords.size() - 1});
308  slSelectorICP->setValue(0);
309  slSelectorICP->setCallback([&](float /*v*/) { rebuild_3d_view(); });
310 
311  for (auto& lb : lbICPStats)
312  {
313  lb = w->add<nanogui::TextBox>(" ");
314  lb->setFontSize(MID_FONT_SIZE);
315  lb->setAlignment(nanogui::TextBox::Alignment::Left);
316  lb->setEditable(true);
317  }
318 
319  // navigation panel:
320  {
321  auto pn = w->add<nanogui::Widget>();
322  pn->setLayout(new nanogui::BoxLayout(nanogui::Orientation::Horizontal));
323 
324  // shortcut:
325  auto s = slSelectorICP;
326 
327  btnSelectorBack = pn->add<nanogui::Button>("", ENTYPO_ICON_CONTROLLER_FAST_BACKWARD);
328  btnSelectorBack->setCallback(
329  [=]()
330  {
331  if (s->value() > 0)
332  {
333  s->setValue(s->value() - 1);
334  s->callback()(s->value());
335  }
336  });
337 
338  btnSelectorForw = pn->add<nanogui::Button>("", ENTYPO_ICON_CONTROLLER_FAST_FORWARD);
339  btnSelectorForw->setCallback(
340  [=]()
341  {
342  if (s->value() < s->range().second - 0.01f)
343  {
344  s->setValue(s->value() + 1);
345  rebuild_3d_view();
346  }
347  });
348 
349  pn->add<nanogui::Label>(" "); // separator
350 
351  btnSelectorAutoplay = pn->add<nanogui::Button>("", ENTYPO_ICON_CONTROLLER_PLAY);
352  btnSelectorAutoplay->setFlags(nanogui::Button::ToggleButton);
353 
354  btnSelectorAutoplay->setChangeCallback([&](bool active) { isAutoPlayActive = active; });
355  }
356 
357  //
358  w->add<nanogui::Label>(" "); // separator
359 
360  auto tabWidget = w->add<nanogui::TabWidget>();
361 
362  auto* tab1 = tabWidget->createTab("Summary");
363  tab1->setLayout(
364  new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
365 
366  auto* tab2 = tabWidget->createTab("Variables");
367  tab2->setLayout(
368  new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
369 
370  auto* tab3 = tabWidget->createTab("Maps");
371  tab3->setLayout(new nanogui::GroupLayout());
372 
373  auto* tab4 = tabWidget->createTab("Pairings");
374  tab4->setLayout(new nanogui::GroupLayout());
375 
376  auto* tab5 = tabWidget->createTab("View");
377  tab5->setLayout(new nanogui::GroupLayout());
378 
379  auto* tab6 = tabWidget->createTab("Manual");
380  tab6->setLayout(new nanogui::GroupLayout());
381 
382  tabWidget->setActiveTab(0);
383 
384  tab1->add<nanogui::Label>(" ")->setFontSize(SMALL_FONT_SIZE);
385  tab1->add<nanogui::Label>("ICP result pose [x y z yaw(deg) pitch(deg) roll(deg)]:")
386  ->setFontSize(MID_FONT_SIZE);
387  tbLogPose = tab1->add<nanogui::TextBox>();
388  tbLogPose->setFontSize(MID_FONT_SIZE);
389  tbLogPose->setEditable(true);
390  tbLogPose->setAlignment(nanogui::TextBox::Alignment::Left);
391  tab1->add<nanogui::Label>(" ")->setFontSize(SMALL_FONT_SIZE);
392 
393  tab1->add<nanogui::Label>("Initial -> final pose change:")->setFontSize(MID_FONT_SIZE);
394  tbInit2Final = tab1->add<nanogui::TextBox>();
395  tbInit2Final->setFontSize(MID_FONT_SIZE);
396  tbInit2Final->setEditable(false);
397  tab1->add<nanogui::Label>(" ")->setFontSize(SMALL_FONT_SIZE);
398 
399  tab1->add<nanogui::Label>("Uncertainty: diagonal sigmas (x y z yaw pitch roll)")
400  ->setFontSize(MID_FONT_SIZE);
401  tbCovariance = tab1->add<nanogui::TextBox>();
402  tbCovariance->setFontSize(MID_FONT_SIZE);
403  tbCovariance->setEditable(false);
404  tab1->add<nanogui::Label>(" ")->setFontSize(SMALL_FONT_SIZE);
405 
406  tab1->add<nanogui::Label>("Uncertainty: Covariance condition numbers")
407  ->setFontSize(MID_FONT_SIZE);
408  tbConditionNumber = tab1->add<nanogui::TextBox>();
409  tbConditionNumber->setFontSize(MID_FONT_SIZE);
410  tbConditionNumber->setEditable(false);
411  tab1->add<nanogui::Label>(" ");
412 
413  tab6->add<nanogui::Label>("Manual solution modification:");
414  const float handTunedRange[6] = {4.0, 4.0, 10.0, 0.5 * M_PI, 0.25 * M_PI, 0.5};
415 
416  for (int i = 0; i < 6; i++)
417  {
418  slGTPose[i] = tab6->add<nanogui::Slider>();
419  slGTPose[i]->setRange({-handTunedRange[i], handTunedRange[i]});
420  slGTPose[i]->setValue(0.0f);
421 
422  slGTPose[i]->setCallback(
423  [=](float v)
424  {
425  const size_t idx = mrpt::round(slSelectorICP->value());
426  auto& lr = logRecords.at(idx).get();
427 
428  auto p = lr.icpResult.optimal_tf.mean.asTPose();
429  p[i] = v;
430  lr.icpResult.optimal_tf.mean = mrpt::poses::CPose3D(p);
431 
432  rebuild_3d_view_fast();
433  });
434  }
435 
436  tab1->add<nanogui::Label>("Initial guess pose:");
437  tbInitialGuess = tab1->add<nanogui::TextBox>();
438  tbInitialGuess->setFontSize(14);
439  tbInitialGuess->setEditable(true);
440  tbInitialGuess->setAlignment(nanogui::TextBox::Alignment::Left);
441 
442  // Save map buttons:
443  auto lambdaSave = [&](const mp2p_icp::metric_map_t& m)
444  {
445  const std::string outFile = nanogui::file_dialog(
446  {{"mm", "mp2p_icp::metric_map_t binary serialized object (*.mm)"}}, true /*save*/);
447  if (outFile.empty()) return;
448  m.save_to_file(outFile);
449  };
450 
451  // tab 2: variables
452  {
453  tab2->add<nanogui::Label>("Dynamic variables:");
454 
455  auto vscroll = tab2->add<nanogui::VScrollPanel>();
456  vscroll->setFixedSize({WINDOW_FIXED_WIDTH - 15, 300});
457 
458  auto wrapper = vscroll->add<nanogui::Widget>();
459 
460  wrapper->setFixedSize({WINDOW_FIXED_WIDTH - 30, 300});
461  wrapper->setLayout(
462  new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
463 
464  for (size_t i = 0; i < MAX_VARIABLE_LIST; i++)
465  {
466  auto* tb = wrapper->add<nanogui::TextBox>("aaaa");
467  tb->setAlignment(nanogui::TextBox::Alignment::Left);
468  tb->setEditable(true);
469  tb->setFontSize(MID_FONT_SIZE);
470  lbDynVariables.push_back(tb);
471  }
472  }
473 
474  // tab 3: maps
475  {
476  auto pn = tab3->add<nanogui::Widget>();
477  pn->setLayout(
478  new nanogui::BoxLayout(nanogui::Orientation::Horizontal, nanogui::Alignment::Fill));
479  pn->add<nanogui::Button>("Export 'local' map...")
480  ->setCallback(
481  [&]()
482  {
483  const size_t idx = mrpt::round(slSelectorICP->value());
484  auto& lr = logRecords.at(idx).get();
485  ASSERT_(lr.pcLocal);
486  lambdaSave(*lr.pcLocal);
487  });
488  pn->add<nanogui::Button>("Export 'global' map...")
489  ->setCallback(
490  [&]()
491  {
492  const size_t idx = mrpt::round(slSelectorICP->value());
493  auto& lr = logRecords.at(idx).get();
494  ASSERT_(lr.pcGlobal);
495  lambdaSave(*lr.pcGlobal);
496  });
497  }
498 
499  tab3->add<nanogui::Label>("[GLOBAL map] Visible layers:");
500 
501  for (size_t i = 0; i < layerNames_global.size(); i++)
502  {
503  auto cb = tab3->add<nanogui::CheckBox>(layerNames_global.at(i));
504  cb->setChecked(true);
505  cb->setCallback([](bool) { rebuild_3d_view(); });
506  cb->setFontSize(13);
507 
508  cbLayersByName_global[layerNames_global.at(i)] = cb;
509  }
510 
511  tab3->add<nanogui::Label>("[LOCAL map] Visible layers:");
512  for (size_t i = 0; i < layerNames_local.size(); i++)
513  {
514  auto cb = tab3->add<nanogui::CheckBox>(layerNames_local.at(i));
515  cb->setChecked(true);
516  cb->setCallback([](bool) { rebuild_3d_view(); });
517  cb->setFontSize(13);
518 
519  cbLayersByName_local[layerNames_local.at(i)] = cb;
520  }
521 
522  // tab4: pairings:
523  tbPairings = tab4->add<nanogui::TextBox>();
524  tbPairings->setFontSize(16);
525  tbPairings->setEditable(false);
526 
527  cbViewPairings = tab4->add<nanogui::CheckBox>("View pairings");
528  cbViewPairings->setCallback([](bool) { rebuild_3d_view_fast(); });
529 
530  cbViewPairings_pt2pt = tab4->add<nanogui::CheckBox>("View: point-to-point");
531  cbViewPairings_pt2pt->setChecked(true);
532  cbViewPairings_pt2pt->setCallback([](bool) { rebuild_3d_view_fast(); });
533 
534  {
535  auto pn = tab4->add<nanogui::Widget>();
536  pn->setLayout(
537  new nanogui::GridLayout(nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
538 
539  cbViewPairings_pt2pl = pn->add<nanogui::CheckBox>("View: point-to-plane");
540  cbViewPairings_pt2pl->setChecked(true);
541  cbViewPairings_pt2pl->setCallback([](bool) { rebuild_3d_view_fast(); });
542 
543  pn->add<nanogui::Label>("Plane size:");
544  slPairingsPl2PlSize = pn->add<nanogui::Slider>();
545  slPairingsPl2PlSize->setRange({-2.0f, 2.0f});
546  slPairingsPl2PlSize->setValue(-1.0f);
547  slPairingsPl2PlSize->setCallback([&](float) { rebuild_3d_view_fast(); });
548  }
549 
550  {
551  auto pn = tab4->add<nanogui::Widget>();
552  pn->setLayout(
553  new nanogui::GridLayout(nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
554 
555  cbViewPairings_pt2ln = pn->add<nanogui::CheckBox>("View: point-to-line");
556  cbViewPairings_pt2ln->setChecked(true);
557  cbViewPairings_pt2ln->setCallback([](bool) { rebuild_3d_view_fast(); });
558 
559  pn->add<nanogui::Label>("Line length:");
560  slPairingsPl2LnSize = pn->add<nanogui::Slider>();
561  slPairingsPl2LnSize->setRange({-2.0f, 2.0f});
562  slPairingsPl2LnSize->setValue(-1.0f);
563  slPairingsPl2LnSize->setCallback([&](float) { rebuild_3d_view_fast(); });
564  }
565 
566  // tab5: view
567  {
568  auto pn = tab5->add<nanogui::Widget>();
569  pn->setLayout(
570  new nanogui::GridLayout(nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
571 
572  pn->add<nanogui::Label>("Global map point size");
573 
574  slGlobalPointSize = pn->add<nanogui::Slider>();
575  slGlobalPointSize->setRange({1.0f, 10.0f});
576  slGlobalPointSize->setValue(2.0f);
577  slGlobalPointSize->setCallback([&](float) { rebuild_3d_view(); });
578  }
579  {
580  auto pn = tab5->add<nanogui::Widget>();
581  pn->setLayout(
582  new nanogui::GridLayout(nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
583 
584  pn->add<nanogui::Label>("Local map point size");
585 
586  slLocalPointSize = pn->add<nanogui::Slider>();
587  slLocalPointSize->setRange({1.0f, 10.0f});
588  slLocalPointSize->setValue(2.0f);
589  slLocalPointSize->setCallback([&](float) { rebuild_3d_view(); });
590  }
591  {
592  auto pn = tab5->add<nanogui::Widget>();
593  pn->setLayout(
594  new nanogui::GridLayout(nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
595 
596  lbDepthFieldMid = pn->add<nanogui::Label>("Center depth clip plane:");
597  slMidDepthField = pn->add<nanogui::Slider>();
598  }
599  slMidDepthField->setRange({-2.0, 3.0});
600  slMidDepthField->setValue(1.0f);
601  slMidDepthField->setCallback([&](float) { rebuild_3d_view_fast(); });
602 
603  {
604  auto pn = tab5->add<nanogui::Widget>();
605  pn->setLayout(
606  new nanogui::GridLayout(nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
607 
608  lbDepthFieldThickness = pn->add<nanogui::Label>("Max-Min depth thickness:");
609  slThicknessDepthField = pn->add<nanogui::Slider>();
610  }
611  slThicknessDepthField->setRange({-2.0, 6.0});
612  slThicknessDepthField->setValue(3.0);
613  slThicknessDepthField->setCallback([&](float) { rebuild_3d_view_fast(); });
614  lbDepthFieldValues = tab5->add<nanogui::Label>(" ");
615 
616  cbViewOrtho = tab5->add<nanogui::CheckBox>("Orthogonal view");
617  cbViewOrtho->setCallback([&](bool) { rebuild_3d_view_fast(); });
618 
619  cbCameraFollowsLocal = tab5->add<nanogui::CheckBox>("Camera follows 'local'");
620  cbCameraFollowsLocal->setCallback([&](bool) { rebuild_3d_view_fast(); });
621 
622  cbViewVoxelsAsPoints = tab5->add<nanogui::CheckBox>("Render voxel maps as point clouds");
623  cbViewVoxelsAsPoints->setChecked(true);
624  cbViewVoxelsAsPoints->setCallback([&](bool) { rebuild_3d_view(); });
625 
626  cbViewVoxelsFreeSpace = tab5->add<nanogui::CheckBox>("Render free space of voxel maps");
627  cbViewVoxelsFreeSpace->setChecked(false);
628  cbViewVoxelsFreeSpace->setCallback([&](bool) { rebuild_3d_view(); });
629 
630  cbColorizeLocalMap = tab5->add<nanogui::CheckBox>("Recolorize local map");
631  cbColorizeLocalMap->setCallback([&](bool) { rebuild_3d_view(); });
632 
633  cbColorizeGlobalMap = tab5->add<nanogui::CheckBox>("Recolorize global map");
634  cbColorizeGlobalMap->setCallback([&](bool) { rebuild_3d_view(); });
635 
636  // ----
637  w->add<nanogui::Label>(" "); // separator
638  w->add<nanogui::Button>("Quit", ENTYPO_ICON_ARROW_BOLD_LEFT)
639  ->setCallback([]() { win->setVisible(false); });
640 
641  win->setKeyboardCallback(
642  [&](int key, [[maybe_unused]] int scancode, int action, [[maybe_unused]] int modifiers)
643  {
644  if (action != GLFW_PRESS && action != GLFW_REPEAT) return false;
645 
646  int increment = 0;
647  switch (key)
648  {
649  case GLFW_KEY_LEFT:
650  increment = -1;
651  break;
652  case GLFW_KEY_RIGHT:
653  increment = +1;
654  break;
655  case GLFW_KEY_PAGE_DOWN:
656  increment = +100;
657  break;
658  case GLFW_KEY_PAGE_UP:
659  increment = -100;
660  break;
661  case GLFW_KEY_SPACE:
662  isAutoPlayActive = !isAutoPlayActive;
663  btnSelectorAutoplay->setPushed(isAutoPlayActive);
664  break;
665  case 'i':
666  case 'I':
667  cbShowInitialPose->setChecked(!cbShowInitialPose->checked());
668  cbShowInitialPose->callback()(cbShowInitialPose->checked());
669  break;
670  };
671 
672  if (increment != 0)
673  {
674  nanogui::Slider* sl = slSelectorICP; // shortcut
675  sl->setValue(sl->value() + increment);
676  if (sl->value() < 0) sl->setValue(0);
677  if (sl->value() > sl->range().second) sl->setValue(sl->range().second);
678  rebuild_3d_view();
679  }
680 
681  return false;
682  });
683 
684  win->performLayout();
685  win->camera().setCameraPointing(8.0f, .0f, .0f);
686  win->camera().setAzimuthDegrees(110.0f);
687  win->camera().setElevationDegrees(15.0f);
688  win->camera().setZoomDistance(30.0f);
689 
690  // save and load UI state:
691 #define LOAD_CB_STATE(CB_NAME__) do_cb(CB_NAME__, #CB_NAME__)
692 #define SAVE_CB_STATE(CB_NAME__) appCfg.write("", #CB_NAME__, CB_NAME__->checked())
693 
694 #define LOAD_SL_STATE(SL_NAME__) do_sl(SL_NAME__, #SL_NAME__)
695 #define SAVE_SL_STATE(SL_NAME__) appCfg.write("", #SL_NAME__, SL_NAME__->value())
696 
697  auto load_UI_state_from_user_config = [&]()
698  {
699  auto do_cb = [&](nanogui::CheckBox* cb, const std::string& name)
700  { cb->setChecked(appCfg.read_bool("", name, cb->checked())); };
701  auto do_sl = [&](nanogui::Slider* sl, const std::string& name)
702  { sl->setValue(appCfg.read_float("", name, sl->value())); };
703 
704  LOAD_CB_STATE(cbColorizeLocalMap);
705  LOAD_CB_STATE(cbColorizeGlobalMap);
706  LOAD_CB_STATE(cbShowInitialPose);
707  LOAD_CB_STATE(cbViewOrtho);
708  LOAD_CB_STATE(cbCameraFollowsLocal);
709  LOAD_CB_STATE(cbViewVoxelsAsPoints);
710  LOAD_CB_STATE(cbViewPairings);
711  LOAD_CB_STATE(cbViewPairings_pt2pt);
712  LOAD_CB_STATE(cbViewPairings_pt2pl);
713  LOAD_CB_STATE(cbViewPairings_pt2ln);
714 
715  LOAD_SL_STATE(slPairingsPl2PlSize);
716  LOAD_SL_STATE(slPairingsPl2LnSize);
717  LOAD_SL_STATE(slGlobalPointSize);
718  LOAD_SL_STATE(slLocalPointSize);
719  LOAD_SL_STATE(slMidDepthField);
720  LOAD_SL_STATE(slThicknessDepthField);
721 
722  win->camera().setCameraPointing(
723  appCfg.read_float("", "cam_x", win->camera().getCameraPointingX()),
724  appCfg.read_float("", "cam_y", win->camera().getCameraPointingY()),
725  appCfg.read_float("", "cam_z", win->camera().getCameraPointingZ()));
726  win->camera().setAzimuthDegrees(
727  appCfg.read_float("", "cam_az", win->camera().getAzimuthDegrees()));
728  win->camera().setElevationDegrees(
729  appCfg.read_float("", "cam_el", win->camera().getElevationDegrees()));
730  win->camera().setZoomDistance(
731  appCfg.read_float("", "cam_d", win->camera().getZoomDistance()));
732  };
733  auto save_UI_state_to_user_config = [&]()
734  {
735  SAVE_CB_STATE(cbColorizeLocalMap);
736  SAVE_CB_STATE(cbColorizeGlobalMap);
737  SAVE_CB_STATE(cbShowInitialPose);
738  SAVE_CB_STATE(cbViewOrtho);
739  SAVE_CB_STATE(cbCameraFollowsLocal);
740  SAVE_CB_STATE(cbViewVoxelsAsPoints);
741  SAVE_CB_STATE(cbViewPairings);
742  SAVE_CB_STATE(cbViewPairings_pt2pt);
743  SAVE_CB_STATE(cbViewPairings_pt2pl);
744  SAVE_CB_STATE(cbViewPairings_pt2ln);
745 
746  SAVE_SL_STATE(slPairingsPl2PlSize);
747  SAVE_SL_STATE(slPairingsPl2LnSize);
748  SAVE_SL_STATE(slGlobalPointSize);
749  SAVE_SL_STATE(slLocalPointSize);
750  SAVE_SL_STATE(slMidDepthField);
751  SAVE_SL_STATE(slThicknessDepthField);
752 
753  appCfg.write("", "cam_x", win->camera().getCameraPointingX());
754  appCfg.write("", "cam_y", win->camera().getCameraPointingY());
755  appCfg.write("", "cam_z", win->camera().getCameraPointingZ());
756  appCfg.write("", "cam_az", win->camera().getAzimuthDegrees());
757  appCfg.write("", "cam_el", win->camera().getElevationDegrees());
758  appCfg.write("", "cam_d", win->camera().getZoomDistance());
759  };
760 
761  // load UI state from last session:
762  load_UI_state_from_user_config();
763 
764  rebuild_3d_view();
765 
766  // Main loop
767  // ---------------------
768  win->drawAll();
769  win->setVisible(true);
770 
771  win->addLoopCallback(
772  [&]()
773  {
774  processAutoPlay();
775  updateMiniCornerView();
776  });
777 
778  nanogui::mainloop(1000 /*idleLoopPeriod ms*/, 25 /* minRepaintPeriod ms */);
779 
780  nanogui::shutdown();
781 
782  // save UI state:
783  save_UI_state_to_user_config();
784 }
785 
786 } // namespace
787 
788 template <class MATRIX> //
789 double conditionNumber(const MATRIX& m)
790 {
791  MATRIX eVecs;
792  std::vector<double> eVals;
793  m.eig_symmetric(eVecs, eVals);
794  return eVals.back() / eVals.front();
795 }
796 
797 // ==============================
798 // rebuild_3d_view
799 // ==============================
800 void rebuild_3d_view(bool regenerateMaps)
801 {
802  using namespace std::string_literals;
803 
804  const size_t idx = mrpt::round(slSelectorICP->value());
805 
806  btnSelectorBack->setEnabled(!logRecords.empty() && idx > 0);
807  btnSelectorForw->setEnabled(!logRecords.empty() && idx < logRecords.size() - 1);
808 
809  if (idx >= logRecords.size()) return;
810 
811  glVizICP->clear();
812 
813  // Free memory
814  static std::optional<size_t> lastIdx;
815  bool mustResetIterationSlider = false;
816 
817  if (!lastIdx || (lastIdx && idx != *lastIdx))
818  {
819  // free memory:
820  if (lastIdx) logRecords.at(*lastIdx).dispose();
821 
822  // and note that we should show the first/last ICP iteration:
823  mustResetIterationSlider = true;
824  }
825  lastIdx = idx;
826 
827  // lazy load from disk happens in the "get()":
828  const auto& lr = logRecords.at(idx).get();
829 
830  lbICPStats[0]->setValue(logRecords.at(idx).shortFileName());
831 
832  lbICPStats[1]->setValue(mrpt::format(
833  "ICP log #%zu | Local: ID:%u%s | Global: ID:%u%s", idx,
834  static_cast<unsigned int>(lr.pcLocal->id ? lr.pcLocal->id.value() : 0),
835  lr.pcLocal->label ? lr.pcLocal->label.value().c_str() : "",
836  static_cast<unsigned int>(lr.pcGlobal->id ? lr.pcGlobal->id.value() : 0),
837  lr.pcGlobal->label ? lr.pcGlobal->label.value().c_str() : ""));
838 
839  lbICPStats[2]->setValue(mrpt::format(
840  "Quality: %.02f%% | Iters: %u | Term.Reason: %s", 100.0 * lr.icpResult.quality,
841  static_cast<unsigned int>(lr.icpResult.nIterations),
842  mrpt::typemeta::enum2str(lr.icpResult.terminationReason).c_str()));
843 
844  lbICPStats[3]->setValue("Global: "s + lr.pcGlobal->contents_summary());
845  lbICPStats[4]->setValue("Local: "s + lr.pcLocal->contents_summary());
846 
847  tbInitialGuess->setValue(lr.initialGuessLocalWrtGlobal.asString());
848 
849  tbLogPose->setValue(lr.icpResult.optimal_tf.mean.asString());
850 
851  // dyn variables:
852  {
853  for (auto* lb : lbDynVariables) lb->setValue("");
854 
855  size_t lbIdx = 0;
856  for (const auto& [name, value] : lr.dynamicVariables)
857  {
858  lbDynVariables[lbIdx++]->setValue(mrpt::format("%s = %g", name.c_str(), value));
859  if (lbIdx >= MAX_VARIABLE_LIST) break;
860  }
861  }
862 
863  {
864  const auto poseChange =
865  lr.icpResult.optimal_tf.mean - mrpt::poses::CPose3D(lr.initialGuessLocalWrtGlobal);
866 
867  tbInit2Final->setValue(mrpt::format(
868  "|T|=%.03f [m] |R|=%.03f [deg]", poseChange.norm(),
869  mrpt::RAD2DEG(mrpt::poses::Lie::SO<3>::log(poseChange.getRotationMatrix()).norm())));
870  }
871 
872  const auto poseFromCorner = mrpt::poses::CPose3D::Identity();
873  mrpt::poses::CPose3DPDFGaussian relativePose;
874  const mp2p_icp::Pairings* pairsToViz = nullptr;
875 
876  if (!lr.iterationsDetails.has_value() || lr.iterationsDetails->empty())
877  {
878  slIterationDetails->setEnabled(false);
879 
880  if (cbShowInitialPose->checked())
881  {
882  relativePose.mean = mrpt::poses::CPose3D(lr.initialGuessLocalWrtGlobal);
883  lbICPIteration->setCaption("Show ICP iteration: INITIAL");
884  }
885  else
886  {
887  relativePose = lr.icpResult.optimal_tf;
888  lbICPIteration->setCaption("Show ICP iteration: FINAL");
889  }
890 
891  if (cbViewPairings->checked()) pairsToViz = &lr.icpResult.finalPairings;
892  }
893  else
894  {
895  slIterationDetails->setEnabled(true);
896  slIterationDetails->setRange({.0f, static_cast<float>(lr.iterationsDetails->size() - 1)});
897 
898  if (mustResetIterationSlider)
899  slIterationDetails->setValue(
900  cbShowInitialPose->checked() ? slIterationDetails->range().first
901  : slIterationDetails->range().second);
902 
903  // final or partial solution?
904  auto it = lr.iterationsDetails->begin();
905 
906  size_t nIter = mrpt::round(slIterationDetails->value());
907  mrpt::keep_min(nIter, lr.iterationsDetails->size() - 1);
908 
909  std::advance(it, nIter);
910 
911  relativePose.mean = it->second.optimalPose;
912  if (cbViewPairings->checked()) pairsToViz = &it->second.pairings;
913 
914  lbICPIteration->setCaption(
915  "Show ICP iteration: "s + std::to_string(it->first) + "/"s +
916  std::to_string(lr.iterationsDetails->rbegin()->first));
917  }
918 
919  {
920  std::string s;
921  for (int i = 0; i < 6; i++) s += mrpt::format("%.02f ", std::sqrt(relativePose.cov(i, i)));
922 
923  s += mrpt::format(
924  " det(XYZ)=%.02e det(rot)=%.02e", relativePose.cov.blockCopy<3, 3>(0, 0).det(),
925  relativePose.cov.blockCopy<3, 3>(3, 3).det());
926 
927  tbCovariance->setValue(s);
928  }
929 
930  // Extract SE(2) covariance:
931  const mrpt::poses::CPosePDFGaussian pose2D(relativePose);
932 
933  // Condition numbers:
934  tbConditionNumber->setValue(mrpt::format(
935  " cn{XYZ}=%.02f cn{SO(3)}=%.02f cn{SE(2)}=%.02f "
936  "cn{SE(3)}=%.02f",
937  conditionNumber(relativePose.cov.blockCopy<3, 3>(0, 0)),
938  conditionNumber(relativePose.cov.blockCopy<3, 3>(3, 3)), conditionNumber(pose2D.cov),
939  conditionNumber(relativePose.cov)));
940 
941  // 3D objects -------------------
942  auto glCornerFrom = mrpt::opengl::stock_objects::CornerXYZSimple(0.75f, 3.0f);
943  glCornerFrom->setPose(poseFromCorner);
944  glVizICP->insert(glCornerFrom);
945 
946  auto glCornerLocal = mrpt::opengl::stock_objects::CornerXYZSimple(0.85f, 5.0f);
947  glCornerLocal->setPose(relativePose.mean);
948  glCornerLocal->setName("Local");
949  glCornerLocal->enableShowName(true);
950  glVizICP->insert(glCornerLocal);
951 
952  auto glCornerToCov = mrpt::opengl::CEllipsoid3D::Create();
953  glCornerToCov->set3DsegmentsCount(16);
954  glCornerToCov->enableDrawSolid3D(true);
955  glCornerToCov->setColor_u8(0xff, 0x00, 0x00, 0x40);
956  // std::cout << "cov:\n" << relativePose.cov << "\n";
957  glCornerToCov->setCovMatrixAndMean(
958  relativePose.cov.blockCopy<3, 3>(0, 0), relativePose.mean.asVectorVal().head<3>());
959  glVizICP->insert(glCornerToCov);
960 
961  // GLOBAL PC:
962  mp2p_icp::render_params_t rpGlobal;
963 
964  rpGlobal.points.visible = false;
965  for (const auto& [lyName, cb] : cbLayersByName_global)
966  {
967  // Update stats in the cb label:
968  cb->setCaption(lyName); // default
969  if (auto itL = lr.pcGlobal->layers.find(lyName); itL != lr.pcGlobal->layers.end())
970  {
971  if (auto pc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itL->second); pc)
972  {
973  cb->setCaption(
974  lyName + " | "s + mrpt::system::unitsFormat(static_cast<double>(pc->size())) +
975  " points"s + " | class="s + pc->GetRuntimeClass()->className);
976  }
977  else
978  {
979  cb->setCaption(lyName + " | class="s + itL->second->GetRuntimeClass()->className);
980  }
981  }
982 
983  // show/hide:
984  if (!cb->checked()) continue; // hidden
985  rpGlobal.points.visible = true;
986 
987  auto& rpL = rpGlobal.points.perLayer[lyName];
988  rpL.pointSize = slGlobalPointSize->value();
989  rpL.render_voxelmaps_as_points = cbViewVoxelsAsPoints->checked();
990  rpL.render_voxelmaps_free_space = cbViewVoxelsFreeSpace->checked();
991 
992  if (cbColorizeGlobalMap->checked())
993  {
994  auto& cm = rpL.colorMode.emplace();
995  cm.colorMap = mrpt::img::TColormap::cmHOT;
996  cm.recolorizeByCoordinate = mp2p_icp::Coordinate::Z;
997  }
998  }
999 
1000  static mrpt::opengl::CSetOfObjects::Ptr lastGlobalPts;
1001 
1002  if (!lastGlobalPts || regenerateMaps)
1003  {
1004  // Show all or selected layers:
1005  for (auto& rpL : rpGlobal.points.perLayer)
1006  rpL.second.color = mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
1007 
1008  auto glPts = lr.pcGlobal->get_visualization(rpGlobal);
1009  lastGlobalPts = glPts;
1010 
1011  // Show all or selected layers:
1012  rpGlobal.points.allLayers.color = mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
1013 
1014  glVizICP->insert(glPts);
1015  }
1016  else
1017  {
1018  // avoid the costly method of re-rendering maps, if possible:
1019  glVizICP->insert(lastGlobalPts);
1020  }
1021 
1022  // LOCAL PC:
1023  mp2p_icp::render_params_t rpLocal;
1024 
1025  rpLocal.points.visible = false;
1026  for (const auto& [lyName, cb] : cbLayersByName_local)
1027  {
1028  // Update stats in the cb label:
1029  cb->setCaption(lyName); // default
1030  if (auto itL = lr.pcLocal->layers.find(lyName); itL != lr.pcLocal->layers.end())
1031  {
1032  if (auto pc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itL->second); pc)
1033  {
1034  cb->setCaption(
1035  lyName + " | "s +
1036  mrpt::system::unitsFormat(static_cast<double>(pc->size()), 2, false) +
1037  " points"s + " | class="s + pc->GetRuntimeClass()->className);
1038  }
1039  else
1040  {
1041  cb->setCaption(lyName + " | class="s + itL->second->GetRuntimeClass()->className);
1042  }
1043  }
1044 
1045  // show/hide:
1046  if (!cb->checked()) continue; // hidden
1047  rpLocal.points.visible = true;
1048 
1049  auto& rpL = rpLocal.points.perLayer[lyName];
1050  rpL.pointSize = slLocalPointSize->value();
1051  rpL.render_voxelmaps_as_points = cbViewVoxelsAsPoints->checked();
1052  rpL.render_voxelmaps_free_space = cbViewVoxelsFreeSpace->checked();
1053  if (cbColorizeLocalMap->checked())
1054  {
1055  auto& cm = rpL.colorMode.emplace();
1056  cm.colorMap = mrpt::img::TColormap::cmHOT;
1057  cm.recolorizeByCoordinate = mp2p_icp::Coordinate::Z;
1058  }
1059  }
1060 
1061  static mrpt::opengl::CSetOfObjects::Ptr lastLocalPts;
1062 
1063  if (!lastLocalPts || regenerateMaps)
1064  {
1065  // Show all or selected layers:
1066  for (auto& rpL : rpLocal.points.perLayer)
1067  rpL.second.color = mrpt::img::TColor(0x00, 0x00, 0xff, 0xff);
1068 
1069  auto glPts = lr.pcLocal->get_visualization(rpLocal);
1070  lastLocalPts = glPts;
1071 
1072  glVizICP->insert(glPts);
1073  }
1074  else
1075  {
1076  // avoid the costly method of re-rendering maps, if possible:
1077  glVizICP->insert(lastLocalPts);
1078  }
1079  lastLocalPts->setPose(relativePose.mean);
1080 
1081  // Global view options:
1082  {
1083  std::lock_guard<std::mutex> lck(win->background_scene_mtx);
1084  win->camera().setCameraProjective(!cbViewOrtho->checked());
1085 
1086  if (cbCameraFollowsLocal->checked())
1087  {
1088  win->camera().setCameraPointing(
1089  relativePose.mean.x(), relativePose.mean.y(), relativePose.mean.z());
1090  }
1091 
1092  // clip planes:
1093  const auto depthFieldMid = std::pow(10.0, slMidDepthField->value());
1094  const auto depthFieldThickness = std::pow(10.0, slThicknessDepthField->value());
1095 
1096  const auto clipNear = std::max(1e-2, depthFieldMid - 0.5 * depthFieldThickness);
1097  const auto clipFar = depthFieldMid + 0.5 * depthFieldThickness;
1098 
1099  lbDepthFieldMid->setCaption(mrpt::format("Frustrum depth center: %.03f", depthFieldMid));
1100  lbDepthFieldThickness->setCaption(
1101  mrpt::format("Frustum depth thickness: %.03f", depthFieldThickness));
1102  lbDepthFieldValues->setCaption(
1103  mrpt::format("Frustum: near=%.02f far=%.02f", clipNear, clipFar));
1104 
1105  win->background_scene->getViewport()->setViewportClipDistances(clipNear, clipFar);
1106  win->camera().setMaximumZoom(std::max<double>(1000, 3.0 * clipFar));
1107  }
1108 
1109  // Pairings ------------------
1110 
1111  // viz pairings:
1112  if (pairsToViz)
1113  {
1115 
1116  rp.pt2pt.visible = cbViewPairings_pt2pt->checked();
1117  rp.pt2pl.visible = cbViewPairings_pt2pl->checked();
1118  rp.pt2pl.planePatchSize = std::pow(10.0, slPairingsPl2PlSize->value());
1119 
1120  rp.pt2ln.visible = cbViewPairings_pt2ln->checked();
1121  rp.pt2ln.lineLength = std::pow(10.0, slPairingsPl2LnSize->value());
1122 
1123  glVizICP->insert(pairsToViz->get_visualization(relativePose.mean, rp));
1124 
1125  tbPairings->setValue(pairsToViz->contents_summary());
1126  }
1127  else
1128  {
1129  tbPairings->setValue("None selected (mark one of the checkboxes below)");
1130  }
1131 
1132  // XYZ corner overlay viewport:
1133  {
1134  auto gl_view = win->background_scene->createViewport("small-view");
1135 
1136  gl_view->setViewportPosition(0, 0, 0.1, 0.1 * 16.0 / 9.0);
1137  gl_view->setTransparent(true);
1138  {
1139  mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create("X");
1140  obj->setLocation(1.1, 0, 0);
1141  gl_view->insert(obj);
1142  }
1143  {
1144  mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create("Y");
1145  obj->setLocation(0, 1.1, 0);
1146  gl_view->insert(obj);
1147  }
1148  {
1149  mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create("Z");
1150  obj->setLocation(0, 0, 1.1);
1151  gl_view->insert(obj);
1152  }
1153  gl_view->insert(mrpt::opengl::stock_objects::CornerXYZ());
1154  }
1155 }
1156 
1157 #else // MRPT_HAS_NANOGUI
1158 static void main_show_gui()
1159 {
1160  THROW_EXCEPTION(
1161  "This application requires a version of MRPT built with nanogui "
1162  "support.");
1163 }
1164 
1165 #endif // MRPT_HAS_NANOGUI
1166 
1167 int main(int argc, char** argv)
1168 {
1169  try
1170  {
1171  // Parse arguments:
1172  if (!cmd.parse(argc, argv)) return 1; // should exit.
1173 
1174  // Load plugins:
1175  if (arg_plugins.isSet())
1176  {
1177  std::string errMsg;
1178  const auto plugins = arg_plugins.getValue();
1179  std::cout << "Loading plugin(s): " << plugins << std::endl;
1180  if (!mrpt::system::loadPluginModules(plugins, errMsg))
1181  {
1182  std::cerr << errMsg << std::endl;
1183  return 1;
1184  }
1185  }
1186 
1187  main_show_gui();
1188  return 0;
1189  }
1190  catch (std::exception& e)
1191  {
1192  std::cerr << "Exit due to exception:\n" << mrpt::exception_to_str(e) << std::endl;
1193  return 1;
1194  }
1195 }
mp2p_icp::pairings_render_params_t::pt2pl
render_params_pairings_pt2pl_t pt2pl
Definition: render_params.h:219
mp2p_icp::Pairings::contents_summary
virtual std::string contents_summary() const
Definition: Pairings.cpp:151
cmd
static TCLAP::CmdLine cmd(APP_NAME)
mp2p_icp::render_params_t::points
render_params_points_t points
Definition: render_params.h:173
main
int main(int argc, char **argv)
Definition: apps/icp-log-viewer/main.cpp:1167
mp2p_icp::pairings_render_params_t::pt2pt
render_params_pairings_pt2pt_t pt2pt
Definition: render_params.h:218
LogRecord.h
A record of the inputs and outputs of an ICP run.
arg_plugins
static TCLAP::ValueArg< std::string > arg_plugins("l", "load-plugins", "One or more (comma separated) *.so files to load as plugins", false, "foobar.so", "foobar.so", cmd)
s
XmlRpcServer s
mp2p_icp::render_params_pairings_pt2pl_t::visible
bool visible
Definition: render_params.h:195
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
argSearchDir
static TCLAP::ValueArg< std::string > argSearchDir("d", "directory", "Directory in which to search for *.icplog files.", false, ".", ".", cmd)
mp2p_icp::Pairings
Definition: Pairings.h:76
mp2p_icp::LogRecord::LoadFromFile
static LogRecord LoadFromFile(const std::string &fileName)
Definition: LogRecord.h:86
mp2p_icp::render_params_pairings_pt2pt_t::visible
bool visible
Definition: render_params.h:186
mp2p_icp::Coordinate::Z
@ Z
mp2p_icp::LogRecord
Definition: LogRecord.h:30
mp2p_icp::render_params_pairings_pt2pl_t::planePatchSize
double planePatchSize
Definition: render_params.h:199
mp2p_icp::pairings_render_params_t::pt2ln
render_params_pairings_pt2ln_t pt2ln
Definition: render_params.h:220
testing::internal::string
::std::string string
Definition: gtest.h:1979
argAutoPlayPeriod
static TCLAP::ValueArg< double > argAutoPlayPeriod("", "autoplay-period", "The period (in seconds) between timestamps to load and show in autoplay " "mode.", false, 0.1, "period [seconds]", cmd)
mp2p_icp::render_params_pairings_pt2ln_t::visible
bool visible
Definition: render_params.h:206
mp2p_icp::render_params_points_t::allLayers
render_params_point_layer_t allLayers
Definition: render_params.h:153
mp2p_icp::render_params_point_layer_t::color
mrpt::img::TColor color
Definition: render_params.h:124
APP_NAME
constexpr const char * APP_NAME
Definition: apps/icp-log-viewer/main.cpp:40
mp2p_icp::render_params_t
Definition: render_params.h:167
argExtension
static TCLAP::ValueArg< std::string > argExtension("e", "file-extension", "Filename extension to look for. Default is `icplog`", false, "icplog", "icplog", cmd)
main_show_gui
static void main_show_gui()
Definition: apps/icp-log-viewer/main.cpp:1158
mp2p_icp::render_params_points_t::perLayer
std::map< layer_name_t, render_params_point_layer_t > perLayer
Definition: render_params.h:157
get_user_config_file
static void get_user_config_file(char *out, unsigned int maxlen, const char *appname)
Definition: cfgpath.h:96
mp2p_icp::render_params_pairings_pt2ln_t::lineLength
double lineLength
Definition: render_params.h:210
SMALL_FONT_SIZE
constexpr int SMALL_FONT_SIZE
Definition: apps/icp-log-viewer/main.cpp:42
mp2p_icp::Pairings::get_visualization
virtual auto get_visualization(const mrpt::poses::CPose3D &localWrtGlobal, const pairings_render_params_t &p=pairings_render_params_t()) const -> std::shared_ptr< mrpt::opengl::CSetOfObjects >
Definition: Pairings.cpp:168
PointMatcherSupport::get
const M::mapped_type & get(const M &m, const typename M::key_type &k)
Definition: Bibliography.cpp:57
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:55
MID_FONT_SIZE
constexpr int MID_FONT_SIZE
Definition: apps/icp-log-viewer/main.cpp:41
mp2p_icp::pairings_render_params_t
Definition: render_params.h:214
PointMatcherSupport::pow
constexpr T pow(const T base, const std::size_t exponent)
Definition: libpointmatcher/pointmatcher/DataPointsFilters/utils/utils.h:47
mp2p_icp::render_params_points_t::visible
bool visible
Definition: render_params.h:149
kitti-batch-convert.filename
filename
Definition: kitti-batch-convert.py:6
WINDOW_FIXED_WIDTH
constexpr int WINDOW_FIXED_WIDTH
Definition: apps/icp-log-viewer/main.cpp:43
argSingleFile
static TCLAP::ValueArg< std::string > argSingleFile("f", "file", "Load just this one single log *.icplog file.", false, "log.icplog", "log.icplog", cmd)


mp2p_icp
Author(s):
autogenerated on Mon May 26 2025 02:45:49