apps/mm-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-2021 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/metricmap.h>
16 // using this:
17 #include <mrpt/gui/CDisplayWindowGUI.h>
18 
19 // other deps:
21 #include <mrpt/3rdparty/tclap/CmdLine.h>
22 #include <mrpt/config.h>
23 #include <mrpt/config/CConfigFile.h>
24 #include <mrpt/core/round.h>
25 #include <mrpt/math/TObject3D.h>
26 #include <mrpt/math/geometry.h>
27 #include <mrpt/opengl/CArrow.h>
28 #include <mrpt/opengl/CGridPlaneXY.h>
29 #include <mrpt/opengl/COpenGLScene.h>
30 #include <mrpt/opengl/stock_objects.h>
31 #include <mrpt/poses/CPose3DInterpolator.h>
32 #include <mrpt/system/filesystem.h>
33 #include <mrpt/system/os.h> // loadPluginModules()
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 = "mm-viewer";
41 constexpr int MID_FONT_SIZE = 14;
42 constexpr int SMALL_FONT_SIZE = 13;
43 
44 // =========== Declare supported cli switches ===========
45 static TCLAP::CmdLine cmd(APP_NAME);
46 
47 static TCLAP::UnlabeledValueArg<std::string> argMapFile(
48  "input", "Load this metric map file (*.mm)", false, "myMap.mm", "myMap.mm",
49  cmd);
50 
51 static TCLAP::ValueArg<std::string> arg_plugins(
52  "l", "load-plugins",
53  "One or more (comma separated) *.so files to load as plugins", false,
54  "foobar.so", "foobar.so", cmd);
55 
56 static TCLAP::ValueArg<std::string> arg_tumTrajectory(
57  "t", "trajectory",
58  "Also draw a trajectory, given by a TUM file trajectory.", false,
59  "trajectory.tum", "trajectory.tum", cmd);
60 
61 // =========== Declare global variables ===========
62 #if MRPT_HAS_NANOGUI
63 
64 auto glVizMap = mrpt::opengl::CSetOfObjects::Create();
65 auto glGrid = mrpt::opengl::CGridPlaneXY::Create();
66 mrpt::opengl::CSetOfObjects::Ptr glENUCorner, glMapCorner;
67 mrpt::opengl::CSetOfObjects::Ptr glTrajectory;
68 
69 mrpt::gui::CDisplayWindowGUI::Ptr win;
70 
71 std::array<nanogui::TextBox*, 2> lbMapStats = {nullptr, nullptr};
72 nanogui::CheckBox* cbApplyGeoRef = nullptr;
73 nanogui::CheckBox* cbViewOrtho = nullptr;
74 nanogui::CheckBox* cbView2D = nullptr;
75 nanogui::CheckBox* cbViewVoxelsAsPoints = nullptr;
76 nanogui::CheckBox* cbViewVoxelsFreeSpace = nullptr;
77 nanogui::CheckBox* cbColorizeMap = nullptr;
78 nanogui::CheckBox* cbKeepOriginalCloudColors = nullptr;
79 nanogui::CheckBox* cbShowGroundGrid = nullptr;
80 nanogui::Slider* slPointSize = nullptr;
81 nanogui::Slider* slTrajectoryThickness = nullptr;
82 nanogui::Slider* slMidDepthField = nullptr;
83 nanogui::Slider* slThicknessDepthField = nullptr;
84 nanogui::Slider* slCameraFOV = nullptr;
85 nanogui::Label* lbCameraFOV = nullptr;
86 nanogui::Label* lbMousePos = nullptr;
87 nanogui::Label* lbCameraPointing = nullptr;
88 nanogui::Label *lbDepthFieldValues = nullptr, *lbDepthFieldMid = nullptr,
89  *lbDepthFieldThickness = nullptr, *lbPointSize = nullptr;
90 nanogui::Label* lbTrajThick = nullptr;
91 nanogui::Widget* panelLayers = nullptr;
92 nanogui::ComboBox* cbTravellingKeys = nullptr;
93 nanogui::TextBox* edAnimFPS = nullptr;
94 nanogui::Slider* slAnimProgress = nullptr;
95 nanogui::Button * btnAnimate = nullptr, *btnAnimStop = nullptr;
96 nanogui::ComboBox* cbTravellingInterp = nullptr;
97 
98 std::vector<std::string> layerNames;
99 std::map<std::string, nanogui::CheckBox*> cbLayersByName;
100 
102 std::string theMapFileName = "unnamed.mm";
103 
104 // Robot path to display (optional):
105 mrpt::poses::CPose3DInterpolator trajectory;
106 
107 // Camera travelling trajectory:
108 mrpt::poses::CPose3DInterpolator camTravelling;
109 std::optional<double> camTravellingCurrentTime;
110 
111 constexpr float TRAV_ZOOM2ROLL = 1e-4;
112 
113 static void rebuild_3d_view();
114 static void onSaveLayers();
115 
116 namespace
117 {
118 void loadMapFile(const std::string& mapFile)
119 {
120  // Load one single file:
121  std::cout << "Loading map file: " << mapFile << std::endl;
122 
123  if (!theMap.load_from_file(mapFile))
124  {
125  std::cerr << "Error loading metric map from file!" << std::endl;
126  return;
127  }
128  theMapFileName = mapFile;
129 
130  // Obtain layer info:
131  std::cout << "Loaded map: " << theMap.contents_summary() << std::endl;
132 
133  for (const auto& [name, map] : theMap.layers) layerNames.push_back(name);
134 
135  // sanity checks:
136  for (const auto& [name, map] : theMap.layers)
137  {
138  const auto* pc = mp2p_icp::MapToPointsMap(*map);
139  if (!pc) continue; // not a point map
140  const bool sanityPassed = mp2p_icp::pointcloud_sanity_check(*pc);
141  ASSERTMSG_(
142  sanityPassed,
143  mrpt::format(
144  "sanity check did not pass for layer: '%s'", name.c_str()));
145  }
146 }
147 
148 void updateMouseCoordinates()
149 {
150  const auto mousexY = win->mousePos();
151 
152  mrpt::math::TLine3D mouse_ray;
153  win->background_scene->getViewport("main")->get3DRayForPixelCoord(
154  mousexY.x(), mousexY.y(), mouse_ray);
155 
156  // Create a 3D plane, e.g. Z=0
157  using mrpt::math::TPoint3D;
158 
159  const mrpt::math::TPlane ground_plane(
160  TPoint3D(0, 0, 0), TPoint3D(1, 0, 0), TPoint3D(0, 1, 0));
161  // Intersection of the line with the plane:
162  mrpt::math::TObject3D inters;
163  mrpt::math::intersect(mouse_ray, ground_plane, inters);
164  // Interpret the intersection as a point, if there is an intersection:
165  mrpt::math::TPoint3D inters_pt;
166  if (inters.getPoint(inters_pt))
167  {
168  lbMousePos->setCaption(mrpt::format(
169  "Mouse pointing to: X=%6.03f Y=%6.03f", inters_pt.x, inters_pt.y));
170  }
171 }
172 
173 void updateCameraLookCoordinates()
174 {
175  lbCameraPointing->setCaption(mrpt::format(
176  "Looking at: X=%6.03f Y=%6.03f Z=%6.03f",
177  win->camera().getCameraPointingX(), win->camera().getCameraPointingY(),
178  win->camera().getCameraPointingZ()));
179 }
180 
181 void observeViewOptions()
182 {
183  if (cbView2D->checked())
184  {
185  win->camera().setAzimuthDegrees(-90.0f);
186  win->camera().setElevationDegrees(90.0f);
187  }
188 }
189 
190 void updateMiniCornerView()
191 {
192  auto gl_view = win->background_scene->getViewport("small-view");
193  if (!gl_view) return;
194 
195  mrpt::opengl::CCamera& view_cam = gl_view->getCamera();
196 
197  view_cam.setAzimuthDegrees(win->camera().getAzimuthDegrees());
198  view_cam.setElevationDegrees(win->camera().getElevationDegrees());
199  view_cam.setZoomDistance(5);
200 }
201 
202 void rebuildLayerCheckboxes()
203 {
204  ASSERT_(panelLayers);
205  while (panelLayers->childCount())
206  { //
207  panelLayers->removeChild(0);
208  }
209 
210  for (size_t i = 0; i < layerNames.size(); i++)
211  {
212  auto cb = panelLayers->add<nanogui::CheckBox>(layerNames.at(i));
213  cb->setChecked(true);
214  cb->setCallback([](bool) { rebuild_3d_view(); });
215  cb->setFontSize(SMALL_FONT_SIZE);
216 
217  cbLayersByName[layerNames.at(i)] = cb;
218  }
219 }
220 
221 void rebuildCamTravellingCombo()
222 {
223  std::vector<std::string> lst, lstShort;
224  for (size_t i = 0; i < camTravelling.size(); i++)
225  {
226  auto it = camTravelling.begin();
227  std::advance(it, i);
228 
229  lstShort.push_back(std::to_string(i));
230  lst.push_back(mrpt::format(
231  "[%02u] t=%.02fs pose=%s", static_cast<unsigned int>(i),
232  mrpt::Clock::toDouble(it->first), it->second.asString().c_str()));
233  }
234  cbTravellingKeys->setItems(lst, lstShort);
235 
236  if (!lst.empty()) cbTravellingKeys->setSelectedIndex(lst.size() - 1);
237  win->performLayout();
238 }
239 
240 void onKeyboardAction(int key)
241 {
242  using mrpt::DEG2RAD;
243 
244  constexpr float SLIDE_VELOCITY = 0.01;
245  constexpr float SENSIBILITY_ROTATE = 1.0;
246 
247  auto cam = win->camera().cameraParams();
248 
249  switch (key)
250  {
251  case GLFW_KEY_UP:
252  case GLFW_KEY_DOWN:
253  case GLFW_KEY_S:
254  case GLFW_KEY_W:
255  {
256  const float dx = std::cos(DEG2RAD(cam.cameraAzimuthDeg));
257  const float dy = std::sin(DEG2RAD(cam.cameraAzimuthDeg));
258  const float d =
259  (key == GLFW_KEY_UP || key == GLFW_KEY_W) ? -1.0f : 1.0f;
260  cam.cameraPointingX +=
261  d * dx * cam.cameraZoomDistance * SLIDE_VELOCITY;
262  cam.cameraPointingY +=
263  d * dy * cam.cameraZoomDistance * SLIDE_VELOCITY;
264  win->camera().setCameraParams(cam);
265  }
266  break;
267 
268  case GLFW_KEY_A:
269  case GLFW_KEY_D:
270  {
271  const float dx = std::cos(DEG2RAD(cam.cameraAzimuthDeg + 90.f));
272  const float dy = std::sin(DEG2RAD(cam.cameraAzimuthDeg + 90.f));
273  const float d = key == GLFW_KEY_A ? -1.0f : 1.0f;
274  cam.cameraPointingX +=
275  d * dx * cam.cameraZoomDistance * SLIDE_VELOCITY;
276  cam.cameraPointingY +=
277  d * dy * cam.cameraZoomDistance * SLIDE_VELOCITY;
278  win->camera().setCameraParams(cam);
279  }
280  break;
281 
282  case GLFW_KEY_RIGHT:
283  case GLFW_KEY_LEFT:
284  {
285  int cmd_rot = key == GLFW_KEY_LEFT ? -1 : 1;
286  int cmd_elev = 0;
287 
288  const float dis = std::max(0.01f, (cam.cameraZoomDistance));
289  float eye_x =
290  cam.cameraPointingX + dis * cos(DEG2RAD(cam.cameraAzimuthDeg)) *
291  cos(DEG2RAD(cam.cameraElevationDeg));
292  float eye_y =
293  cam.cameraPointingY + dis * sin(DEG2RAD(cam.cameraAzimuthDeg)) *
294  cos(DEG2RAD(cam.cameraElevationDeg));
295  float eye_z = cam.cameraPointingZ +
296  dis * sin(DEG2RAD(cam.cameraElevationDeg));
297 
298  // Orbit camera:
299  float A_AzimuthDeg = -SENSIBILITY_ROTATE * cmd_rot;
300  cam.cameraAzimuthDeg += A_AzimuthDeg;
301 
302  float A_ElevationDeg = SENSIBILITY_ROTATE * cmd_elev;
303  cam.setElevationDeg(cam.cameraElevationDeg + A_ElevationDeg);
304 
305  // Move cameraPointing pos:
306  cam.cameraPointingX =
307  eye_x - dis * cos(DEG2RAD(cam.cameraAzimuthDeg)) *
308  cos(DEG2RAD(cam.cameraElevationDeg));
309  cam.cameraPointingY =
310  eye_y - dis * sin(DEG2RAD(cam.cameraAzimuthDeg)) *
311  cos(DEG2RAD(cam.cameraElevationDeg));
312  cam.cameraPointingZ =
313  eye_z - dis * sin(DEG2RAD(cam.cameraElevationDeg));
314 
315  win->camera().setCameraParams(cam);
316  }
317  break;
318  };
319 }
320 
321 void camTravellingStop()
322 {
323  camTravellingCurrentTime.reset();
324  btnAnimate->setEnabled(true);
325  btnAnimStop->setEnabled(false);
326 }
327 
328 void processCameraTravelling()
329 {
330  if (!camTravellingCurrentTime.has_value()) return;
331  double& t = camTravellingCurrentTime.value();
332 
333  // Time range:
334  const double t0 = mrpt::Clock::toDouble(camTravelling.begin()->first);
335  const double t1 = mrpt::Clock::toDouble(camTravelling.rbegin()->first);
336  slAnimProgress->setRange(std::make_pair<float>(t0, t1));
337  slAnimProgress->setValue(t);
338 
339  if (t >= t1)
340  {
341  camTravellingStop();
342  return;
343  }
344 
345  // Interpolate camera params:
346  const auto interpMethod =
347  cbTravellingInterp->selectedIndex() == 0
348  ? mrpt::poses::TInterpolatorMethod::imLinear2Neig
349  : mrpt::poses::TInterpolatorMethod::imSSLSLL;
350  camTravelling.setInterpolationMethod(interpMethod);
351 
352  mrpt::math::TPose3D p;
353  bool valid = false;
354  camTravelling.interpolate(mrpt::Clock::fromDouble(t), p, valid);
355  if (valid)
356  {
357  win->camera().setCameraPointing(p.x, p.y, p.z);
358  win->camera().setAzimuthDegrees(mrpt::RAD2DEG(p.yaw));
359  win->camera().setElevationDegrees(mrpt::RAD2DEG(p.pitch));
360  win->camera().setZoomDistance(p.roll / TRAV_ZOOM2ROLL);
361  }
362 
363  // Move to next time step:
364  const double FPS = std::stod(edAnimFPS->value());
365  ASSERT_(FPS > 0);
366  const double dt = 1.0 / FPS;
367  t += dt;
368 }
369 
370 void main_show_gui()
371 {
372  using namespace std::string_literals;
373 
374  if (argMapFile.isSet()) { loadMapFile(argMapFile.getValue()); }
375 
376  // Get user app config file
377  char appCfgFile[1024];
378  ::get_user_config_file(appCfgFile, sizeof(appCfgFile), APP_NAME);
379  mrpt::config::CConfigFile appCfg(appCfgFile);
380 
381  /*
382  * -------------------------------------------------------------------
383  * GUI
384  * --------------------------------------------------------------------
385  */
386  nanogui::init();
387 
388  mrpt::gui::CDisplayWindowGUI_Params cp;
389  cp.maximized = true;
390  win = mrpt::gui::CDisplayWindowGUI::Create(APP_NAME, 1024, 800, cp);
391 
392  // Add a background scene:
393  auto scene = mrpt::opengl::COpenGLScene::Create();
394  {
395  glGrid->setColor_u8(0xff, 0xff, 0xff, 0x10);
396  scene->insert(glGrid);
397  }
398 
399  glMapCorner = mrpt::opengl::stock_objects::CornerXYZ(1.0f);
400  glMapCorner->setName("map");
401  glMapCorner->enableShowName();
402 
403  glTrajectory = mrpt::opengl::CSetOfObjects::Create();
404 
405  glENUCorner = mrpt::opengl::stock_objects::CornerXYZ(2.0f);
406  glENUCorner->setName("ENU");
407  glENUCorner->enableShowName();
408  scene->insert(glENUCorner);
409 
410  scene->insert(glVizMap);
411 
412  {
413  std::lock_guard<std::mutex> lck(win->background_scene_mtx);
414  win->background_scene = std::move(scene);
415  }
416 
417  // Control GUI sub-window:
418  {
419  auto w = win->createManagedSubWindow("Map viewer");
420  w->setPosition({5, 25});
421  w->requestFocus();
422  w->setLayout(new nanogui::BoxLayout(
423  nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 5, 2));
424  w->setFixedWidth(350);
425 
426  for (size_t i = 0; i < lbMapStats.size(); i++)
427  {
428  auto& lb = lbMapStats[i];
429 
430  if (i == 0)
431  {
432  auto pn = w->add<nanogui::Widget>();
433  pn->setLayout(new nanogui::BoxLayout(
434  nanogui::Orientation::Horizontal,
435  nanogui::Alignment::Fill));
436  lb = pn->add<nanogui::TextBox>(" ");
437  lb->setFixedWidth(300);
438  auto btnLoad =
439  pn->add<nanogui::Button>("", ENTYPO_ICON_ARCHIVE);
440  btnLoad->setCallback(
441  []()
442  {
443  try
444  {
445  const auto fil = nanogui::file_dialog(
446  {{"mm", "Metric maps (*.mm)"}}, false);
447  if (fil.empty()) return;
448 
449  loadMapFile(fil);
450  rebuildLayerCheckboxes();
451  win->performLayout();
452  rebuild_3d_view();
453  }
454  catch (const std::exception& e)
455  {
456  std::cerr << e.what() << std::endl;
457  }
458  });
459  }
460  else { lb = w->add<nanogui::TextBox>(" "); }
461 
462  lb->setFontSize(MID_FONT_SIZE);
463  lb->setAlignment(nanogui::TextBox::Alignment::Left);
464  lb->setEditable(true);
465  }
466 
467  //
468  w->add<nanogui::Label>(" "); // separator
469 
470  auto tabWidget = w->add<nanogui::TabWidget>();
471 
472  auto* tab1 = tabWidget->createTab("View");
473  tab1->setLayout(new nanogui::GroupLayout());
474 
475  auto* tab2 = tabWidget->createTab("Maps");
476  tab2->setLayout(new nanogui::BoxLayout(
477  nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
478 
479  auto* tab3 = tabWidget->createTab("Travelling");
480  tab3->setLayout(new nanogui::BoxLayout(
481  nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
482 
483  tabWidget->setActiveTab(0);
484 
485  // --------------------------------------------------------------
486  // Tab: Map layers
487  // --------------------------------------------------------------
488  tab2->add<nanogui::Label>("Render options:");
489 
490  {
491  auto pn = tab2->add<nanogui::Widget>();
492  pn->setLayout(new nanogui::GridLayout(
493  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
494 
495  lbPointSize = pn->add<nanogui::Label>("Point size");
496  lbPointSize->setFontSize(MID_FONT_SIZE);
497 
498  slPointSize = pn->add<nanogui::Slider>();
499  slPointSize->setRange({1.0f, 10.0f});
500  slPointSize->setValue(2.0f);
501  slPointSize->setCallback([&](float) { rebuild_3d_view(); });
502  }
503 
504  cbViewVoxelsAsPoints =
505  tab2->add<nanogui::CheckBox>("Render voxel maps as point clouds");
506  cbViewVoxelsAsPoints->setFontSize(MID_FONT_SIZE);
507  cbViewVoxelsAsPoints->setChecked(false);
508  cbViewVoxelsAsPoints->setCallback([&](bool) { rebuild_3d_view(); });
509 
510  cbViewVoxelsFreeSpace =
511  tab2->add<nanogui::CheckBox>("Render free space of voxel maps");
512  cbViewVoxelsFreeSpace->setFontSize(MID_FONT_SIZE);
513  cbViewVoxelsFreeSpace->setChecked(false);
514  cbViewVoxelsFreeSpace->setCallback([&](bool) { rebuild_3d_view(); });
515 
516  cbColorizeMap = tab2->add<nanogui::CheckBox>("Recolorize map points");
517  cbColorizeMap->setFontSize(MID_FONT_SIZE);
518  cbColorizeMap->setChecked(true);
519  cbColorizeMap->setCallback([&](bool) { rebuild_3d_view(); });
520 
521  cbKeepOriginalCloudColors =
522  tab2->add<nanogui::CheckBox>("Keep original cloud colors");
523  cbKeepOriginalCloudColors->setFontSize(MID_FONT_SIZE);
524  cbKeepOriginalCloudColors->setChecked(false);
525  cbKeepOriginalCloudColors->setCallback([&](bool)
526  { rebuild_3d_view(); });
527 
528  tab2->add<nanogui::Label>(" ");
529  {
530  auto pn = tab2->add<nanogui::Widget>();
531  pn->setLayout(new nanogui::GridLayout(
532  nanogui::Orientation::Horizontal, 4, nanogui::Alignment::Fill));
533  pn->add<nanogui::Label>("Visible layers:");
534 
535  auto* btnCheckAll = pn->add<nanogui::Button>("", ENTYPO_ICON_CHECK);
536  btnCheckAll->setFontSize(SMALL_FONT_SIZE);
537  btnCheckAll->setCallback(
538  []()
539  {
540  for (auto& [name, cb] : cbLayersByName)
541  cb->setChecked(true);
542 
543  rebuild_3d_view();
544  });
545 
546  auto* btnCheckNone =
547  pn->add<nanogui::Button>("", ENTYPO_ICON_CIRCLE_WITH_CROSS);
548  btnCheckNone->setFontSize(SMALL_FONT_SIZE);
549  btnCheckNone->setCallback(
550  []()
551  {
552  for (auto& [name, cb] : cbLayersByName)
553  cb->setChecked(false);
554  rebuild_3d_view();
555  });
556  }
557 
558  panelLayers = tab2->add<nanogui::Widget>();
559  panelLayers->setLayout(new nanogui::BoxLayout(
560  nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
561 
562  rebuildLayerCheckboxes();
563 
564  {
565  tab2->add<nanogui::Label>(" "); // separator
566  auto btnSave =
567  tab2->add<nanogui::Button>("Export marked layers...");
568  btnSave->setFontSize(MID_FONT_SIZE);
569  btnSave->setCallback([]() { onSaveLayers(); });
570  }
571 
572  // --------------------------------------------------------------
573  // Tab: View
574  // --------------------------------------------------------------
575  {
576  auto pn = tab1->add<nanogui::Widget>();
577  pn->setLayout(new nanogui::GridLayout(
578  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
579 
580  lbTrajThick = pn->add<nanogui::Label>("Trajectory thickness:");
581  lbTrajThick->setFontSize(MID_FONT_SIZE);
582 
583  slTrajectoryThickness = pn->add<nanogui::Slider>();
584  slTrajectoryThickness->setEnabled(trajectory.size() >= 2);
585  slTrajectoryThickness->setRange({std::log(0.005f), std::log(2.0f)});
586  slTrajectoryThickness->setValue(std::log(0.05f));
587  slTrajectoryThickness->setCallback(
588  [&](float)
589  {
590  glTrajectory->clear(); // force rebuild
591  rebuild_3d_view();
592  });
593  }
594 
595  {
596  auto pn = tab1->add<nanogui::Widget>();
597  pn->setLayout(new nanogui::GridLayout(
598  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
599 
600  lbDepthFieldMid =
601  pn->add<nanogui::Label>("Center depth clip plane:");
602  lbDepthFieldMid->setFontSize(MID_FONT_SIZE);
603 
604  slMidDepthField = pn->add<nanogui::Slider>();
605  slMidDepthField->setRange({-2.0, 3.0});
606  slMidDepthField->setValue(1.0f);
607  slMidDepthField->setCallback([&](float) { rebuild_3d_view(); });
608  }
609 
610  {
611  auto pn = tab1->add<nanogui::Widget>();
612  pn->setLayout(new nanogui::GridLayout(
613  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
614 
615  lbDepthFieldThickness =
616  pn->add<nanogui::Label>("Max-Min depth thickness:");
617  lbDepthFieldThickness->setFontSize(MID_FONT_SIZE);
618 
619  slThicknessDepthField = pn->add<nanogui::Slider>();
620  slThicknessDepthField->setRange({-2.0, 6.0});
621  slThicknessDepthField->setValue(3.0);
622  slThicknessDepthField->setCallback([&](float)
623  { rebuild_3d_view(); });
624  }
625  {
626  auto pn = tab1->add<nanogui::Widget>();
627  pn->setLayout(new nanogui::GridLayout(
628  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
629 
630  lbCameraFOV = pn->add<nanogui::Label>("Camera FOV:");
631  lbCameraFOV->setFontSize(MID_FONT_SIZE);
632  slCameraFOV = pn->add<nanogui::Slider>();
633  slCameraFOV->setRange({20.0f, 170.0f});
634  slCameraFOV->setValue(90.0f);
635  slCameraFOV->setCallback([&](float) { rebuild_3d_view(); });
636  }
637  lbDepthFieldValues = tab1->add<nanogui::Label>(" ");
638  lbDepthFieldValues->setFontSize(MID_FONT_SIZE);
639 
640  {
641  auto pn = tab1->add<nanogui::Widget>();
642  pn->setLayout(new nanogui::GridLayout(
643  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
644 
645  cbViewOrtho = pn->add<nanogui::CheckBox>("Orthogonal view");
646  cbViewOrtho->setFontSize(MID_FONT_SIZE);
647  cbViewOrtho->setCallback([&](bool) { rebuild_3d_view(); });
648  cbViewOrtho->setFontSize(MID_FONT_SIZE);
649 
650  cbView2D = pn->add<nanogui::CheckBox>("Force 2D view");
651  cbView2D->setFontSize(MID_FONT_SIZE);
652  cbView2D->setCallback([&](bool) { rebuild_3d_view(); });
653  }
654 
655  cbShowGroundGrid = tab1->add<nanogui::CheckBox>("Show ground grid");
656  cbShowGroundGrid->setFontSize(MID_FONT_SIZE);
657  cbShowGroundGrid->setChecked(true);
658  cbShowGroundGrid->setCallback([&](bool) { rebuild_3d_view(); });
659 
660  cbApplyGeoRef = tab1->add<nanogui::CheckBox>(
661  "Apply georeferenced pose (if available)");
662  cbApplyGeoRef->setFontSize(MID_FONT_SIZE);
663  cbApplyGeoRef->setCallback([&](bool) { rebuild_3d_view(); });
664 
665  // --------------------------------------------------------------
666  // Tab: Travelling
667  // --------------------------------------------------------------
668  tab3->add<nanogui::Label>("Define camera travelling paths");
669 
670  {
671  auto pn = tab3->add<nanogui::Widget>();
672  pn->setLayout(new nanogui::GridLayout(
673  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
674 
675  auto lb = pn->add<nanogui::Label>("Keyframes:");
676  lb->setFontSize(MID_FONT_SIZE);
677 
678  cbTravellingKeys = tab3->add<nanogui::ComboBox>();
679  cbTravellingKeys->setFontSize(MID_FONT_SIZE);
680  }
681  rebuildCamTravellingCombo();
682 
683  tab3->add<nanogui::Label>("");
684 
685  nanogui::TextBox* edTime;
686  {
687  auto pn = tab3->add<nanogui::Widget>();
688  pn->setLayout(new nanogui::GridLayout(
689  nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
690 
691  pn->add<nanogui::Label>("New keyframe:")
692  ->setFontSize(MID_FONT_SIZE);
693 
694  edTime = pn->add<nanogui::TextBox>();
695  edTime->setAlignment(nanogui::TextBox::Alignment::Left);
696  edTime->setValue("0.0");
697  edTime->setEditable(true);
698  edTime->setPlaceholder("Time for this keyframe [s]");
699  edTime->setFormat("[0-9\\.]*");
700  edTime->setFontSize(MID_FONT_SIZE);
701 
702  auto btnAdd =
703  pn->add<nanogui::Button>("Add", ENTYPO_ICON_ADD_TO_LIST);
704  btnAdd->setFontSize(MID_FONT_SIZE);
705  btnAdd->setCallback(
706  [edTime]()
707  {
708  const auto p = mrpt::math::TPose3D(
709  win->camera().cameraParams().cameraPointingX,
710  win->camera().cameraParams().cameraPointingY,
711  win->camera().cameraParams().cameraPointingZ,
712  mrpt::DEG2RAD(
713  win->camera().cameraParams().cameraAzimuthDeg),
714  mrpt::DEG2RAD(
715  win->camera().cameraParams().cameraElevationDeg),
716  win->camera().cameraParams().cameraZoomDistance *
717  TRAV_ZOOM2ROLL);
718  camTravelling.insert(
719  mrpt::Clock::fromDouble(std::stod(edTime->value())), p);
720  rebuildCamTravellingCombo();
721 
722  edTime->setValue(
723  std::to_string(std::stod(edTime->value()) + 1));
724  });
725  }
726 
727  tab3->add<nanogui::Label>("");
728 
729  {
730  auto pn = tab3->add<nanogui::Widget>();
731  pn->setLayout(new nanogui::GridLayout(
732  nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
733 
734  pn->add<nanogui::Label>("Playback:");
735  btnAnimate =
736  pn->add<nanogui::Button>("", ENTYPO_ICON_CONTROLLER_PLAY);
737  btnAnimate->setFontSize(MID_FONT_SIZE);
738  btnAnimate->setCallback(
739  []()
740  {
741  if (camTravelling.empty()) return;
742  camTravellingCurrentTime.emplace(
743  mrpt::Clock::toDouble(camTravelling.begin()->first));
744  btnAnimate->setEnabled(false);
745  btnAnimStop->setEnabled(true);
746  });
747  btnAnimStop =
748  pn->add<nanogui::Button>("", ENTYPO_ICON_CIRCLE_WITH_CROSS);
749  btnAnimStop->setFontSize(MID_FONT_SIZE);
750  btnAnimStop->setEnabled(false);
751  btnAnimStop->setCallback([]() { camTravellingStop(); });
752  }
753 
754  {
755  auto pn = tab3->add<nanogui::Widget>();
756  pn->setLayout(new nanogui::GridLayout(
757  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
758 
759  auto lb = pn->add<nanogui::Label>("Animation FPS:");
760  lb->setFontSize(MID_FONT_SIZE);
761 
762  edAnimFPS = pn->add<nanogui::TextBox>("30.0");
763  edAnimFPS->setFontSize(MID_FONT_SIZE);
764  edAnimFPS->setFormat("[0-9\\.]*");
765  edAnimFPS->setEditable(true);
766  }
767  {
768  auto pn = tab3->add<nanogui::Widget>();
769  pn->setLayout(new nanogui::GridLayout(
770  nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
771 
772  auto lb = pn->add<nanogui::Label>("Interpolation:");
773  lb->setFontSize(MID_FONT_SIZE);
774 
775  cbTravellingInterp = pn->add<nanogui::ComboBox>();
776  cbTravellingInterp->setFontSize(MID_FONT_SIZE);
777  cbTravellingInterp->setItems({"Linear", "Spline"});
778  cbTravellingInterp->setSelectedIndex(0);
779  }
780 
781  slAnimProgress = tab3->add<nanogui::Slider>();
782  slAnimProgress->setEnabled(false);
783 
784  // ---
785  lbMousePos = w->add<nanogui::Label>("Mouse pointing to:");
786  lbMousePos->setFontSize(MID_FONT_SIZE);
787  lbCameraPointing = w->add<nanogui::Label>("Camera looking at:");
788  lbCameraPointing->setFontSize(MID_FONT_SIZE);
789 
790  w->add<nanogui::Button>("Quit", ENTYPO_ICON_ARROW_BOLD_LEFT)
791  ->setCallback([]() { win->setVisible(false); });
792 
793  win->setKeyboardCallback(
794  [&](int key, [[maybe_unused]] int scancode, int action,
795  [[maybe_unused]] int modifiers)
796  {
797  if (action != GLFW_PRESS && action != GLFW_REPEAT) return false;
798 
799  onKeyboardAction(key);
800 
801  return false;
802  });
803  }
804 
805  // --------------------------------------------------------------
806  // ^^^^^^^^ GUI definition done ^^^^^^^^
807  // --------------------------------------------------------------
808  win->performLayout();
809  win->camera().setCameraPointing(8.0f, .0f, .0f);
810  win->camera().setAzimuthDegrees(110.0f);
811  win->camera().setElevationDegrees(15.0f);
812  win->camera().setZoomDistance(50.0f);
813 
814  // save and load UI state:
815 #define LOAD_CB_STATE(CB_NAME__) do_cb(CB_NAME__, #CB_NAME__)
816 #define SAVE_CB_STATE(CB_NAME__) \
817  appCfg.write("", #CB_NAME__, CB_NAME__->checked())
818 
819 #define LOAD_SL_STATE(SL_NAME__) do_sl(SL_NAME__, #SL_NAME__)
820 #define SAVE_SL_STATE(SL_NAME__) \
821  appCfg.write("", #SL_NAME__, SL_NAME__->value())
822 
823  auto load_UI_state_from_user_config = [&]()
824  {
825  auto do_cb = [&](nanogui::CheckBox* cb, const std::string& name)
826  { cb->setChecked(appCfg.read_bool("", name, cb->checked())); };
827  auto do_sl = [&](nanogui::Slider* sl, const std::string& name)
828  { sl->setValue(appCfg.read_float("", name, sl->value())); };
829 
830  LOAD_CB_STATE(cbApplyGeoRef);
831  LOAD_CB_STATE(cbViewOrtho);
832  LOAD_CB_STATE(cbView2D);
833  LOAD_CB_STATE(cbViewVoxelsAsPoints);
834  LOAD_CB_STATE(cbViewVoxelsFreeSpace);
835  LOAD_CB_STATE(cbColorizeMap);
836  LOAD_CB_STATE(cbKeepOriginalCloudColors);
837  LOAD_CB_STATE(cbShowGroundGrid);
838 
839  LOAD_SL_STATE(slPointSize);
840  LOAD_SL_STATE(slTrajectoryThickness);
841  LOAD_SL_STATE(slMidDepthField);
842  LOAD_SL_STATE(slThicknessDepthField);
843  LOAD_SL_STATE(slCameraFOV);
844 
845  win->camera().setCameraPointing(
846  appCfg.read_float("", "cam_x", win->camera().getCameraPointingX()),
847  appCfg.read_float("", "cam_y", win->camera().getCameraPointingY()),
848  appCfg.read_float("", "cam_z", win->camera().getCameraPointingZ()));
849  win->camera().setAzimuthDegrees(
850  appCfg.read_float("", "cam_az", win->camera().getAzimuthDegrees()));
851  win->camera().setElevationDegrees(appCfg.read_float(
852  "", "cam_el", win->camera().getElevationDegrees()));
853  win->camera().setZoomDistance(
854  appCfg.read_float("", "cam_d", win->camera().getZoomDistance()));
855  };
856  auto save_UI_state_to_user_config = [&]()
857  {
858  SAVE_CB_STATE(cbApplyGeoRef);
859  SAVE_CB_STATE(cbViewOrtho);
860  SAVE_CB_STATE(cbView2D);
861  SAVE_CB_STATE(cbViewVoxelsAsPoints);
862  SAVE_CB_STATE(cbViewVoxelsFreeSpace);
863  SAVE_CB_STATE(cbColorizeMap);
864  SAVE_CB_STATE(cbKeepOriginalCloudColors);
865  SAVE_CB_STATE(cbShowGroundGrid);
866 
867  SAVE_SL_STATE(slPointSize);
868  SAVE_SL_STATE(slTrajectoryThickness);
869  SAVE_SL_STATE(slMidDepthField);
870  SAVE_SL_STATE(slThicknessDepthField);
871  SAVE_SL_STATE(slCameraFOV);
872 
873  appCfg.write("", "cam_x", win->camera().getCameraPointingX());
874  appCfg.write("", "cam_y", win->camera().getCameraPointingY());
875  appCfg.write("", "cam_z", win->camera().getCameraPointingZ());
876  appCfg.write("", "cam_az", win->camera().getAzimuthDegrees());
877  appCfg.write("", "cam_el", win->camera().getElevationDegrees());
878  appCfg.write("", "cam_d", win->camera().getZoomDistance());
879  };
880 
881  // load UI state from last session:
882  load_UI_state_from_user_config();
883 
884  // Build 3D:
885  rebuild_3d_view();
886 
887  // Main loop
888  // ---------------------
889  win->drawAll();
890  win->setVisible(true);
891 
892  win->addLoopCallback(
893  [&]()
894  {
895  updateMouseCoordinates();
896  updateCameraLookCoordinates();
897  observeViewOptions();
898  updateMiniCornerView();
899  processCameraTravelling();
900  });
901 
902  nanogui::mainloop(1 /*loop callbacks Hz*/, -1 /* no force repaint */);
903 
904  nanogui::shutdown();
905 
906  // save UI state:
907  save_UI_state_to_user_config();
908 }
909 
910 } // namespace
911 // ==============================
912 // rebuild_3d_view
913 // ==============================
914 void rebuild_3d_view()
915 {
916  using namespace std::string_literals;
917 
918  lbMapStats[0]->setValue(theMapFileName);
919  lbMapStats[1]->setValue("Map: "s + theMap.contents_summary());
920 
921  cbApplyGeoRef->setEnabled(theMap.georeferencing.has_value());
922 
923  // 3D objects -------------------
924  std::optional<mrpt::math::TBoundingBoxf> mapBbox;
925 
926  // the map:
928 
929  rpMap.points.visible = false;
930  for (const auto& [lyName, cb] : cbLayersByName)
931  {
932  // Update stats in the cb label:
933  cb->setCaption(lyName); // default
934  if (auto itL = theMap.layers.find(lyName); itL != theMap.layers.end())
935  {
936  if (auto pc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
937  itL->second);
938  pc)
939  {
940  cb->setCaption(
941  lyName + " | "s +
942  mrpt::system::unitsFormat(
943  static_cast<double>(pc->size()), 2, false) +
944  " points"s + " | class="s +
945  pc->GetRuntimeClass()->className);
946 
947  const auto bb = pc->boundingBox();
948  if (!mapBbox.has_value())
949  mapBbox = bb;
950  else { mapBbox = mapBbox->unionWith(bb); }
951  }
952  else
953  {
954  cb->setCaption(
955  lyName + " | class="s +
956  itL->second->GetRuntimeClass()->className);
957  }
958  }
959 
960  // show/hide:
961  if (!cb->checked()) continue; // hidden
962  rpMap.points.visible = true;
963 
964  auto& rpL = rpMap.points.perLayer[lyName];
965  rpL.pointSize = slPointSize->value();
966  rpL.render_voxelmaps_as_points = cbViewVoxelsAsPoints->checked();
967  rpL.render_voxelmaps_free_space = cbViewVoxelsFreeSpace->checked();
968 
969  lbPointSize->setCaption("Point size: " + std::to_string(rpL.pointSize));
970 
971  if (cbColorizeMap->checked())
972  {
973  auto& cm = rpL.colorMode.emplace();
974  cm.colorMap = mrpt::img::TColormap::cmJET;
975  cm.recolorizeByCoordinate = mp2p_icp::Coordinate::Z;
976  }
977  if (cbKeepOriginalCloudColors->checked())
978  {
979  auto& cm = rpL.colorMode.emplace();
980  cm.keep_original_cloud_color = true;
981  }
982  }
983 
984  // Default color:
985  for (auto& [layer, rp] : rpMap.points.perLayer)
986  rp.color = mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
987 
988  // Regenerate points opengl representation only if some parameter changed:
989  static std::optional<mp2p_icp::render_params_t> prevRenderParams;
990 
991  if (!prevRenderParams.has_value() || prevRenderParams.value() != rpMap)
992  {
993  prevRenderParams = rpMap;
994  glVizMap->clear();
995 
996  auto glPts = theMap.get_visualization(rpMap);
997 
998  // Show all or selected layers:
999  rpMap.points.allLayers.color =
1000  mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
1001 
1002  glVizMap->insert(glPts);
1003  glVizMap->insert(glMapCorner);
1004  glVizMap->insert(glTrajectory);
1005  }
1006 
1007  if (cbApplyGeoRef->checked() && theMap.georeferencing.has_value())
1008  {
1009  glVizMap->setPose(theMap.georeferencing->T_enu_to_map.mean);
1010  glGrid->setPose(theMap.georeferencing->T_enu_to_map.mean);
1011  glENUCorner->setVisibility(true);
1012  }
1013  else
1014  {
1015  glVizMap->setPose(mrpt::poses::CPose3D::Identity());
1016  glGrid->setPose(mrpt::poses::CPose3D::Identity());
1017  glENUCorner->setVisibility(false);
1018  }
1019 
1020  // ground grid:
1021  if (mapBbox)
1022  {
1023  glGrid->setPlaneLimits(
1024  mapBbox->min.x, mapBbox->max.x, mapBbox->min.y, mapBbox->max.y);
1025  }
1026  glGrid->setVisibility(cbShowGroundGrid->checked());
1027 
1028  // glTrajectory:
1029  if (glTrajectory->empty() && trajectory.size() >= 2)
1030  {
1031  const float trajCylRadius = std::exp(slTrajectoryThickness->value());
1032  lbTrajThick->setCaption(
1033  "Traj. thickness: " + std::to_string(trajCylRadius));
1034 
1035  std::optional<mrpt::math::TPose3D> prevPose;
1036  for (const auto& [t, p] : trajectory)
1037  {
1038  if (prevPose)
1039  {
1040  const auto& p0 = prevPose.value();
1041 
1042  auto glSegment = mrpt::opengl::CArrow::Create();
1043  glSegment->setArrowEnds(p0.translation(), p.translation());
1044  glSegment->setHeadRatio(.0);
1045  glSegment->setLargeRadius(trajCylRadius);
1046  glSegment->setSmallRadius(trajCylRadius);
1047  glSegment->setColor_u8(0x30, 0x30, 0x30, 0xff);
1048 
1049  glTrajectory->insert(glSegment);
1050  }
1051  prevPose = p;
1052  }
1053  }
1054 
1055  // XYZ corner overlay viewport:
1056  {
1057  auto gl_view = win->background_scene->createViewport("small-view");
1058 
1059  gl_view->setViewportPosition(0, 0, 0.1, 0.1 * 16.0 / 9.0);
1060  gl_view->setTransparent(true);
1061  {
1062  mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create("X");
1063  obj->setLocation(1.1, 0, 0);
1064  gl_view->insert(obj);
1065  }
1066  {
1067  mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create("Y");
1068  obj->setLocation(0, 1.1, 0);
1069  gl_view->insert(obj);
1070  }
1071  {
1072  mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create("Z");
1073  obj->setLocation(0, 0, 1.1);
1074  gl_view->insert(obj);
1075  }
1076  gl_view->insert(mrpt::opengl::stock_objects::CornerXYZ());
1077  }
1078 
1079  // Global view options:
1080  {
1081  std::lock_guard<std::mutex> lck(win->background_scene_mtx);
1082  win->camera().setCameraProjective(
1083  !cbViewOrtho->checked() && !cbView2D->checked());
1084 
1085  // clip planes:
1086  const auto depthFieldMid = std::pow(10.0, slMidDepthField->value());
1087  const auto depthFieldThickness =
1088  std::pow(10.0, slThicknessDepthField->value());
1089 
1090  const auto clipNear =
1091  std::max(1e-2, depthFieldMid - 0.5 * depthFieldThickness);
1092  const auto clipFar = depthFieldMid + 0.5 * depthFieldThickness;
1093 
1094  const float cameraFOV = slCameraFOV->value();
1095  win->camera().setCameraFOV(cameraFOV);
1096  win->camera().setMaximumZoom(std::max<double>(1000, 3.0 * clipFar));
1097 
1098  lbDepthFieldValues->setCaption(
1099  mrpt::format("Depth field: near=%g far=%g", clipNear, clipFar));
1100  lbDepthFieldMid->setCaption(
1101  mrpt::format("Frustrum center: %.03g", depthFieldMid));
1102  lbDepthFieldThickness->setCaption(
1103  mrpt::format("Frustum thickness: %.03g", depthFieldThickness));
1104 
1105  lbDepthFieldValues->setCaption(
1106  mrpt::format("Frustum: near=%.02g far=%.02g", clipNear, clipFar));
1107 
1108  lbCameraFOV->setCaption(
1109  mrpt::format("Camera FOV: %.02f deg", cameraFOV));
1110 
1111  win->background_scene->getViewport()->setViewportClipDistances(
1112  clipNear, clipFar);
1113  }
1114 }
1115 
1116 void onSaveLayers()
1117 {
1118  const std::string outFile =
1119  nanogui::file_dialog({{"txt", "(*.txt)"}}, true /*save*/);
1120  if (outFile.empty()) return;
1121 
1122  for (const auto& [lyName, cb] : cbLayersByName)
1123  {
1124  if (auto itL = theMap.layers.find(lyName); itL != theMap.layers.end())
1125  {
1126  itL->second->saveMetricMapRepresentationToFile(outFile);
1127  }
1128  }
1129 }
1130 
1131 #else // MRPT_HAS_NANOGUI
1132 static void main_show_gui()
1133 {
1134  THROW_EXCEPTION(
1135  "This application requires a version of MRPT built with nanogui "
1136  "support.");
1137 }
1138 
1139 #endif // MRPT_HAS_NANOGUI
1140 
1141 int main(int argc, char** argv)
1142 {
1143  try
1144  {
1145  // Parse arguments:
1146  if (!cmd.parse(argc, argv)) return 1; // should exit.
1147 
1148  // Load plugins:
1149  if (arg_plugins.isSet())
1150  {
1151  std::string errMsg;
1152  const auto plugins = arg_plugins.getValue();
1153  std::cout << "Loading plugin(s): " << plugins << std::endl;
1154  if (!mrpt::system::loadPluginModules(plugins, errMsg))
1155  {
1156  std::cerr << errMsg << std::endl;
1157  return 1;
1158  }
1159  }
1160 
1161  // load trajectory?
1162  if (arg_tumTrajectory.isSet())
1163  {
1164  ASSERT_FILE_EXISTS_(arg_tumTrajectory.getValue());
1165  bool trajectoryReadOk =
1166  trajectory.loadFromTextFile_TUM(arg_tumTrajectory.getValue());
1167  ASSERT_(trajectoryReadOk);
1168  std::cout << "Read trajectory with " << trajectory.size()
1169  << " keyframes.\n";
1170  }
1171 
1172  main_show_gui();
1173  return 0;
1174  }
1175  catch (std::exception& e)
1176  {
1177  std::cerr << "Exit due to exception:\n"
1178  << mrpt::exception_to_str(e) << std::endl;
1179  return 1;
1180  }
1181 }
main_show_gui
static void main_show_gui()
Definition: apps/mm-viewer/main.cpp:1132
mp2p_icp::render_params_t::points
render_params_points_t points
Definition: render_params.h:190
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp::Coordinate::Z
@ Z
mp2p_icp::pointcloud_sanity_check
bool pointcloud_sanity_check(const mrpt::maps::CPointsMap &pc, bool printWarnings=true)
Definition: pointcloud_sanity_check.cpp:19
pointcloud_sanity_check.h
Checks for consistent length of field vectors.
testing::internal::string
::std::string string
Definition: gtest.h:1979
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)
cmd
static TCLAP::CmdLine cmd(APP_NAME)
mp2p_icp::render_params_points_t::allLayers
render_params_point_layer_t allLayers
Definition: render_params.h:166
argMapFile
static TCLAP::UnlabeledValueArg< std::string > argMapFile("input", "Load this metric map file (*.mm)", false, "myMap.mm", "myMap.mm", cmd)
arg_tumTrajectory
static TCLAP::ValueArg< std::string > arg_tumTrajectory("t", "trajectory", "Also draw a trajectory, given by a TUM file trajectory.", false, "trajectory.tum", "trajectory.tum", cmd)
APP_NAME
constexpr const char * APP_NAME
Definition: apps/mm-viewer/main.cpp:40
mp2p_icp::render_params_point_layer_t::color
mrpt::img::TColor color
Definition: render_params.h:133
mp2p_icp::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:648
main
int main(int argc, char **argv)
Definition: apps/mm-viewer/main.cpp:1141
d
d
MID_FONT_SIZE
constexpr int MID_FONT_SIZE
Definition: apps/mm-viewer/main.cpp:41
mp2p_icp::metric_map_t::contents_summary
virtual std::string contents_summary() const
Definition: metricmap.cpp:500
mp2p_icp::render_params_t
Definition: render_params.h:184
mp2p_icp::metric_map_t::get_visualization
virtual auto get_visualization(const render_params_t &p=render_params_t()) const -> std::shared_ptr< mrpt::opengl::CSetOfObjects >
Definition: metricmap.cpp:121
mp2p_icp::metric_map_t::load_from_file
bool load_from_file(const std::string &fileName)
Definition: metricmap.cpp:578
mp2p_icp::render_params_points_t::perLayer
std::map< layer_name_t, render_params_point_layer_t > perLayer
Definition: render_params.h:170
get_user_config_file
static void get_user_config_file(char *out, unsigned int maxlen, const char *appname)
Definition: cfgpath.h:96
metricmap.h
Generic representation of pointcloud(s) and/or extracted features.
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:49
mp2p_icp::metric_map_t::georeferencing
std::optional< Georeferencing > georeferencing
Definition: metricmap.h:117
SMALL_FONT_SIZE
constexpr int SMALL_FONT_SIZE
Definition: apps/mm-viewer/main.cpp:42
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:76
PointMatcherSupport::pow
constexpr T pow(const T base, const std::size_t exponent)
Definition: libpointmatcher/pointmatcher/DataPointsFilters/utils/utils.h:47
t
geometry_msgs::TransformStamped t
mp2p_icp::render_params_points_t::visible
bool visible
Definition: render_params.h:162


mp2p_icp
Author(s):
autogenerated on Wed Oct 2 2024 02:45:24