17 #include <mrpt/gui/CDisplayWindowGUI.h> 20 #include <mrpt/3rdparty/tclap/CmdLine.h> 21 #include <mrpt/config.h> 22 #include <mrpt/core/round.h> 23 #include <mrpt/opengl/CEllipsoid3D.h> 24 #include <mrpt/opengl/CGridPlaneXY.h> 25 #include <mrpt/opengl/COpenGLScene.h> 26 #include <mrpt/opengl/stock_objects.h> 27 #include <mrpt/poses/CPosePDFGaussian.h> 28 #include <mrpt/poses/Lie/SO.h> 29 #include <mrpt/system/CDirectoryExplorer.h> 30 #include <mrpt/system/filesystem.h> 31 #include <mrpt/system/progress.h> 35 constexpr
const char*
APP_NAME =
"mp2p-icp-log-viewer";
41 "e",
"file-extension",
42 "Filename extension to look for. Default is `icplog`",
false,
"icplog",
46 "d",
"directory",
"Directory in which to search for *.icplog files.",
false,
50 "v",
"verbose",
"Verbosity level",
false,
"DEBUG",
"DEBUG",
cmd);
54 "Minimum quality (range [0,1]) for a log files to be loaded and shown in " 55 "the list. Default=0 so all log files are visible.",
56 false, 0.0,
"Quality[0,1]",
cmd);
61 auto glVizICP = mrpt::opengl::CSetOfObjects::Create();
62 mrpt::gui::CDisplayWindowGUI::Ptr win;
64 nanogui::Slider* slSelectorICP =
nullptr;
65 nanogui::Button *btnSelectorBack =
nullptr, *btnSelectorForw =
nullptr;
67 std::array<nanogui::Label*, 4> lbICPStats = {
68 nullptr,
nullptr,
nullptr,
nullptr};
69 nanogui::CheckBox* cbShowInitialPose =
nullptr;
70 nanogui::CheckBox* cbViewOrtho =
nullptr;
71 nanogui::CheckBox* cbViewFinalPairings =
nullptr;
72 nanogui::CheckBox* cbViewPairingEvolution =
nullptr;
74 nanogui::CheckBox* cbViewPairings_pt2pt =
nullptr;
75 nanogui::CheckBox* cbViewPairings_pt2pl =
nullptr;
76 nanogui::CheckBox* cbViewPairings_pt2ln =
nullptr;
78 nanogui::TextBox *tbLogPose =
nullptr, *tbInitialGuess =
nullptr,
79 *tbInit2Final =
nullptr, *tbCovariance =
nullptr,
80 *tbConditionNumber =
nullptr, *tbPairings =
nullptr;
82 nanogui::Slider* slPairingsPl2PlSize =
nullptr;
83 nanogui::Slider* slPairingsPl2LnSize =
nullptr;
84 nanogui::Slider* slPointSize =
nullptr;
85 nanogui::Slider* slMidDepthField =
nullptr;
86 nanogui::Slider* slThicknessDepthField =
nullptr;
87 nanogui::Label * lbDepthFieldValues =
nullptr, *lbDepthFieldMid =
nullptr,
88 *lbDepthFieldThickness =
nullptr;
90 nanogui::Slider* slGTPose[6] = {
nullptr,
nullptr,
nullptr,
91 nullptr,
nullptr,
nullptr};
93 std::vector<std::string> layerNames_global, layerNames_local;
94 std::vector<nanogui::CheckBox*> cbPointLayers_global, cbPointLayers_local;
96 std::vector<mp2p_icp::LogRecord> logRecords;
98 static void rebuild_3d_view();
102 using namespace std::string_literals;
105 ASSERT_DIRECTORY_EXISTS_(searchDir);
107 std::cout <<
"Searching in: '" << searchDir
108 <<
"' for files with extension '" <<
argExtension.getValue()
111 mrpt::system::CDirectoryExplorer::TFileInfoList files;
112 mrpt::system::CDirectoryExplorer::explore(
113 searchDir, FILE_ATTRIB_ARCHIVE, files);
114 mrpt::system::CDirectoryExplorer::filterByExtension(
116 mrpt::system::CDirectoryExplorer::sortByName(files);
118 std::cout <<
"Found " << files.size() <<
" ICP records." << std::endl;
121 size_t filesLoaded = 0, filesFilteredOut = 0;
122 std::cout << std::endl;
123 for (
const auto& file : files)
125 const double pc =
static_cast<double>(filesLoaded) /
126 (std::max<size_t>(1, files.size() - 1));
129 " Loading %s %7.02f%% (%u / %u) ",
130 mrpt::system::progress(pc, 50).c_str(), 100 * pc,
131 static_cast<unsigned int>(filesLoaded + 1),
132 static_cast<unsigned int>(files.size()));
135 const auto& lr = logRecords.emplace_back(
145 logRecords.erase(logRecords.rbegin().base());
148 std::cout << std::endl;
149 std::cout <<
"Loaded " << logRecords.size() <<
" ICP records (" 150 << filesLoaded <<
" actually loaded, " << filesFilteredOut
151 <<
" filtered out)" << std::endl;
153 ASSERT_(!logRecords.empty());
157 const auto& lr = logRecords.front();
158 if (layerNames_global.empty() && lr.pcGlobal)
160 for (
const auto& layer : lr.pcGlobal->layers)
162 layerNames_global.push_back(layer.first);
163 std::cout <<
"Global point cloud: Found point layer='" 164 << layer.first <<
"'\n";
167 if (layerNames_local.empty() && lr.pcLocal)
169 for (
const auto& layer : lr.pcLocal->layers)
171 layerNames_local.push_back(layer.first);
172 std::cout <<
"Local point cloud: Found point layer='" 173 << layer.first <<
"'\n";
185 mrpt::gui::CDisplayWindowGUI_Params cp;
187 win = mrpt::gui::CDisplayWindowGUI::Create(
APP_NAME, 1024, 800, cp);
190 auto scene = mrpt::opengl::COpenGLScene::Create();
192 auto glGrid = mrpt::opengl::CGridPlaneXY::Create();
193 glGrid->setColor_u8(0xff, 0xff, 0xff, 0x10);
194 scene->insert(glGrid);
197 auto gl_base = mrpt::opengl::stock_objects::CornerXYZ(1.0
f);
198 gl_base->setName(
"Global");
199 gl_base->enableShowName();
200 scene->insert(gl_base);
202 scene->insert(glVizICP);
205 std::lock_guard<std::mutex> lck(win->background_scene_mtx);
206 win->background_scene = std::move(scene);
211 auto w = win->createManagedSubWindow(
"Control");
212 w->setPosition({5, 25});
214 w->setLayout(
new nanogui::BoxLayout(
215 nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 5, 2));
216 w->setFixedWidth(450);
219 w->add<nanogui::CheckBox>(
"Show at INITIAL GUESS pose");
220 cbShowInitialPose->setCallback([=](
bool) { rebuild_3d_view(); });
223 w->add<nanogui::Label>(
" ");
224 w->add<nanogui::Label>(mrpt::format(
225 "Select ICP record file (N=%u)",
226 static_cast<unsigned int>(logRecords.size())));
227 slSelectorICP = w->add<nanogui::Slider>();
228 slSelectorICP->setRange({.0f, logRecords.size() - 1});
229 slSelectorICP->setValue(0);
230 slSelectorICP->setCallback([&](
float ) { rebuild_3d_view(); });
232 for (
auto& lb : lbICPStats) lb = w->add<nanogui::Label>(
" ");
236 auto pn = w->add<nanogui::Widget>();
238 new nanogui::BoxLayout(nanogui::Orientation::Horizontal));
241 auto s = slSelectorICP;
243 btnSelectorBack = pn->add<nanogui::Button>(
244 "", ENTYPO_ICON_CONTROLLER_FAST_BACKWARD);
245 btnSelectorBack->setCallback([=]() {
248 s->setValue(
s->value() - 1);
249 s->callback()(
s->value());
253 btnSelectorForw = pn->add<nanogui::Button>(
254 "", ENTYPO_ICON_CONTROLLER_FAST_FORWARD);
255 btnSelectorForw->setCallback([=]() {
256 if (
s->value() <
s->range().second - 0.01f)
258 s->setValue(
s->value() + 1);
259 s->callback()(
s->value());
265 w->add<nanogui::Label>(
" ");
267 auto tabWidget = w->add<nanogui::TabWidget>();
269 auto* tab1 = tabWidget->createTab(
"Summary");
270 tab1->setLayout(
new nanogui::GroupLayout());
272 auto* tab2 = tabWidget->createTab(
"Uncertainty");
273 tab2->setLayout(
new nanogui::GroupLayout());
275 auto* tab3 = tabWidget->createTab(
"Maps");
276 tab3->setLayout(
new nanogui::GroupLayout());
278 auto* tab4 = tabWidget->createTab(
"Pairings");
279 tab4->setLayout(
new nanogui::GroupLayout());
281 auto* tab5 = tabWidget->createTab(
"View");
282 tab5->setLayout(
new nanogui::GroupLayout());
284 tabWidget->setActiveTab(0);
286 tab1->add<nanogui::Label>(
287 "ICP result pose [x y z yaw(deg) pitch(deg) roll(deg)]:");
288 tbLogPose = tab1->add<nanogui::TextBox>();
289 tbLogPose->setFontSize(16);
290 tbLogPose->setEditable(
true);
292 tab1->add<nanogui::Label>(
"Initial -> final pose change:");
293 tbInit2Final = tab1->add<nanogui::TextBox>();
294 tbInit2Final->setFontSize(16);
295 tbInit2Final->setEditable(
false);
297 tab2->add<nanogui::Label>(
298 "Uncertainty: diagonal sigmas (x y z yaw pitch roll)");
299 tbCovariance = tab2->add<nanogui::TextBox>();
300 tbCovariance->setFontSize(16);
301 tbCovariance->setEditable(
false);
303 tab2->add<nanogui::Label>(
"Uncertainty: Covariance condition numbers");
304 tbConditionNumber = tab2->add<nanogui::TextBox>();
305 tbConditionNumber->setFontSize(16);
306 tbConditionNumber->setEditable(
false);
308 const float handTunedRange[6] = {4.0, 4.0, 10.0,
311 for (
int i = 0; i < 6; i++)
313 slGTPose[i] = tab2->add<nanogui::Slider>();
314 slGTPose[i]->setRange({-handTunedRange[i], handTunedRange[i]});
315 slGTPose[i]->setValue(0.0
f);
317 slGTPose[i]->setCallback([=](
float v) {
318 const size_t idx = mrpt::round(slSelectorICP->value());
319 auto& lr = logRecords.at(idx);
321 auto p = lr.icpResult.optimal_tf.mean.asTPose();
323 lr.icpResult.optimal_tf.mean = mrpt::poses::CPose3D(p);
329 tab1->add<nanogui::Label>(
"Initial guess pose:");
330 tbInitialGuess = tab1->add<nanogui::TextBox>();
331 tbInitialGuess->setFontSize(16);
332 tbInitialGuess->setEditable(
true);
338 "mp2p_icp::metric_map_t binary serialized object (*.mm)"}},
340 if (outFile.empty())
return;
341 m.save_to_file(outFile);
346 auto pn = tab3->add<nanogui::Widget>();
347 pn->setLayout(
new nanogui::BoxLayout(
348 nanogui::Orientation::Horizontal, nanogui::Alignment::Middle));
349 pn->add<nanogui::Button>(
"Export 'local' map...")
350 ->setCallback([&]() {
351 const size_t idx = mrpt::round(slSelectorICP->value());
352 auto& lr = logRecords.at(idx);
354 lambdaSave(*lr.pcLocal);
356 pn->add<nanogui::Button>(
"Export 'global' map...")
357 ->setCallback([&]() {
358 const size_t idx = mrpt::round(slSelectorICP->value());
359 auto& lr = logRecords.at(idx);
360 ASSERT_(lr.pcGlobal);
361 lambdaSave(*lr.pcGlobal);
365 tab3->add<nanogui::Label>(
"[GLOBAL point cloud] Show point layers:");
366 cbPointLayers_global.resize(layerNames_global.size());
367 for (
size_t i = 0; i < layerNames_global.size(); i++)
369 cbPointLayers_global[i] =
370 tab3->add<nanogui::CheckBox>(layerNames_global.at(i));
371 cbPointLayers_global[i]->setChecked(
true);
372 cbPointLayers_global[i]->setCallback(
373 [](
bool) { rebuild_3d_view(); });
376 tab3->add<nanogui::Label>(
"[LOCAL point cloud] Show point layers:");
377 cbPointLayers_local.resize(layerNames_local.size());
378 for (
size_t i = 0; i < layerNames_local.size(); i++)
380 cbPointLayers_local[i] =
381 tab3->add<nanogui::CheckBox>(layerNames_local.at(i));
382 cbPointLayers_local[i]->setChecked(
true);
383 cbPointLayers_local[i]->setCallback(
384 [](
bool) { rebuild_3d_view(); });
388 tbPairings = tab4->add<nanogui::TextBox>();
389 tbPairings->setFontSize(16);
390 tbPairings->setEditable(
false);
392 cbViewFinalPairings =
393 tab4->add<nanogui::CheckBox>(
"View final pairings");
394 cbViewPairingEvolution =
395 tab4->add<nanogui::CheckBox>(
"View pairing evolution");
397 cbViewFinalPairings->setCallback([](
bool checked) {
398 if (checked) cbViewPairingEvolution->setChecked(
false);
402 cbViewPairingEvolution->setCallback([](
bool checked) {
403 if (checked) cbViewFinalPairings->setChecked(
false);
407 cbViewPairings_pt2pt =
408 tab4->add<nanogui::CheckBox>(
"View: point-to-point");
409 cbViewPairings_pt2pt->setChecked(
true);
410 cbViewPairings_pt2pt->setCallback([](
bool) { rebuild_3d_view(); });
413 auto pn = tab4->add<nanogui::Widget>();
414 pn->setLayout(
new nanogui::GridLayout(
415 nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
417 cbViewPairings_pt2pl =
418 pn->add<nanogui::CheckBox>(
"View: point-to-plane");
419 cbViewPairings_pt2pl->setChecked(
true);
420 cbViewPairings_pt2pl->setCallback([](
bool) { rebuild_3d_view(); });
422 pn->add<nanogui::Label>(
"Plane size:");
423 slPairingsPl2PlSize = pn->add<nanogui::Slider>();
424 slPairingsPl2PlSize->setRange({-2.0f, 2.0f});
425 slPairingsPl2PlSize->setValue(-1.0
f);
426 slPairingsPl2PlSize->setCallback([&](
float) { rebuild_3d_view(); });
430 auto pn = tab4->add<nanogui::Widget>();
431 pn->setLayout(
new nanogui::GridLayout(
432 nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
434 cbViewPairings_pt2ln =
435 pn->add<nanogui::CheckBox>(
"View: point-to-line");
436 cbViewPairings_pt2ln->setChecked(
true);
437 cbViewPairings_pt2ln->setCallback([](
bool) { rebuild_3d_view(); });
439 pn->add<nanogui::Label>(
"Line length:");
440 slPairingsPl2LnSize = pn->add<nanogui::Slider>();
441 slPairingsPl2LnSize->setRange({-2.0f, 2.0f});
442 slPairingsPl2LnSize->setValue(-1.0
f);
443 slPairingsPl2LnSize->setCallback([&](
float) { rebuild_3d_view(); });
448 auto pn = tab5->add<nanogui::Widget>();
449 pn->setLayout(
new nanogui::GridLayout(
450 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
452 pn->add<nanogui::Label>(
"Point size");
454 slPointSize = pn->add<nanogui::Slider>();
455 slPointSize->setRange({1.0f, 10.0f});
456 slPointSize->setValue(2.0
f);
457 slPointSize->setCallback([&](
float) { rebuild_3d_view(); });
460 lbDepthFieldMid = tab5->add<nanogui::Label>(
"Center depth clip plane:");
461 slMidDepthField = tab5->add<nanogui::Slider>();
462 slMidDepthField->setRange({-2.0, 3.0});
463 slMidDepthField->setValue(1.0
f);
464 slMidDepthField->setCallback([&](
float) { rebuild_3d_view(); });
466 lbDepthFieldThickness =
467 tab5->add<nanogui::Label>(
"Max-Min depth thickness:");
468 slThicknessDepthField = tab5->add<nanogui::Slider>();
469 slThicknessDepthField->setRange({-2.0, 3.0});
470 slThicknessDepthField->setValue(3.0);
471 slThicknessDepthField->setCallback([&](
float) { rebuild_3d_view(); });
472 lbDepthFieldValues = tab5->add<nanogui::Label>(
" ");
474 cbViewOrtho = tab5->add<nanogui::CheckBox>(
"Orthogonal view");
475 cbViewOrtho->setCallback([&](
bool) { rebuild_3d_view(); });
478 w->add<nanogui::Label>(
" ");
479 w->add<nanogui::Button>(
"Quit", ENTYPO_ICON_ARROW_BOLD_LEFT)
480 ->setCallback([]() { win->setVisible(
false); });
482 win->setKeyboardCallback([&](
int key, [[maybe_unused]]
int scancode,
484 [[maybe_unused]]
int modifiers) {
485 if (action != GLFW_PRESS && action != GLFW_REPEAT)
return false;
496 case GLFW_KEY_PAGE_DOWN:
499 case GLFW_KEY_PAGE_UP:
506 nanogui::Slider* sl = slSelectorICP;
507 sl->setValue(sl->value() + increment);
508 if (sl->value() < 0) sl->setValue(0);
509 if (sl->value() > sl->range().second)
510 sl->setValue(sl->range().second);
518 win->performLayout();
519 win->camera().setCameraPointing(8.0
f, .0
f, .0
f);
520 win->camera().setAzimuthDegrees(110.0
f);
521 win->camera().setElevationDegrees(15.0
f);
522 win->camera().setZoomDistance(30.0
f);
529 win->setVisible(
true);
530 nanogui::mainloop(10 );
535 template <
class MATRIX>
536 double conditionNumber(
const MATRIX& m)
539 std::vector<double> eVals;
540 m.eig_symmetric(eVecs, eVals);
541 return eVals.back() / eVals.front();
547 void rebuild_3d_view()
549 using namespace std::string_literals;
551 const size_t idx = mrpt::round(slSelectorICP->value());
553 btnSelectorBack->setEnabled(!logRecords.empty() && idx > 0);
554 btnSelectorForw->setEnabled(
555 !logRecords.empty() && idx < logRecords.size() - 1);
559 const auto& lr = logRecords.at(idx);
561 lbICPStats[0]->setCaption(mrpt::format(
562 "ICP pair #%u, local: ID:%u%s, global: ID:%u%s",
563 static_cast<unsigned int>(idx),
564 static_cast<unsigned int>(lr.pcLocal->id ? lr.pcLocal->id.value() : 0),
565 lr.pcLocal->label ? lr.pcLocal->label.value().c_str() :
"",
566 static_cast<unsigned int>(
567 lr.pcGlobal->id ? lr.pcGlobal->id.value() : 0),
568 lr.pcGlobal->label ? lr.pcGlobal->label.value().c_str() :
""));
570 lbICPStats[1]->setCaption(mrpt::format(
571 "Log quality: %.02f%% iters: %u Term.Reason: %s",
572 100.0 * lr.icpResult.quality,
573 static_cast<unsigned int>(lr.icpResult.nIterations),
574 mrpt::typemeta::enum2str(lr.icpResult.terminationReason).c_str()));
576 lbICPStats[2]->setCaption(
"Global: "s + lr.pcGlobal->contents_summary());
577 lbICPStats[3]->setCaption(
"Local: "s + lr.pcLocal->contents_summary());
579 tbInitialGuess->setValue(lr.initialGuessLocalWrtGlobal.asString());
581 tbLogPose->setValue(lr.icpResult.optimal_tf.mean.asString());
584 const auto poseChange =
585 lr.icpResult.optimal_tf.mean -
586 mrpt::poses::CPose3D(lr.initialGuessLocalWrtGlobal);
588 tbInit2Final->setValue(mrpt::format(
589 "|T|=%.03f [m] |R|=%.03f [deg]", poseChange.norm(),
591 mrpt::poses::Lie::SO<3>::log(poseChange.getRotationMatrix())
595 const auto poseFromCorner = mrpt::poses::CPose3D::Identity();
596 mrpt::poses::CPose3DPDFGaussian relativePose;
598 if (cbShowInitialPose->checked())
600 relativePose.mean = mrpt::poses::CPose3D(lr.initialGuessLocalWrtGlobal);
604 relativePose = lr.icpResult.optimal_tf;
609 for (
int i = 0; i < 6; i++)
610 s += mrpt::format(
"%.02f ", std::sqrt(relativePose.cov(i, i)));
613 " det(XYZ)=%.02e det(rot)=%.02e",
614 relativePose.cov.blockCopy<3, 3>(0, 0).det(),
615 relativePose.cov.blockCopy<3, 3>(3, 3).det());
617 tbCovariance->setValue(s);
621 const mrpt::poses::CPosePDFGaussian pose2D(relativePose);
624 tbConditionNumber->setValue(mrpt::format(
625 " cn{XYZ}=%.02f cn{SO(3)}=%.02f cn{SE(2)}=%.02f " 627 conditionNumber(relativePose.cov.blockCopy<3, 3>(0, 0)),
628 conditionNumber(relativePose.cov.blockCopy<3, 3>(3, 3)),
629 conditionNumber(pose2D.cov), conditionNumber(relativePose.cov)));
633 mrpt::opengl::stock_objects::CornerXYZSimple(0.75
f, 3.0
f);
634 glCornerFrom->setPose(poseFromCorner);
635 glVizICP->insert(glCornerFrom);
638 mrpt::opengl::stock_objects::CornerXYZSimple(0.85
f, 5.0
f);
639 glCornerLocal->setPose(relativePose.mean);
640 glCornerLocal->setName(
"Local");
641 glCornerLocal->enableShowName(
true);
642 glVizICP->insert(glCornerLocal);
644 auto glCornerToCov = mrpt::opengl::CEllipsoid3D::Create();
645 glCornerToCov->set3DsegmentsCount(16);
646 glCornerToCov->enableDrawSolid3D(
true);
647 glCornerToCov->setColor_u8(0xff, 0x00, 0x00, 0x40);
649 glCornerToCov->setCovMatrixAndMean(
650 relativePose.cov.blockCopy<3, 3>(0, 0),
651 relativePose.mean.asVectorVal().head<3>());
652 glVizICP->insert(glCornerToCov);
658 for (
const auto& cbPL : cbPointLayers_global)
660 if (!cbPL->checked())
continue;
664 rpL.pointSize = slPointSize->value();
670 rpL.second.color = mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
672 auto glPts = lr.pcGlobal->get_visualization(rpGlobal);
676 mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
678 glVizICP->insert(glPts);
685 for (
const auto& cbPL : cbPointLayers_local)
687 if (!cbPL->checked())
continue;
691 rpL.pointSize = slPointSize->value();
697 rpL.second.color = mrpt::img::TColor(0x00, 0x00, 0xff, 0xff);
699 auto glPts = lr.pcLocal->get_visualization(rpLocal);
701 glPts->setPose(relativePose.mean);
702 glVizICP->insert(glPts);
707 std::lock_guard<std::mutex> lck(win->background_scene_mtx);
708 win->camera().setCameraProjective(!cbViewOrtho->checked());
711 const auto depthFieldMid =
std::pow(10.0, slMidDepthField->value());
712 const auto depthFieldThickness =
713 std::pow(10.0, slThicknessDepthField->value());
715 const auto clipNear =
716 std::max(1e-2, depthFieldMid - 0.5 * depthFieldThickness);
717 const auto clipFar = depthFieldMid + 0.5 * depthFieldThickness;
719 lbDepthFieldMid->setCaption(
720 mrpt::format(
"Center depth clip plane: %f", depthFieldMid));
721 lbDepthFieldThickness->setCaption(
722 mrpt::format(
"Max-Min depth thickness:%f", depthFieldThickness));
723 lbDepthFieldValues->setCaption(mrpt::format(
724 "Depth field: near plane=%f far plane=%f", clipNear, clipFar));
726 win->background_scene->getViewport()->setViewportClipDistances(
731 cbViewPairingEvolution->setEnabled(lr.iterationsDetails.has_value());
735 if (cbViewFinalPairings->checked())
738 pairsToViz = &lr.icpResult.finalPairings;
764 tbPairings->setValue(
765 "None selected (mark one of the checkboxes below)");
769 #else // MRPT_HAS_NANOGUI 773 "This application requires a version of MRPT built with nanogui " 777 #endif // MRPT_HAS_NANOGUI 779 int main(
int argc,
char** argv)
784 if (!
cmd.parse(argc, argv))
return 1;
789 catch (std::exception& e)
791 std::cerr <<
"Exit due to exception:\n" 792 << mrpt::exception_to_str(e) << std::endl;
static TCLAP::CmdLine cmd(APP_NAME)
constexpr T pow(const T base, const std::size_t exponent)
Generic container of pointcloud(s), extracted features and other maps.
render_params_pairings_pt2pt_t pt2pt
static TCLAP::ValueArg< std::string > argSearchDir("d", "directory", "Directory in which to search for *.icplog files.", false, ".", ".", cmd)
virtual std::string contents_summary() const
std::map< layer_name_t, render_params_point_layer_t > perLayer
render_params_points_t points
static LogRecord LoadFromFile(const std::string &fileName)
render_params_pairings_pt2pl_t pt2pl
static TCLAP::ValueArg< std::string > argExtension("e", "file-extension", "Filename extension to look for. Default is `icplog`", false, "icplog", "icplog", cmd)
A record of the inputs and outputs of an ICP run.
constexpr const char * APP_NAME
static TCLAP::ValueArg< double > argMinQuality("", "min-quality", "Minimum quality (range [0,1]) for a log files to be loaded and shown in " "the list. Default=0 so all log files are visible.", false, 0.0, "Quality[0,1]", cmd)
virtual auto get_visualization(const mrpt::poses::CPose3D &localWrtGlobal, const pairings_render_params_t &p=pairings_render_params_t()) const -> std::shared_ptr< mrpt::opengl::CSetOfObjects >
static TCLAP::ValueArg< std::string > argVerbosity("v", "verbose", "Verbosity level", false, "DEBUG", "DEBUG", cmd)
static void main_show_gui()
render_params_pairings_pt2ln_t pt2ln
render_params_point_layer_t allLayers
int main(int argc, char **argv)