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


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