17 #include <mrpt/gui/CDisplayWindowGUI.h>
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>
34 #include <mrpt/system/string_utils.h>
38 #include "../libcfgpath/cfgpath.h"
47 static TCLAP::UnlabeledValueArg<std::string>
argMapFile(
48 "input",
"Load this metric map file (*.mm)",
false,
"myMap.mm",
"myMap.mm",
cmd);
51 "l",
"load-plugins",
"One or more (comma separated) *.so files to load as plugins",
false,
52 "foobar.so",
"foobar.so",
cmd);
55 "t",
"trajectory",
"Also draw a trajectory, given by a TUM file trajectory.",
false,
56 "trajectory.tum",
"trajectory.tum",
cmd);
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;
66 mrpt::gui::CDisplayWindowGUI::Ptr win;
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;
95 std::vector<std::string> layerNames;
96 std::map<std::string, nanogui::CheckBox*> cbLayersByName;
97 bool doFitView =
false;
103 mrpt::poses::CPose3DInterpolator trajectory;
106 mrpt::poses::CPose3DInterpolator camTravelling;
107 std::optional<double> camTravellingCurrentTime;
109 constexpr
float TRAV_ZOOM2ROLL = 1e-4;
111 static void rebuild_3d_view();
112 static void onSaveLayers();
119 std::cout <<
"Loading map file: " << mapFile << std::endl;
123 std::cerr <<
"Error loading metric map from file!" << std::endl;
126 theMapFileName = mapFile;
131 for (
const auto& [name, map] : theMap.
layers) layerNames.push_back(name);
134 for (
const auto& [name, map] : theMap.
layers)
140 sanityPassed, mrpt::format(
"sanity check did not pass for layer: '%s'", name.c_str()));
144 void updateMouseCoordinates()
146 const auto mousexY = win->mousePos();
148 mrpt::math::TLine3D mouse_ray;
149 win->background_scene->getViewport(
"main")->get3DRayForPixelCoord(
150 mousexY.x(), mousexY.y(), mouse_ray);
153 using mrpt::math::TPoint3D;
155 const mrpt::math::TPlane ground_plane(TPoint3D(0, 0, 0), TPoint3D(1, 0, 0), TPoint3D(0, 1, 0));
157 mrpt::math::TObject3D inters;
158 mrpt::math::intersect(mouse_ray, ground_plane, inters);
160 mrpt::math::TPoint3D inters_pt;
161 if (inters.getPoint(inters_pt))
163 lbMousePos->setCaption(
164 mrpt::format(
"Mouse pointing to: X=%6.03f Y=%6.03f", inters_pt.x, inters_pt.y));
168 void updateCameraLookCoordinates()
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()));
175 void observeViewOptions()
177 if (cbView2D->checked())
179 win->camera().setAzimuthDegrees(-90.0
f);
180 win->camera().setElevationDegrees(90.0
f);
184 void updateMiniCornerView()
186 auto gl_view = win->background_scene->getViewport(
"small-view");
187 if (!gl_view)
return;
189 mrpt::opengl::CCamera& view_cam = gl_view->getCamera();
191 view_cam.setAzimuthDegrees(win->camera().getAzimuthDegrees());
192 view_cam.setElevationDegrees(win->camera().getElevationDegrees());
193 view_cam.setZoomDistance(5);
196 void rebuildLayerCheckboxes()
198 ASSERT_(panelLayers);
199 while (panelLayers->childCount())
201 panelLayers->removeChild(0);
204 for (
size_t i = 0; i < layerNames.size(); i++)
206 auto cb = panelLayers->add<nanogui::CheckBox>(layerNames.at(i));
207 cb->setChecked(
true);
208 cb->setCallback([](
bool) { rebuild_3d_view(); });
211 cbLayersByName[layerNames.at(i)] = cb;
215 void rebuildCamTravellingCombo()
217 std::vector<std::string> lst, lstShort;
218 for (
size_t i = 0; i < camTravelling.size(); i++)
220 auto it = camTravelling.begin();
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()));
228 cbTravellingKeys->setItems(lst, lstShort);
230 if (!lst.empty()) cbTravellingKeys->setSelectedIndex(lst.size() - 1);
231 win->performLayout();
234 void onKeyboardAction(
int key)
238 constexpr
float SLIDE_VELOCITY = 0.01;
239 constexpr
float SENSIBILITY_ROTATE = 1.0;
241 auto cam = win->camera().cameraParams();
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.0
f : 1.0
f;
253 cam.cameraPointingX +=
d * dx * cam.cameraZoomDistance * SLIDE_VELOCITY;
254 cam.cameraPointingY +=
d * dy * cam.cameraZoomDistance * SLIDE_VELOCITY;
255 win->camera().setCameraParams(cam);
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);
274 int cmd_rot = key == GLFW_KEY_LEFT ? -1 : 1;
277 const float dis = std::max(0.01
f, (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));
285 float A_AzimuthDeg = -SENSIBILITY_ROTATE * cmd_rot;
286 cam.cameraAzimuthDeg += A_AzimuthDeg;
288 float A_ElevationDeg = SENSIBILITY_ROTATE * cmd_elev;
289 cam.setElevationDeg(cam.cameraElevationDeg + A_ElevationDeg);
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));
298 win->camera().setCameraParams(cam);
304 void camTravellingStop()
306 camTravellingCurrentTime.reset();
307 btnAnimate->setEnabled(
true);
308 btnAnimStop->setEnabled(
false);
311 void processCameraTravelling()
313 if (!camTravellingCurrentTime.has_value())
return;
314 double&
t = camTravellingCurrentTime.value();
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);
329 const auto interpMethod = cbTravellingInterp->selectedIndex() == 0
330 ? mrpt::poses::TInterpolatorMethod::imLinear2Neig
331 : mrpt::poses::TInterpolatorMethod::imSSLSLL;
332 camTravelling.setInterpolationMethod(interpMethod);
334 mrpt::math::TPose3D p;
336 camTravelling.interpolate(mrpt::Clock::fromDouble(t), p, valid);
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);
346 const double FPS = std::stod(edAnimFPS->value());
348 const double dt = 1.0 / FPS;
354 using namespace std::string_literals;
362 char appCfgFile[1024];
364 mrpt::config::CConfigFile appCfg(appCfgFile);
373 mrpt::gui::CDisplayWindowGUI_Params cp;
375 win = mrpt::gui::CDisplayWindowGUI::Create(
APP_NAME, 1024, 800, cp);
378 auto scene = mrpt::opengl::COpenGLScene::Create();
380 glGrid->setColor_u8(0xff, 0xff, 0xff, 0x10);
381 scene->insert(glGrid);
384 glMapCorner = mrpt::opengl::stock_objects::CornerXYZ(1.0
f);
385 glMapCorner->setName(
"map");
386 glMapCorner->enableShowName();
388 glTrajectory = mrpt::opengl::CSetOfObjects::Create();
390 glENUCorner = mrpt::opengl::stock_objects::CornerXYZ(2.0
f);
391 glENUCorner->setName(
"ENU");
392 glENUCorner->enableShowName();
393 scene->insert(glENUCorner);
395 scene->insert(glVizMap);
398 std::lock_guard<std::mutex> lck(win->background_scene_mtx);
399 win->background_scene = std::move(scene);
404 auto w = win->createManagedSubWindow(
"Map viewer");
405 w->setPosition({5, 25});
408 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 5, 2));
409 w->setFixedWidth(350);
411 for (
size_t i = 0; i < lbMapStats.size(); i++)
413 auto& lb = lbMapStats[i];
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(
429 nanogui::file_dialog({{
"mm",
"Metric maps (*.mm)"}},
false);
430 if (fil.empty())
return;
433 rebuildLayerCheckboxes();
434 win->performLayout();
437 catch (
const std::exception& e)
439 std::cerr << e.what() << std::endl;
445 lb = w->add<nanogui::TextBox>(
" ");
449 lb->setAlignment(nanogui::TextBox::Alignment::Left);
450 lb->setEditable(
true);
454 w->add<nanogui::Label>(
" ");
456 auto tabWidget = w->add<nanogui::TabWidget>();
458 auto* tab1 = tabWidget->createTab(
"View");
459 tab1->setLayout(
new nanogui::GroupLayout());
461 auto* tab2 = tabWidget->createTab(
"Maps");
463 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
465 auto* tab3 = tabWidget->createTab(
"Travelling");
467 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
469 tabWidget->setActiveTab(0);
474 tab2->add<nanogui::Label>(
"Render options:");
477 auto pn = tab2->add<nanogui::Widget>();
478 pn->setLayout(
new nanogui::GridLayout(
479 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
481 lbPointSize = pn->add<nanogui::Label>(
"Point size");
484 slPointSize = pn->add<nanogui::Slider>();
485 slPointSize->setRange({1.0f, 10.0f});
486 slPointSize->setValue(2.0
f);
487 slPointSize->setCallback([&](
float) { rebuild_3d_view(); });
490 cbViewVoxelsAsPoints = tab2->add<nanogui::CheckBox>(
"Render voxel maps as point clouds");
492 cbViewVoxelsAsPoints->setChecked(
false);
493 cbViewVoxelsAsPoints->setCallback([&](
bool) { rebuild_3d_view(); });
495 cbViewVoxelsFreeSpace = tab2->add<nanogui::CheckBox>(
"Render free space of voxel maps");
497 cbViewVoxelsFreeSpace->setChecked(
false);
498 cbViewVoxelsFreeSpace->setCallback([&](
bool) { rebuild_3d_view(); });
500 cbColorizeMap = tab2->add<nanogui::CheckBox>(
"Recolorize map points");
502 cbColorizeMap->setChecked(
true);
503 cbColorizeMap->setCallback([&](
bool) { rebuild_3d_view(); });
505 cbKeepOriginalCloudColors = tab2->add<nanogui::CheckBox>(
"Keep original cloud colors");
507 cbKeepOriginalCloudColors->setChecked(
false);
508 cbKeepOriginalCloudColors->setCallback([&](
bool) { rebuild_3d_view(); });
510 tab2->add<nanogui::Label>(
" ");
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:");
517 auto* btnCheckAll = pn->add<nanogui::Button>(
"", ENTYPO_ICON_CHECK);
519 btnCheckAll->setCallback(
522 for (
auto& [name, cb] : cbLayersByName) cb->setChecked(
true);
527 auto* btnCheckNone = pn->add<nanogui::Button>(
"", ENTYPO_ICON_CIRCLE_WITH_CROSS);
529 btnCheckNone->setCallback(
532 for (
auto& [name, cb] : cbLayersByName) cb->setChecked(
false);
537 panelLayers = tab2->add<nanogui::Widget>();
538 panelLayers->setLayout(
539 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
541 rebuildLayerCheckboxes();
544 tab2->add<nanogui::Label>(
" ");
545 auto btnSave = tab2->add<nanogui::Button>(
"Export marked layers...");
547 btnSave->setCallback([]() { onSaveLayers(); });
554 auto pn = tab1->add<nanogui::Widget>();
555 pn->setLayout(
new nanogui::GridLayout(
556 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
558 lbTrajThick = pn->add<nanogui::Label>(
"Trajectory thickness:");
561 slTrajectoryThickness = pn->add<nanogui::Slider>();
562 slTrajectoryThickness->setEnabled(trajectory.size() >= 2);
563 slTrajectoryThickness->setRange({std::log(0.005
f), std::log(2.0
f)});
564 slTrajectoryThickness->setValue(std::log(0.05
f));
565 slTrajectoryThickness->setCallback(
568 glTrajectory->clear();
574 auto pn = tab1->add<nanogui::Widget>();
575 pn->setLayout(
new nanogui::GridLayout(
576 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
578 lbDepthFieldMid = pn->add<nanogui::Label>(
"Center depth clip plane:");
581 slMidDepthField = pn->add<nanogui::Slider>();
582 slMidDepthField->setRange({-2.0, 3.0});
583 slMidDepthField->setValue(1.0
f);
584 slMidDepthField->setCallback([&](
float) { rebuild_3d_view(); });
588 auto pn = tab1->add<nanogui::Widget>();
589 pn->setLayout(
new nanogui::GridLayout(
590 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
592 lbDepthFieldThickness = pn->add<nanogui::Label>(
"Max-Min depth thickness:");
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(); });
601 auto pn = tab1->add<nanogui::Widget>();
602 pn->setLayout(
new nanogui::GridLayout(
603 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
605 lbCameraFOV = pn->add<nanogui::Label>(
"Camera FOV:");
607 slCameraFOV = pn->add<nanogui::Slider>();
608 slCameraFOV->setRange({20.0f, 170.0f});
609 slCameraFOV->setValue(90.0
f);
610 slCameraFOV->setCallback([&](
float) { rebuild_3d_view(); });
612 lbDepthFieldValues = tab1->add<nanogui::Label>(
" ");
616 auto pn = tab1->add<nanogui::Widget>();
617 pn->setLayout(
new nanogui::GridLayout(
618 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
620 cbViewOrtho = pn->add<nanogui::CheckBox>(
"Orthogonal view");
622 cbViewOrtho->setCallback([&](
bool) { rebuild_3d_view(); });
625 cbView2D = pn->add<nanogui::CheckBox>(
"Force 2D view");
627 cbView2D->setCallback([&](
bool) { rebuild_3d_view(); });
631 auto pn = tab1->add<nanogui::Widget>();
632 pn->setLayout(
new nanogui::GridLayout(
633 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
635 cbShowGroundGrid = pn->add<nanogui::CheckBox>(
"Show ground grid");
637 cbShowGroundGrid->setChecked(
true);
638 cbShowGroundGrid->setCallback([&](
bool) { rebuild_3d_view(); });
640 auto btnFitView = pn->add<nanogui::Button>(
"Fit view to map");
642 btnFitView->setCallback(
650 cbApplyGeoRef = tab1->add<nanogui::CheckBox>(
"Apply georeferenced pose (if available)");
652 cbApplyGeoRef->setCallback([&](
bool) { rebuild_3d_view(); });
657 tab3->add<nanogui::Label>(
"Define camera travelling paths");
660 auto pn = tab3->add<nanogui::Widget>();
661 pn->setLayout(
new nanogui::GridLayout(
662 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
664 auto lb = pn->add<nanogui::Label>(
"Keyframes:");
667 cbTravellingKeys = tab3->add<nanogui::ComboBox>();
670 rebuildCamTravellingCombo();
672 tab3->add<nanogui::Label>(
"");
674 nanogui::TextBox* edTime;
676 auto pn = tab3->add<nanogui::Widget>();
677 pn->setLayout(
new nanogui::GridLayout(
678 nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
680 pn->add<nanogui::Label>(
"New keyframe:")->setFontSize(
MID_FONT_SIZE);
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\\.]*");
690 auto btnAdd = pn->add<nanogui::Button>(
"Add", ENTYPO_ICON_ADD_TO_LIST);
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();
705 edTime->setValue(std::to_string(std::stod(edTime->value()) + 1));
709 tab3->add<nanogui::Label>(
"");
712 auto pn = tab3->add<nanogui::Widget>();
713 pn->setLayout(
new nanogui::GridLayout(
714 nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
716 pn->add<nanogui::Label>(
"Playback:");
717 btnAnimate = pn->add<nanogui::Button>(
"", ENTYPO_ICON_CONTROLLER_PLAY);
719 btnAnimate->setCallback(
722 if (camTravelling.empty())
return;
723 camTravellingCurrentTime.emplace(
724 mrpt::Clock::toDouble(camTravelling.begin()->first));
725 btnAnimate->setEnabled(
false);
726 btnAnimStop->setEnabled(
true);
728 btnAnimStop = pn->add<nanogui::Button>(
"", ENTYPO_ICON_CIRCLE_WITH_CROSS);
730 btnAnimStop->setEnabled(
false);
731 btnAnimStop->setCallback([]() { camTravellingStop(); });
735 auto pn = tab3->add<nanogui::Widget>();
736 pn->setLayout(
new nanogui::GridLayout(
737 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
739 auto lb = pn->add<nanogui::Label>(
"Animation FPS:");
742 edAnimFPS = pn->add<nanogui::TextBox>(
"30.0");
744 edAnimFPS->setFormat(
"[0-9\\.]*");
745 edAnimFPS->setEditable(
true);
748 auto pn = tab3->add<nanogui::Widget>();
749 pn->setLayout(
new nanogui::GridLayout(
750 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
752 auto lb = pn->add<nanogui::Label>(
"Interpolation:");
755 cbTravellingInterp = pn->add<nanogui::ComboBox>();
757 cbTravellingInterp->setItems({
"Linear",
"Spline"});
758 cbTravellingInterp->setSelectedIndex(0);
761 slAnimProgress = tab3->add<nanogui::Slider>();
762 slAnimProgress->setEnabled(
false);
765 lbMousePos = w->add<nanogui::Label>(
"Mouse pointing to:");
767 lbCameraPointing = w->add<nanogui::Label>(
"Camera looking at:");
770 w->add<nanogui::Button>(
"Quit", ENTYPO_ICON_ARROW_BOLD_LEFT)
771 ->setCallback([]() { win->setVisible(
false); });
773 win->setKeyboardCallback(
774 [&](
int key, [[maybe_unused]]
int scancode,
int action, [[maybe_unused]]
int modifiers)
776 if (action != GLFW_PRESS && action != GLFW_REPEAT)
return false;
778 onKeyboardAction(key);
787 win->performLayout();
788 win->camera().setCameraPointing(8.0
f, .0
f, .0
f);
789 win->camera().setAzimuthDegrees(110.0
f);
790 win->camera().setElevationDegrees(15.0
f);
791 win->camera().setZoomDistance(50.0
f);
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())
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())
800 auto load_UI_state_from_user_config = [&]()
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())); };
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);
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);
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()));
833 auto save_UI_state_to_user_config = [&]()
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);
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);
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());
859 load_UI_state_from_user_config();
867 win->setVisible(
true);
869 win->addLoopCallback(
872 updateMouseCoordinates();
873 updateCameraLookCoordinates();
874 observeViewOptions();
875 updateMiniCornerView();
876 processCameraTravelling();
879 nanogui::mainloop(1000 , 25 );
884 save_UI_state_to_user_config();
892 void rebuild_3d_view()
894 using namespace std::string_literals;
896 lbMapStats[0]->setValue(theMapFileName);
902 std::optional<mrpt::math::TBoundingBoxf> mapBbox;
908 for (
const auto& [lyName, cb] : cbLayersByName)
911 cb->setCaption(lyName);
912 if (
auto itL = theMap.
layers.find(lyName); itL != theMap.
layers.end())
914 if (
auto pc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itL->second); pc)
918 mrpt::system::unitsFormat(
static_cast<double>(pc->size()), 2,
false) +
919 " points"s +
" | class="s + pc->GetRuntimeClass()->className);
921 const auto bb = pc->boundingBox();
922 if (!mapBbox.has_value())
926 mapBbox = mapBbox->unionWith(bb);
931 cb->setCaption(lyName +
" | class="s + itL->second->GetRuntimeClass()->className);
936 if (!cb->checked())
continue;
940 rpL.pointSize = slPointSize->value();
941 rpL.render_voxelmaps_as_points = cbViewVoxelsAsPoints->checked();
942 rpL.render_voxelmaps_free_space = cbViewVoxelsFreeSpace->checked();
944 lbPointSize->setCaption(
"Point size: " + std::to_string(rpL.pointSize));
946 if (cbColorizeMap->checked())
948 auto& cm = rpL.colorMode.emplace();
949 cm.colorMap = mrpt::img::TColormap::cmJET;
952 if (cbKeepOriginalCloudColors->checked())
954 auto& cm = rpL.colorMode.emplace();
955 cm.keep_original_cloud_color =
true;
961 rp.color = mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
964 static std::optional<mp2p_icp::render_params_t> prevRenderParams;
966 if (!prevRenderParams.has_value() || prevRenderParams.value() != rpMap)
968 prevRenderParams = rpMap;
976 glVizMap->insert(glPts);
977 glVizMap->insert(glMapCorner);
978 glVizMap->insert(glTrajectory);
981 if (cbApplyGeoRef->checked() && theMap.
georeferencing.has_value())
985 glENUCorner->setVisibility(
true);
989 glVizMap->setPose(mrpt::poses::CPose3D::Identity());
990 glGrid->setPose(mrpt::poses::CPose3D::Identity());
991 glENUCorner->setVisibility(
false);
997 glGrid->setPlaneLimits(mapBbox->min.x, mapBbox->max.x, mapBbox->min.y, mapBbox->max.y);
999 glGrid->setVisibility(cbShowGroundGrid->checked());
1002 if (mapBbox && doFitView)
1004 const auto midPt = (mapBbox->min + mapBbox->max) * 0.5;
1005 const auto mapLen = (mapBbox->max - mapBbox->min).norm();
1007 win->camera().setCameraPointing(midPt.x, midPt.y, midPt.z);
1008 win->camera().setZoomDistance(mapLen);
1013 if (glTrajectory->empty() && trajectory.size() >= 2)
1015 const float trajCylRadius = std::exp(slTrajectoryThickness->value());
1016 lbTrajThick->setCaption(
"Traj. thickness: " + std::to_string(trajCylRadius));
1018 std::optional<mrpt::math::TPose3D> prevPose;
1019 for (
const auto& [t, p] : trajectory)
1023 const auto& p0 = prevPose.value();
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);
1032 glTrajectory->insert(glSegment);
1040 auto gl_view = win->background_scene->createViewport(
"small-view");
1042 gl_view->setViewportPosition(0, 0, 0.1, 0.1 * 16.0 / 9.0);
1043 gl_view->setTransparent(
true);
1045 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"X");
1046 obj->setLocation(1.1, 0, 0);
1047 gl_view->insert(obj);
1050 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"Y");
1051 obj->setLocation(0, 1.1, 0);
1052 gl_view->insert(obj);
1055 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"Z");
1056 obj->setLocation(0, 0, 1.1);
1057 gl_view->insert(obj);
1059 gl_view->insert(mrpt::opengl::stock_objects::CornerXYZ());
1064 std::lock_guard<std::mutex> lck(win->background_scene_mtx);
1065 win->camera().setCameraProjective(!cbViewOrtho->checked() && !cbView2D->checked());
1068 const auto depthFieldMid =
std::pow(10.0, slMidDepthField->value());
1069 const auto depthFieldThickness =
std::pow(10.0, slThicknessDepthField->value());
1071 const auto clipNear = std::max(1e-2, depthFieldMid - 0.5 * depthFieldThickness);
1072 const auto clipFar = depthFieldMid + 0.5 * depthFieldThickness;
1074 const float cameraFOV = slCameraFOV->value();
1075 win->camera().setCameraFOV(cameraFOV);
1076 win->camera().setMaximumZoom(std::max<double>(1000, 3.0 * clipFar));
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));
1084 lbDepthFieldValues->setCaption(
1085 mrpt::format(
"Frustum: near=%.02g far=%.02g", clipNear, clipFar));
1087 lbCameraFOV->setCaption(mrpt::format(
"Camera FOV: %.02f deg", cameraFOV));
1089 win->background_scene->getViewport()->setViewportClipDistances(clipNear, clipFar);
1095 const std::string outFile = nanogui::file_dialog({{
"txt",
"(*.txt)"}},
true );
1096 if (outFile.empty())
return;
1098 for (
const auto& [lyName, cb] : cbLayersByName)
1100 if (
auto itL = theMap.
layers.find(lyName); itL != theMap.
layers.end())
1102 itL->second->saveMetricMapRepresentationToFile(outFile);
1107 #else // MRPT_HAS_NANOGUI
1111 "This application requires a version of MRPT built with nanogui "
1115 #endif // MRPT_HAS_NANOGUI
1122 if (!
cmd.parse(argc, argv))
return 1;
1129 std::cout <<
"Loading plugin(s): " << plugins << std::endl;
1130 if (!mrpt::system::loadPluginModules(plugins, errMsg))
1132 std::cerr << errMsg << std::endl;
1141 bool trajectoryReadOk = trajectory.loadFromTextFile_TUM(
arg_tumTrajectory.getValue());
1142 ASSERT_(trajectoryReadOk);
1143 std::cout <<
"Read trajectory with " << trajectory.size() <<
" keyframes.\n";
1149 catch (std::exception& e)
1151 std::cerr <<
"Exit due to exception:\n" << mrpt::exception_to_str(e) << std::endl;