17 #include <mrpt/gui/CDisplayWindowGUI.h>
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>
38 #include "../libcfgpath/cfgpath.h"
40 constexpr
const char*
APP_NAME =
"icp-log-viewer";
49 "e",
"file-extension",
"Filename extension to look for. Default is `icplog`",
false,
"icplog",
53 "d",
"directory",
"Directory in which to search for *.icplog files.",
false,
".",
".",
cmd);
56 "f",
"file",
"Load just this one single log *.icplog file.",
false,
"log.icplog",
"log.icplog",
60 "l",
"load-plugins",
"One or more (comma separated) *.so files to load as plugins",
false,
61 "foobar.so",
"foobar.so",
cmd);
64 "",
"autoplay-period",
65 "The period (in seconds) between timestamps to load and show in autoplay "
67 false, 0.1,
"period [seconds]",
cmd);
72 auto glVizICP = mrpt::opengl::CSetOfObjects::Create();
73 mrpt::gui::CDisplayWindowGUI::Ptr win;
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;
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;
86 const size_t MAX_VARIABLE_LIST = 100;
87 std::vector<nanogui::TextBox*> lbDynVariables;
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;
96 nanogui::CheckBox* cbViewPairings =
nullptr;
98 nanogui::CheckBox* cbViewPairings_pt2pt =
nullptr;
99 nanogui::CheckBox* cbViewPairings_pt2pl =
nullptr;
100 nanogui::CheckBox* cbViewPairings_pt2ln =
nullptr;
102 nanogui::TextBox *tbLogPose =
nullptr, *tbInitialGuess =
nullptr, *tbInit2Final =
nullptr,
103 *tbCovariance =
nullptr, *tbConditionNumber =
nullptr, *tbPairings =
nullptr;
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;
114 nanogui::Slider* slGTPose[6] = {
nullptr,
nullptr,
nullptr,
nullptr,
nullptr,
nullptr};
116 std::vector<std::string> layerNames_global, layerNames_local;
118 std::map<std::string, nanogui::CheckBox*> cbLayersByName_global;
119 std::map<std::string, nanogui::CheckBox*> cbLayersByName_local;
124 DelayedLoadLog() =
default;
126 : filename_(fileName), shortFileName_(shortFileName)
141 void dispose() { log_.reset(); }
144 const std::string& shortFileName()
const {
return shortFileName_; }
147 std::optional<mp2p_icp::LogRecord> log_;
151 std::vector<DelayedLoadLog> logRecords;
153 static void rebuild_3d_view(
bool regenerateMaps =
true);
157 void rebuild_3d_view_fast() { rebuild_3d_view(
false); }
159 void processAutoPlay()
161 if (!isAutoPlayActive)
return;
163 const double tNow = mrpt::Clock::nowDouble();
166 lastAutoPlayTime = tNow;
168 if (slSelectorICP->value() < slSelectorICP->range().second - 0.01f)
170 slSelectorICP->setValue(slSelectorICP->value() + 1);
175 void updateMiniCornerView()
177 auto gl_view = win->background_scene->getViewport(
"small-view");
178 if (!gl_view)
return;
180 mrpt::opengl::CCamera& view_cam = gl_view->getCamera();
182 view_cam.setAzimuthDegrees(win->camera().getAzimuthDegrees());
183 view_cam.setElevationDegrees(win->camera().getElevationDegrees());
184 view_cam.setZoomDistance(5);
189 using namespace std::string_literals;
191 mrpt::system::CDirectoryExplorer::TFileInfoList files;
196 ASSERT_DIRECTORY_EXISTS_(searchDir);
198 std::cout <<
"Searching in: '" << searchDir <<
"' for files with extension '"
201 mrpt::system::CDirectoryExplorer::explore(searchDir, FILE_ATTRIB_ARCHIVE, files);
202 mrpt::system::CDirectoryExplorer::filterByExtension(files,
argExtension.getValue());
203 mrpt::system::CDirectoryExplorer::sortByName(files);
205 std::cout <<
"Found " << files.size() <<
" ICP records." << std::endl;
210 std::cout <<
"Loading one single log file: " <<
argSingleFile.getValue() << std::endl;
217 for (
const auto& file : files) logRecords.emplace_back(file.wholePath, file.name);
219 ASSERT_(!logRecords.empty());
223 const auto& lr = logRecords.front().get();
224 if (layerNames_global.empty() && lr.pcGlobal)
226 for (
const auto& layer : lr.pcGlobal->layers)
228 layerNames_global.push_back(layer.first);
229 std::cout <<
"Global point cloud: Found point layer='" << layer.first <<
"'\n";
232 if (layerNames_local.empty() && lr.pcLocal)
234 for (
const auto& layer : lr.pcLocal->layers)
236 layerNames_local.push_back(layer.first);
237 std::cout <<
"Local point cloud: Found point layer='" << layer.first <<
"'\n";
243 char appCfgFile[1024];
245 mrpt::config::CConfigFile appCfg(appCfgFile);
254 mrpt::gui::CDisplayWindowGUI_Params cp;
256 win = mrpt::gui::CDisplayWindowGUI::Create(
APP_NAME, 1024, 800, cp);
259 auto scene = mrpt::opengl::COpenGLScene::Create();
261 auto glGrid = mrpt::opengl::CGridPlaneXY::Create();
262 glGrid->setColor_u8(0xff, 0xff, 0xff, 0x10);
263 scene->insert(glGrid);
266 auto gl_base = mrpt::opengl::stock_objects::CornerXYZ(1.0
f);
267 gl_base->setName(
"Global");
268 gl_base->enableShowName();
269 scene->insert(gl_base);
271 scene->insert(glVizICP);
274 std::lock_guard<std::mutex> lck(win->background_scene_mtx);
275 win->background_scene = std::move(scene);
279 auto w = win->createManagedSubWindow(
"Control");
280 w->setPosition({5, 25});
283 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 5, 2));
286 cbShowInitialPose = w->add<nanogui::CheckBox>(
"Show at INITIAL GUESS pose");
287 cbShowInitialPose->setCallback(
290 if (slIterationDetails->enabled())
292 const auto& r = slIterationDetails->range();
293 slIterationDetails->setValue(v ? r.first : r.second);
295 rebuild_3d_view_fast();
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(); });
303 w->add<nanogui::Label>(
" ");
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 ) { rebuild_3d_view(); });
311 for (
auto& lb : lbICPStats)
313 lb = w->add<nanogui::TextBox>(
" ");
315 lb->setAlignment(nanogui::TextBox::Alignment::Left);
316 lb->setEditable(
true);
321 auto pn = w->add<nanogui::Widget>();
322 pn->setLayout(
new nanogui::BoxLayout(nanogui::Orientation::Horizontal));
325 auto s = slSelectorICP;
327 btnSelectorBack = pn->add<nanogui::Button>(
"", ENTYPO_ICON_CONTROLLER_FAST_BACKWARD);
328 btnSelectorBack->setCallback(
333 s->setValue(
s->value() - 1);
334 s->callback()(
s->value());
338 btnSelectorForw = pn->add<nanogui::Button>(
"", ENTYPO_ICON_CONTROLLER_FAST_FORWARD);
339 btnSelectorForw->setCallback(
342 if (
s->value() <
s->range().second - 0.01f)
344 s->setValue(
s->value() + 1);
349 pn->add<nanogui::Label>(
" ");
351 btnSelectorAutoplay = pn->add<nanogui::Button>(
"", ENTYPO_ICON_CONTROLLER_PLAY);
352 btnSelectorAutoplay->setFlags(nanogui::Button::ToggleButton);
354 btnSelectorAutoplay->setChangeCallback([&](
bool active) { isAutoPlayActive = active; });
358 w->add<nanogui::Label>(
" ");
360 auto tabWidget = w->add<nanogui::TabWidget>();
362 auto* tab1 = tabWidget->createTab(
"Summary");
364 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
366 auto* tab2 = tabWidget->createTab(
"Variables");
368 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
370 auto* tab3 = tabWidget->createTab(
"Maps");
371 tab3->setLayout(
new nanogui::GroupLayout());
373 auto* tab4 = tabWidget->createTab(
"Pairings");
374 tab4->setLayout(
new nanogui::GroupLayout());
376 auto* tab5 = tabWidget->createTab(
"View");
377 tab5->setLayout(
new nanogui::GroupLayout());
379 auto* tab6 = tabWidget->createTab(
"Manual");
380 tab6->setLayout(
new nanogui::GroupLayout());
382 tabWidget->setActiveTab(0);
385 tab1->add<nanogui::Label>(
"ICP result pose [x y z yaw(deg) pitch(deg) roll(deg)]:")
387 tbLogPose = tab1->add<nanogui::TextBox>();
389 tbLogPose->setEditable(
true);
390 tbLogPose->setAlignment(nanogui::TextBox::Alignment::Left);
393 tab1->add<nanogui::Label>(
"Initial -> final pose change:")->setFontSize(
MID_FONT_SIZE);
394 tbInit2Final = tab1->add<nanogui::TextBox>();
396 tbInit2Final->setEditable(
false);
399 tab1->add<nanogui::Label>(
"Uncertainty: diagonal sigmas (x y z yaw pitch roll)")
401 tbCovariance = tab1->add<nanogui::TextBox>();
403 tbCovariance->setEditable(
false);
406 tab1->add<nanogui::Label>(
"Uncertainty: Covariance condition numbers")
408 tbConditionNumber = tab1->add<nanogui::TextBox>();
410 tbConditionNumber->setEditable(
false);
411 tab1->add<nanogui::Label>(
" ");
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};
416 for (
int i = 0; i < 6; i++)
418 slGTPose[i] = tab6->add<nanogui::Slider>();
419 slGTPose[i]->setRange({-handTunedRange[i], handTunedRange[i]});
420 slGTPose[i]->setValue(0.0
f);
422 slGTPose[i]->setCallback(
425 const size_t idx = mrpt::round(slSelectorICP->value());
426 auto& lr = logRecords.at(idx).get();
428 auto p = lr.icpResult.optimal_tf.mean.asTPose();
430 lr.icpResult.optimal_tf.mean = mrpt::poses::CPose3D(p);
432 rebuild_3d_view_fast();
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);
446 {{
"mm",
"mp2p_icp::metric_map_t binary serialized object (*.mm)"}},
true );
447 if (outFile.empty())
return;
448 m.save_to_file(outFile);
453 tab2->add<nanogui::Label>(
"Dynamic variables:");
455 auto vscroll = tab2->add<nanogui::VScrollPanel>();
458 auto wrapper = vscroll->add<nanogui::Widget>();
462 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
464 for (
size_t i = 0; i < MAX_VARIABLE_LIST; i++)
466 auto* tb = wrapper->add<nanogui::TextBox>(
"aaaa");
467 tb->setAlignment(nanogui::TextBox::Alignment::Left);
468 tb->setEditable(
true);
470 lbDynVariables.push_back(tb);
476 auto pn = tab3->add<nanogui::Widget>();
478 new nanogui::BoxLayout(nanogui::Orientation::Horizontal, nanogui::Alignment::Fill));
479 pn->add<nanogui::Button>(
"Export 'local' map...")
483 const size_t idx = mrpt::round(slSelectorICP->value());
484 auto& lr = logRecords.at(idx).get();
486 lambdaSave(*lr.pcLocal);
488 pn->add<nanogui::Button>(
"Export 'global' map...")
492 const size_t idx = mrpt::round(slSelectorICP->value());
493 auto& lr = logRecords.at(idx).get();
494 ASSERT_(lr.pcGlobal);
495 lambdaSave(*lr.pcGlobal);
499 tab3->add<nanogui::Label>(
"[GLOBAL map] Visible layers:");
501 for (
size_t i = 0; i < layerNames_global.size(); i++)
503 auto cb = tab3->add<nanogui::CheckBox>(layerNames_global.at(i));
504 cb->setChecked(
true);
505 cb->setCallback([](
bool) { rebuild_3d_view(); });
508 cbLayersByName_global[layerNames_global.at(i)] = cb;
511 tab3->add<nanogui::Label>(
"[LOCAL map] Visible layers:");
512 for (
size_t i = 0; i < layerNames_local.size(); i++)
514 auto cb = tab3->add<nanogui::CheckBox>(layerNames_local.at(i));
515 cb->setChecked(
true);
516 cb->setCallback([](
bool) { rebuild_3d_view(); });
519 cbLayersByName_local[layerNames_local.at(i)] = cb;
523 tbPairings = tab4->add<nanogui::TextBox>();
524 tbPairings->setFontSize(16);
525 tbPairings->setEditable(
false);
527 cbViewPairings = tab4->add<nanogui::CheckBox>(
"View pairings");
528 cbViewPairings->setCallback([](
bool) { rebuild_3d_view_fast(); });
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(); });
535 auto pn = tab4->add<nanogui::Widget>();
537 new nanogui::GridLayout(nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
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(); });
543 pn->add<nanogui::Label>(
"Plane size:");
544 slPairingsPl2PlSize = pn->add<nanogui::Slider>();
545 slPairingsPl2PlSize->setRange({-2.0f, 2.0f});
546 slPairingsPl2PlSize->setValue(-1.0
f);
547 slPairingsPl2PlSize->setCallback([&](
float) { rebuild_3d_view_fast(); });
551 auto pn = tab4->add<nanogui::Widget>();
553 new nanogui::GridLayout(nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
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(); });
559 pn->add<nanogui::Label>(
"Line length:");
560 slPairingsPl2LnSize = pn->add<nanogui::Slider>();
561 slPairingsPl2LnSize->setRange({-2.0f, 2.0f});
562 slPairingsPl2LnSize->setValue(-1.0
f);
563 slPairingsPl2LnSize->setCallback([&](
float) { rebuild_3d_view_fast(); });
568 auto pn = tab5->add<nanogui::Widget>();
570 new nanogui::GridLayout(nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
572 pn->add<nanogui::Label>(
"Global map point size");
574 slGlobalPointSize = pn->add<nanogui::Slider>();
575 slGlobalPointSize->setRange({1.0f, 10.0f});
576 slGlobalPointSize->setValue(2.0
f);
577 slGlobalPointSize->setCallback([&](
float) { rebuild_3d_view(); });
580 auto pn = tab5->add<nanogui::Widget>();
582 new nanogui::GridLayout(nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
584 pn->add<nanogui::Label>(
"Local map point size");
586 slLocalPointSize = pn->add<nanogui::Slider>();
587 slLocalPointSize->setRange({1.0f, 10.0f});
588 slLocalPointSize->setValue(2.0
f);
589 slLocalPointSize->setCallback([&](
float) { rebuild_3d_view(); });
592 auto pn = tab5->add<nanogui::Widget>();
594 new nanogui::GridLayout(nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
596 lbDepthFieldMid = pn->add<nanogui::Label>(
"Center depth clip plane:");
597 slMidDepthField = pn->add<nanogui::Slider>();
599 slMidDepthField->setRange({-2.0, 3.0});
600 slMidDepthField->setValue(1.0
f);
601 slMidDepthField->setCallback([&](
float) { rebuild_3d_view_fast(); });
604 auto pn = tab5->add<nanogui::Widget>();
606 new nanogui::GridLayout(nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
608 lbDepthFieldThickness = pn->add<nanogui::Label>(
"Max-Min depth thickness:");
609 slThicknessDepthField = pn->add<nanogui::Slider>();
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>(
" ");
616 cbViewOrtho = tab5->add<nanogui::CheckBox>(
"Orthogonal view");
617 cbViewOrtho->setCallback([&](
bool) { rebuild_3d_view_fast(); });
619 cbCameraFollowsLocal = tab5->add<nanogui::CheckBox>(
"Camera follows 'local'");
620 cbCameraFollowsLocal->setCallback([&](
bool) { rebuild_3d_view_fast(); });
622 cbViewVoxelsAsPoints = tab5->add<nanogui::CheckBox>(
"Render voxel maps as point clouds");
623 cbViewVoxelsAsPoints->setChecked(
true);
624 cbViewVoxelsAsPoints->setCallback([&](
bool) { rebuild_3d_view(); });
626 cbViewVoxelsFreeSpace = tab5->add<nanogui::CheckBox>(
"Render free space of voxel maps");
627 cbViewVoxelsFreeSpace->setChecked(
false);
628 cbViewVoxelsFreeSpace->setCallback([&](
bool) { rebuild_3d_view(); });
630 cbColorizeLocalMap = tab5->add<nanogui::CheckBox>(
"Recolorize local map");
631 cbColorizeLocalMap->setCallback([&](
bool) { rebuild_3d_view(); });
633 cbColorizeGlobalMap = tab5->add<nanogui::CheckBox>(
"Recolorize global map");
634 cbColorizeGlobalMap->setCallback([&](
bool) { rebuild_3d_view(); });
637 w->add<nanogui::Label>(
" ");
638 w->add<nanogui::Button>(
"Quit", ENTYPO_ICON_ARROW_BOLD_LEFT)
639 ->setCallback([]() { win->setVisible(
false); });
641 win->setKeyboardCallback(
642 [&](
int key, [[maybe_unused]]
int scancode,
int action, [[maybe_unused]]
int modifiers)
644 if (action != GLFW_PRESS && action != GLFW_REPEAT)
return false;
655 case GLFW_KEY_PAGE_DOWN:
658 case GLFW_KEY_PAGE_UP:
662 isAutoPlayActive = !isAutoPlayActive;
663 btnSelectorAutoplay->setPushed(isAutoPlayActive);
667 cbShowInitialPose->setChecked(!cbShowInitialPose->checked());
668 cbShowInitialPose->callback()(cbShowInitialPose->checked());
674 nanogui::Slider* sl = slSelectorICP;
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);
684 win->performLayout();
685 win->camera().setCameraPointing(8.0
f, .0
f, .0
f);
686 win->camera().setAzimuthDegrees(110.0
f);
687 win->camera().setElevationDegrees(15.0
f);
688 win->camera().setZoomDistance(30.0
f);
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())
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())
697 auto load_UI_state_from_user_config = [&]()
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())); };
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);
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);
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()));
733 auto save_UI_state_to_user_config = [&]()
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);
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);
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());
762 load_UI_state_from_user_config();
769 win->setVisible(
true);
771 win->addLoopCallback(
775 updateMiniCornerView();
778 nanogui::mainloop(1000 , 25 );
783 save_UI_state_to_user_config();
788 template <
class MATRIX>
789 double conditionNumber(
const MATRIX& m)
792 std::vector<double> eVals;
793 m.eig_symmetric(eVecs, eVals);
794 return eVals.back() / eVals.front();
800 void rebuild_3d_view(
bool regenerateMaps)
802 using namespace std::string_literals;
804 const size_t idx = mrpt::round(slSelectorICP->value());
806 btnSelectorBack->setEnabled(!logRecords.empty() && idx > 0);
807 btnSelectorForw->setEnabled(!logRecords.empty() && idx < logRecords.size() - 1);
809 if (idx >= logRecords.size())
return;
814 static std::optional<size_t> lastIdx;
815 bool mustResetIterationSlider =
false;
817 if (!lastIdx || (lastIdx && idx != *lastIdx))
820 if (lastIdx) logRecords.at(*lastIdx).dispose();
823 mustResetIterationSlider =
true;
828 const auto& lr = logRecords.at(idx).get();
830 lbICPStats[0]->setValue(logRecords.at(idx).shortFileName());
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() :
""));
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()));
844 lbICPStats[3]->setValue(
"Global: "s + lr.pcGlobal->contents_summary());
845 lbICPStats[4]->setValue(
"Local: "s + lr.pcLocal->contents_summary());
847 tbInitialGuess->setValue(lr.initialGuessLocalWrtGlobal.asString());
849 tbLogPose->setValue(lr.icpResult.optimal_tf.mean.asString());
853 for (
auto* lb : lbDynVariables) lb->setValue(
"");
856 for (
const auto& [name, value] : lr.dynamicVariables)
858 lbDynVariables[lbIdx++]->setValue(mrpt::format(
"%s = %g", name.c_str(), value));
859 if (lbIdx >= MAX_VARIABLE_LIST)
break;
864 const auto poseChange =
865 lr.icpResult.optimal_tf.mean - mrpt::poses::CPose3D(lr.initialGuessLocalWrtGlobal);
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())));
872 const auto poseFromCorner = mrpt::poses::CPose3D::Identity();
873 mrpt::poses::CPose3DPDFGaussian relativePose;
876 if (!lr.iterationsDetails.has_value() || lr.iterationsDetails->empty())
878 slIterationDetails->setEnabled(
false);
880 if (cbShowInitialPose->checked())
882 relativePose.mean = mrpt::poses::CPose3D(lr.initialGuessLocalWrtGlobal);
883 lbICPIteration->setCaption(
"Show ICP iteration: INITIAL");
887 relativePose = lr.icpResult.optimal_tf;
888 lbICPIteration->setCaption(
"Show ICP iteration: FINAL");
891 if (cbViewPairings->checked()) pairsToViz = &lr.icpResult.finalPairings;
895 slIterationDetails->setEnabled(
true);
896 slIterationDetails->setRange({.0f,
static_cast<float>(lr.iterationsDetails->size() - 1)});
898 if (mustResetIterationSlider)
899 slIterationDetails->setValue(
900 cbShowInitialPose->checked() ? slIterationDetails->range().first
901 : slIterationDetails->range().second);
904 auto it = lr.iterationsDetails->begin();
906 size_t nIter = mrpt::round(slIterationDetails->value());
907 mrpt::keep_min(nIter, lr.iterationsDetails->size() - 1);
909 std::advance(it, nIter);
911 relativePose.mean = it->second.optimalPose;
912 if (cbViewPairings->checked()) pairsToViz = &it->second.pairings;
914 lbICPIteration->setCaption(
915 "Show ICP iteration: "s + std::to_string(it->first) +
"/"s +
916 std::to_string(lr.iterationsDetails->rbegin()->first));
921 for (
int i = 0; i < 6; i++) s += mrpt::format(
"%.02f ", std::sqrt(relativePose.cov(i, i)));
924 " det(XYZ)=%.02e det(rot)=%.02e", relativePose.cov.blockCopy<3, 3>(0, 0).det(),
925 relativePose.cov.blockCopy<3, 3>(3, 3).det());
927 tbCovariance->setValue(s);
931 const mrpt::poses::CPosePDFGaussian pose2D(relativePose);
934 tbConditionNumber->setValue(mrpt::format(
935 " cn{XYZ}=%.02f cn{SO(3)}=%.02f cn{SE(2)}=%.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)));
942 auto glCornerFrom = mrpt::opengl::stock_objects::CornerXYZSimple(0.75
f, 3.0
f);
943 glCornerFrom->setPose(poseFromCorner);
944 glVizICP->insert(glCornerFrom);
946 auto glCornerLocal = mrpt::opengl::stock_objects::CornerXYZSimple(0.85
f, 5.0
f);
947 glCornerLocal->setPose(relativePose.mean);
948 glCornerLocal->setName(
"Local");
949 glCornerLocal->enableShowName(
true);
950 glVizICP->insert(glCornerLocal);
952 auto glCornerToCov = mrpt::opengl::CEllipsoid3D::Create();
953 glCornerToCov->set3DsegmentsCount(16);
954 glCornerToCov->enableDrawSolid3D(
true);
955 glCornerToCov->setColor_u8(0xff, 0x00, 0x00, 0x40);
957 glCornerToCov->setCovMatrixAndMean(
958 relativePose.cov.blockCopy<3, 3>(0, 0), relativePose.mean.asVectorVal().head<3>());
959 glVizICP->insert(glCornerToCov);
965 for (
const auto& [lyName, cb] : cbLayersByName_global)
968 cb->setCaption(lyName);
969 if (
auto itL = lr.pcGlobal->layers.find(lyName); itL != lr.pcGlobal->layers.end())
971 if (
auto pc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itL->second); pc)
974 lyName +
" | "s + mrpt::system::unitsFormat(
static_cast<double>(pc->size())) +
975 " points"s +
" | class="s + pc->GetRuntimeClass()->className);
979 cb->setCaption(lyName +
" | class="s + itL->second->GetRuntimeClass()->className);
984 if (!cb->checked())
continue;
988 rpL.pointSize = slGlobalPointSize->value();
989 rpL.render_voxelmaps_as_points = cbViewVoxelsAsPoints->checked();
990 rpL.render_voxelmaps_free_space = cbViewVoxelsFreeSpace->checked();
992 if (cbColorizeGlobalMap->checked())
994 auto& cm = rpL.colorMode.emplace();
995 cm.colorMap = mrpt::img::TColormap::cmHOT;
1000 static mrpt::opengl::CSetOfObjects::Ptr lastGlobalPts;
1002 if (!lastGlobalPts || regenerateMaps)
1006 rpL.second.color = mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
1008 auto glPts = lr.pcGlobal->get_visualization(rpGlobal);
1009 lastGlobalPts = glPts;
1014 glVizICP->insert(glPts);
1019 glVizICP->insert(lastGlobalPts);
1026 for (
const auto& [lyName, cb] : cbLayersByName_local)
1029 cb->setCaption(lyName);
1030 if (
auto itL = lr.pcLocal->layers.find(lyName); itL != lr.pcLocal->layers.end())
1032 if (
auto pc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itL->second); pc)
1036 mrpt::system::unitsFormat(
static_cast<double>(pc->size()), 2,
false) +
1037 " points"s +
" | class="s + pc->GetRuntimeClass()->className);
1041 cb->setCaption(lyName +
" | class="s + itL->second->GetRuntimeClass()->className);
1046 if (!cb->checked())
continue;
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())
1055 auto& cm = rpL.colorMode.emplace();
1056 cm.colorMap = mrpt::img::TColormap::cmHOT;
1061 static mrpt::opengl::CSetOfObjects::Ptr lastLocalPts;
1063 if (!lastLocalPts || regenerateMaps)
1067 rpL.second.color = mrpt::img::TColor(0x00, 0x00, 0xff, 0xff);
1069 auto glPts = lr.pcLocal->get_visualization(rpLocal);
1070 lastLocalPts = glPts;
1072 glVizICP->insert(glPts);
1077 glVizICP->insert(lastLocalPts);
1079 lastLocalPts->setPose(relativePose.mean);
1083 std::lock_guard<std::mutex> lck(win->background_scene_mtx);
1084 win->camera().setCameraProjective(!cbViewOrtho->checked());
1086 if (cbCameraFollowsLocal->checked())
1088 win->camera().setCameraPointing(
1089 relativePose.mean.x(), relativePose.mean.y(), relativePose.mean.z());
1093 const auto depthFieldMid =
std::pow(10.0, slMidDepthField->value());
1094 const auto depthFieldThickness =
std::pow(10.0, slThicknessDepthField->value());
1096 const auto clipNear = std::max(1e-2, depthFieldMid - 0.5 * depthFieldThickness);
1097 const auto clipFar = depthFieldMid + 0.5 * depthFieldThickness;
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));
1105 win->background_scene->getViewport()->setViewportClipDistances(clipNear, clipFar);
1106 win->camera().setMaximumZoom(std::max<double>(1000, 3.0 * clipFar));
1129 tbPairings->setValue(
"None selected (mark one of the checkboxes below)");
1134 auto gl_view = win->background_scene->createViewport(
"small-view");
1136 gl_view->setViewportPosition(0, 0, 0.1, 0.1 * 16.0 / 9.0);
1137 gl_view->setTransparent(
true);
1139 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"X");
1140 obj->setLocation(1.1, 0, 0);
1141 gl_view->insert(obj);
1144 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"Y");
1145 obj->setLocation(0, 1.1, 0);
1146 gl_view->insert(obj);
1149 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"Z");
1150 obj->setLocation(0, 0, 1.1);
1151 gl_view->insert(obj);
1153 gl_view->insert(mrpt::opengl::stock_objects::CornerXYZ());
1157 #else // MRPT_HAS_NANOGUI
1161 "This application requires a version of MRPT built with nanogui "
1165 #endif // MRPT_HAS_NANOGUI
1172 if (!
cmd.parse(argc, argv))
return 1;
1179 std::cout <<
"Loading plugin(s): " << plugins << std::endl;
1180 if (!mrpt::system::loadPluginModules(plugins, errMsg))
1182 std::cerr << errMsg << std::endl;
1190 catch (std::exception& e)
1192 std::cerr <<
"Exit due to exception:\n" << mrpt::exception_to_str(e) << std::endl;