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",
53 "One or more (comma separated) *.so files to load as plugins",
false,
54 "foobar.so",
"foobar.so",
cmd);
58 "Also draw a trajectory, given by a TUM file trajectory.",
false,
59 "trajectory.tum",
"trajectory.tum",
cmd);
64 auto glVizMap = mrpt::opengl::CSetOfObjects::Create();
65 auto glGrid = mrpt::opengl::CGridPlaneXY::Create();
66 mrpt::opengl::CSetOfObjects::Ptr glENUCorner, glMapCorner;
67 mrpt::opengl::CSetOfObjects::Ptr glTrajectory;
69 mrpt::gui::CDisplayWindowGUI::Ptr win;
71 std::array<nanogui::TextBox*, 2> lbMapStats = {
nullptr,
nullptr};
72 nanogui::CheckBox* cbApplyGeoRef =
nullptr;
73 nanogui::CheckBox* cbViewOrtho =
nullptr;
74 nanogui::CheckBox* cbView2D =
nullptr;
75 nanogui::CheckBox* cbViewVoxelsAsPoints =
nullptr;
76 nanogui::CheckBox* cbViewVoxelsFreeSpace =
nullptr;
77 nanogui::CheckBox* cbColorizeMap =
nullptr;
78 nanogui::CheckBox* cbKeepOriginalCloudColors =
nullptr;
79 nanogui::CheckBox* cbShowGroundGrid =
nullptr;
80 nanogui::Slider* slPointSize =
nullptr;
81 nanogui::Slider* slTrajectoryThickness =
nullptr;
82 nanogui::Slider* slMidDepthField =
nullptr;
83 nanogui::Slider* slThicknessDepthField =
nullptr;
84 nanogui::Slider* slCameraFOV =
nullptr;
85 nanogui::Label* lbCameraFOV =
nullptr;
86 nanogui::Label* lbMousePos =
nullptr;
87 nanogui::Label* lbCameraPointing =
nullptr;
88 nanogui::Label *lbDepthFieldValues =
nullptr, *lbDepthFieldMid =
nullptr,
89 *lbDepthFieldThickness =
nullptr, *lbPointSize =
nullptr;
90 nanogui::Label* lbTrajThick =
nullptr;
91 nanogui::Widget* panelLayers =
nullptr;
92 nanogui::ComboBox* cbTravellingKeys =
nullptr;
93 nanogui::TextBox* edAnimFPS =
nullptr;
94 nanogui::Slider* slAnimProgress =
nullptr;
95 nanogui::Button * btnAnimate =
nullptr, *btnAnimStop =
nullptr;
96 nanogui::ComboBox* cbTravellingInterp =
nullptr;
98 std::vector<std::string> layerNames;
99 std::map<std::string, nanogui::CheckBox*> cbLayersByName;
105 mrpt::poses::CPose3DInterpolator trajectory;
108 mrpt::poses::CPose3DInterpolator camTravelling;
109 std::optional<double> camTravellingCurrentTime;
111 constexpr
float TRAV_ZOOM2ROLL = 1e-4;
113 static void rebuild_3d_view();
114 static void onSaveLayers();
121 std::cout <<
"Loading map file: " << mapFile << std::endl;
125 std::cerr <<
"Error loading metric map from file!" << std::endl;
128 theMapFileName = mapFile;
133 for (
const auto& [name, map] : theMap.
layers) layerNames.push_back(name);
136 for (
const auto& [name, map] : theMap.
layers)
144 "sanity check did not pass for layer: '%s'", name.c_str()));
148 void updateMouseCoordinates()
150 const auto mousexY = win->mousePos();
152 mrpt::math::TLine3D mouse_ray;
153 win->background_scene->getViewport(
"main")->get3DRayForPixelCoord(
154 mousexY.x(), mousexY.y(), mouse_ray);
157 using mrpt::math::TPoint3D;
159 const mrpt::math::TPlane ground_plane(
160 TPoint3D(0, 0, 0), TPoint3D(1, 0, 0), TPoint3D(0, 1, 0));
162 mrpt::math::TObject3D inters;
163 mrpt::math::intersect(mouse_ray, ground_plane, inters);
165 mrpt::math::TPoint3D inters_pt;
166 if (inters.getPoint(inters_pt))
168 lbMousePos->setCaption(mrpt::format(
169 "Mouse pointing to: X=%6.03f Y=%6.03f", inters_pt.x, inters_pt.y));
173 void updateCameraLookCoordinates()
175 lbCameraPointing->setCaption(mrpt::format(
176 "Looking at: X=%6.03f Y=%6.03f Z=%6.03f",
177 win->camera().getCameraPointingX(), win->camera().getCameraPointingY(),
178 win->camera().getCameraPointingZ()));
181 void observeViewOptions()
183 if (cbView2D->checked())
185 win->camera().setAzimuthDegrees(-90.0
f);
186 win->camera().setElevationDegrees(90.0
f);
190 void updateMiniCornerView()
192 auto gl_view = win->background_scene->getViewport(
"small-view");
193 if (!gl_view)
return;
195 mrpt::opengl::CCamera& view_cam = gl_view->getCamera();
197 view_cam.setAzimuthDegrees(win->camera().getAzimuthDegrees());
198 view_cam.setElevationDegrees(win->camera().getElevationDegrees());
199 view_cam.setZoomDistance(5);
202 void rebuildLayerCheckboxes()
204 ASSERT_(panelLayers);
205 while (panelLayers->childCount())
207 panelLayers->removeChild(0);
210 for (
size_t i = 0; i < layerNames.size(); i++)
212 auto cb = panelLayers->add<nanogui::CheckBox>(layerNames.at(i));
213 cb->setChecked(
true);
214 cb->setCallback([](
bool) { rebuild_3d_view(); });
217 cbLayersByName[layerNames.at(i)] = cb;
221 void rebuildCamTravellingCombo()
223 std::vector<std::string> lst, lstShort;
224 for (
size_t i = 0; i < camTravelling.size(); i++)
226 auto it = camTravelling.begin();
229 lstShort.push_back(std::to_string(i));
230 lst.push_back(mrpt::format(
231 "[%02u] t=%.02fs pose=%s",
static_cast<unsigned int>(i),
232 mrpt::Clock::toDouble(it->first), it->second.asString().c_str()));
234 cbTravellingKeys->setItems(lst, lstShort);
236 if (!lst.empty()) cbTravellingKeys->setSelectedIndex(lst.size() - 1);
237 win->performLayout();
240 void onKeyboardAction(
int key)
244 constexpr
float SLIDE_VELOCITY = 0.01;
245 constexpr
float SENSIBILITY_ROTATE = 1.0;
247 auto cam = win->camera().cameraParams();
256 const float dx = std::cos(DEG2RAD(cam.cameraAzimuthDeg));
257 const float dy = std::sin(DEG2RAD(cam.cameraAzimuthDeg));
259 (key == GLFW_KEY_UP || key == GLFW_KEY_W) ? -1.0
f : 1.0
f;
260 cam.cameraPointingX +=
261 d * dx * cam.cameraZoomDistance * SLIDE_VELOCITY;
262 cam.cameraPointingY +=
263 d * dy * cam.cameraZoomDistance * SLIDE_VELOCITY;
264 win->camera().setCameraParams(cam);
271 const float dx = std::cos(DEG2RAD(cam.cameraAzimuthDeg + 90.f));
272 const float dy = std::sin(DEG2RAD(cam.cameraAzimuthDeg + 90.f));
273 const float d = key == GLFW_KEY_A ? -1.0f : 1.0f;
274 cam.cameraPointingX +=
275 d * dx * cam.cameraZoomDistance * SLIDE_VELOCITY;
276 cam.cameraPointingY +=
277 d * dy * cam.cameraZoomDistance * SLIDE_VELOCITY;
278 win->camera().setCameraParams(cam);
285 int cmd_rot = key == GLFW_KEY_LEFT ? -1 : 1;
288 const float dis = std::max(0.01
f, (cam.cameraZoomDistance));
290 cam.cameraPointingX + dis * cos(DEG2RAD(cam.cameraAzimuthDeg)) *
291 cos(DEG2RAD(cam.cameraElevationDeg));
293 cam.cameraPointingY + dis * sin(DEG2RAD(cam.cameraAzimuthDeg)) *
294 cos(DEG2RAD(cam.cameraElevationDeg));
295 float eye_z = cam.cameraPointingZ +
296 dis * sin(DEG2RAD(cam.cameraElevationDeg));
299 float A_AzimuthDeg = -SENSIBILITY_ROTATE * cmd_rot;
300 cam.cameraAzimuthDeg += A_AzimuthDeg;
302 float A_ElevationDeg = SENSIBILITY_ROTATE * cmd_elev;
303 cam.setElevationDeg(cam.cameraElevationDeg + A_ElevationDeg);
306 cam.cameraPointingX =
307 eye_x - dis * cos(DEG2RAD(cam.cameraAzimuthDeg)) *
308 cos(DEG2RAD(cam.cameraElevationDeg));
309 cam.cameraPointingY =
310 eye_y - dis * sin(DEG2RAD(cam.cameraAzimuthDeg)) *
311 cos(DEG2RAD(cam.cameraElevationDeg));
312 cam.cameraPointingZ =
313 eye_z - dis * sin(DEG2RAD(cam.cameraElevationDeg));
315 win->camera().setCameraParams(cam);
321 void camTravellingStop()
323 camTravellingCurrentTime.reset();
324 btnAnimate->setEnabled(
true);
325 btnAnimStop->setEnabled(
false);
328 void processCameraTravelling()
330 if (!camTravellingCurrentTime.has_value())
return;
331 double&
t = camTravellingCurrentTime.value();
334 const double t0 = mrpt::Clock::toDouble(camTravelling.begin()->first);
335 const double t1 = mrpt::Clock::toDouble(camTravelling.rbegin()->first);
336 slAnimProgress->setRange(std::make_pair<float>(t0, t1));
337 slAnimProgress->setValue(t);
346 const auto interpMethod =
347 cbTravellingInterp->selectedIndex() == 0
348 ? mrpt::poses::TInterpolatorMethod::imLinear2Neig
349 : mrpt::poses::TInterpolatorMethod::imSSLSLL;
350 camTravelling.setInterpolationMethod(interpMethod);
352 mrpt::math::TPose3D p;
354 camTravelling.interpolate(mrpt::Clock::fromDouble(t), p, valid);
357 win->camera().setCameraPointing(p.x, p.y, p.z);
358 win->camera().setAzimuthDegrees(mrpt::RAD2DEG(p.yaw));
359 win->camera().setElevationDegrees(mrpt::RAD2DEG(p.pitch));
360 win->camera().setZoomDistance(p.roll / TRAV_ZOOM2ROLL);
364 const double FPS = std::stod(edAnimFPS->value());
366 const double dt = 1.0 / FPS;
372 using namespace std::string_literals;
377 char appCfgFile[1024];
379 mrpt::config::CConfigFile appCfg(appCfgFile);
388 mrpt::gui::CDisplayWindowGUI_Params cp;
390 win = mrpt::gui::CDisplayWindowGUI::Create(
APP_NAME, 1024, 800, cp);
393 auto scene = mrpt::opengl::COpenGLScene::Create();
395 glGrid->setColor_u8(0xff, 0xff, 0xff, 0x10);
396 scene->insert(glGrid);
399 glMapCorner = mrpt::opengl::stock_objects::CornerXYZ(1.0
f);
400 glMapCorner->setName(
"map");
401 glMapCorner->enableShowName();
403 glTrajectory = mrpt::opengl::CSetOfObjects::Create();
405 glENUCorner = mrpt::opengl::stock_objects::CornerXYZ(2.0
f);
406 glENUCorner->setName(
"ENU");
407 glENUCorner->enableShowName();
408 scene->insert(glENUCorner);
410 scene->insert(glVizMap);
413 std::lock_guard<std::mutex> lck(win->background_scene_mtx);
414 win->background_scene = std::move(scene);
419 auto w = win->createManagedSubWindow(
"Map viewer");
420 w->setPosition({5, 25});
422 w->setLayout(
new nanogui::BoxLayout(
423 nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 5, 2));
424 w->setFixedWidth(350);
426 for (
size_t i = 0; i < lbMapStats.size(); i++)
428 auto& lb = lbMapStats[i];
432 auto pn = w->add<nanogui::Widget>();
433 pn->setLayout(
new nanogui::BoxLayout(
434 nanogui::Orientation::Horizontal,
435 nanogui::Alignment::Fill));
436 lb = pn->add<nanogui::TextBox>(
" ");
437 lb->setFixedWidth(300);
439 pn->add<nanogui::Button>(
"", ENTYPO_ICON_ARCHIVE);
440 btnLoad->setCallback(
445 const auto fil = nanogui::file_dialog(
446 {{
"mm",
"Metric maps (*.mm)"}},
false);
447 if (fil.empty())
return;
450 rebuildLayerCheckboxes();
451 win->performLayout();
454 catch (
const std::exception& e)
456 std::cerr << e.what() << std::endl;
460 else { lb = w->add<nanogui::TextBox>(
" "); }
463 lb->setAlignment(nanogui::TextBox::Alignment::Left);
464 lb->setEditable(
true);
468 w->add<nanogui::Label>(
" ");
470 auto tabWidget = w->add<nanogui::TabWidget>();
472 auto* tab1 = tabWidget->createTab(
"View");
473 tab1->setLayout(
new nanogui::GroupLayout());
475 auto* tab2 = tabWidget->createTab(
"Maps");
476 tab2->setLayout(
new nanogui::BoxLayout(
477 nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
479 auto* tab3 = tabWidget->createTab(
"Travelling");
480 tab3->setLayout(
new nanogui::BoxLayout(
481 nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
483 tabWidget->setActiveTab(0);
488 tab2->add<nanogui::Label>(
"Render options:");
491 auto pn = tab2->add<nanogui::Widget>();
492 pn->setLayout(
new nanogui::GridLayout(
493 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
495 lbPointSize = pn->add<nanogui::Label>(
"Point size");
498 slPointSize = pn->add<nanogui::Slider>();
499 slPointSize->setRange({1.0f, 10.0f});
500 slPointSize->setValue(2.0
f);
501 slPointSize->setCallback([&](
float) { rebuild_3d_view(); });
504 cbViewVoxelsAsPoints =
505 tab2->add<nanogui::CheckBox>(
"Render voxel maps as point clouds");
507 cbViewVoxelsAsPoints->setChecked(
false);
508 cbViewVoxelsAsPoints->setCallback([&](
bool) { rebuild_3d_view(); });
510 cbViewVoxelsFreeSpace =
511 tab2->add<nanogui::CheckBox>(
"Render free space of voxel maps");
513 cbViewVoxelsFreeSpace->setChecked(
false);
514 cbViewVoxelsFreeSpace->setCallback([&](
bool) { rebuild_3d_view(); });
516 cbColorizeMap = tab2->add<nanogui::CheckBox>(
"Recolorize map points");
518 cbColorizeMap->setChecked(
true);
519 cbColorizeMap->setCallback([&](
bool) { rebuild_3d_view(); });
521 cbKeepOriginalCloudColors =
522 tab2->add<nanogui::CheckBox>(
"Keep original cloud colors");
524 cbKeepOriginalCloudColors->setChecked(
false);
525 cbKeepOriginalCloudColors->setCallback([&](
bool)
526 { rebuild_3d_view(); });
528 tab2->add<nanogui::Label>(
" ");
530 auto pn = tab2->add<nanogui::Widget>();
531 pn->setLayout(
new nanogui::GridLayout(
532 nanogui::Orientation::Horizontal, 4, nanogui::Alignment::Fill));
533 pn->add<nanogui::Label>(
"Visible layers:");
535 auto* btnCheckAll = pn->add<nanogui::Button>(
"", ENTYPO_ICON_CHECK);
537 btnCheckAll->setCallback(
540 for (
auto& [name, cb] : cbLayersByName)
541 cb->setChecked(
true);
547 pn->add<nanogui::Button>(
"", ENTYPO_ICON_CIRCLE_WITH_CROSS);
549 btnCheckNone->setCallback(
552 for (
auto& [name, cb] : cbLayersByName)
553 cb->setChecked(
false);
558 panelLayers = tab2->add<nanogui::Widget>();
559 panelLayers->setLayout(
new nanogui::BoxLayout(
560 nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
562 rebuildLayerCheckboxes();
565 tab2->add<nanogui::Label>(
" ");
567 tab2->add<nanogui::Button>(
"Export marked layers...");
569 btnSave->setCallback([]() { onSaveLayers(); });
576 auto pn = tab1->add<nanogui::Widget>();
577 pn->setLayout(
new nanogui::GridLayout(
578 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
580 lbTrajThick = pn->add<nanogui::Label>(
"Trajectory thickness:");
583 slTrajectoryThickness = pn->add<nanogui::Slider>();
584 slTrajectoryThickness->setEnabled(trajectory.size() >= 2);
585 slTrajectoryThickness->setRange({std::log(0.005
f), std::log(2.0
f)});
586 slTrajectoryThickness->setValue(std::log(0.05
f));
587 slTrajectoryThickness->setCallback(
590 glTrajectory->clear();
596 auto pn = tab1->add<nanogui::Widget>();
597 pn->setLayout(
new nanogui::GridLayout(
598 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
601 pn->add<nanogui::Label>(
"Center depth clip plane:");
604 slMidDepthField = pn->add<nanogui::Slider>();
605 slMidDepthField->setRange({-2.0, 3.0});
606 slMidDepthField->setValue(1.0
f);
607 slMidDepthField->setCallback([&](
float) { rebuild_3d_view(); });
611 auto pn = tab1->add<nanogui::Widget>();
612 pn->setLayout(
new nanogui::GridLayout(
613 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
615 lbDepthFieldThickness =
616 pn->add<nanogui::Label>(
"Max-Min depth thickness:");
619 slThicknessDepthField = pn->add<nanogui::Slider>();
620 slThicknessDepthField->setRange({-2.0, 6.0});
621 slThicknessDepthField->setValue(3.0);
622 slThicknessDepthField->setCallback([&](
float)
623 { rebuild_3d_view(); });
626 auto pn = tab1->add<nanogui::Widget>();
627 pn->setLayout(
new nanogui::GridLayout(
628 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
630 lbCameraFOV = pn->add<nanogui::Label>(
"Camera FOV:");
632 slCameraFOV = pn->add<nanogui::Slider>();
633 slCameraFOV->setRange({20.0f, 170.0f});
634 slCameraFOV->setValue(90.0
f);
635 slCameraFOV->setCallback([&](
float) { rebuild_3d_view(); });
637 lbDepthFieldValues = tab1->add<nanogui::Label>(
" ");
641 auto pn = tab1->add<nanogui::Widget>();
642 pn->setLayout(
new nanogui::GridLayout(
643 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
645 cbViewOrtho = pn->add<nanogui::CheckBox>(
"Orthogonal view");
647 cbViewOrtho->setCallback([&](
bool) { rebuild_3d_view(); });
650 cbView2D = pn->add<nanogui::CheckBox>(
"Force 2D view");
652 cbView2D->setCallback([&](
bool) { rebuild_3d_view(); });
655 cbShowGroundGrid = tab1->add<nanogui::CheckBox>(
"Show ground grid");
657 cbShowGroundGrid->setChecked(
true);
658 cbShowGroundGrid->setCallback([&](
bool) { rebuild_3d_view(); });
660 cbApplyGeoRef = tab1->add<nanogui::CheckBox>(
661 "Apply georeferenced pose (if available)");
663 cbApplyGeoRef->setCallback([&](
bool) { rebuild_3d_view(); });
668 tab3->add<nanogui::Label>(
"Define camera travelling paths");
671 auto pn = tab3->add<nanogui::Widget>();
672 pn->setLayout(
new nanogui::GridLayout(
673 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
675 auto lb = pn->add<nanogui::Label>(
"Keyframes:");
678 cbTravellingKeys = tab3->add<nanogui::ComboBox>();
681 rebuildCamTravellingCombo();
683 tab3->add<nanogui::Label>(
"");
685 nanogui::TextBox* edTime;
687 auto pn = tab3->add<nanogui::Widget>();
688 pn->setLayout(
new nanogui::GridLayout(
689 nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
691 pn->add<nanogui::Label>(
"New keyframe:")
694 edTime = pn->add<nanogui::TextBox>();
695 edTime->setAlignment(nanogui::TextBox::Alignment::Left);
696 edTime->setValue(
"0.0");
697 edTime->setEditable(
true);
698 edTime->setPlaceholder(
"Time for this keyframe [s]");
699 edTime->setFormat(
"[0-9\\.]*");
703 pn->add<nanogui::Button>(
"Add", ENTYPO_ICON_ADD_TO_LIST);
708 const auto p = mrpt::math::TPose3D(
709 win->camera().cameraParams().cameraPointingX,
710 win->camera().cameraParams().cameraPointingY,
711 win->camera().cameraParams().cameraPointingZ,
713 win->camera().cameraParams().cameraAzimuthDeg),
715 win->camera().cameraParams().cameraElevationDeg),
716 win->camera().cameraParams().cameraZoomDistance *
718 camTravelling.insert(
719 mrpt::Clock::fromDouble(std::stod(edTime->value())), p);
720 rebuildCamTravellingCombo();
723 std::to_string(std::stod(edTime->value()) + 1));
727 tab3->add<nanogui::Label>(
"");
730 auto pn = tab3->add<nanogui::Widget>();
731 pn->setLayout(
new nanogui::GridLayout(
732 nanogui::Orientation::Horizontal, 3, nanogui::Alignment::Fill));
734 pn->add<nanogui::Label>(
"Playback:");
736 pn->add<nanogui::Button>(
"", ENTYPO_ICON_CONTROLLER_PLAY);
738 btnAnimate->setCallback(
741 if (camTravelling.empty())
return;
742 camTravellingCurrentTime.emplace(
743 mrpt::Clock::toDouble(camTravelling.begin()->first));
744 btnAnimate->setEnabled(
false);
745 btnAnimStop->setEnabled(
true);
748 pn->add<nanogui::Button>(
"", ENTYPO_ICON_CIRCLE_WITH_CROSS);
750 btnAnimStop->setEnabled(
false);
751 btnAnimStop->setCallback([]() { camTravellingStop(); });
755 auto pn = tab3->add<nanogui::Widget>();
756 pn->setLayout(
new nanogui::GridLayout(
757 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
759 auto lb = pn->add<nanogui::Label>(
"Animation FPS:");
762 edAnimFPS = pn->add<nanogui::TextBox>(
"30.0");
764 edAnimFPS->setFormat(
"[0-9\\.]*");
765 edAnimFPS->setEditable(
true);
768 auto pn = tab3->add<nanogui::Widget>();
769 pn->setLayout(
new nanogui::GridLayout(
770 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill));
772 auto lb = pn->add<nanogui::Label>(
"Interpolation:");
775 cbTravellingInterp = pn->add<nanogui::ComboBox>();
777 cbTravellingInterp->setItems({
"Linear",
"Spline"});
778 cbTravellingInterp->setSelectedIndex(0);
781 slAnimProgress = tab3->add<nanogui::Slider>();
782 slAnimProgress->setEnabled(
false);
785 lbMousePos = w->add<nanogui::Label>(
"Mouse pointing to:");
787 lbCameraPointing = w->add<nanogui::Label>(
"Camera looking at:");
790 w->add<nanogui::Button>(
"Quit", ENTYPO_ICON_ARROW_BOLD_LEFT)
791 ->setCallback([]() { win->setVisible(
false); });
793 win->setKeyboardCallback(
794 [&](
int key, [[maybe_unused]]
int scancode,
int action,
795 [[maybe_unused]]
int modifiers)
797 if (action != GLFW_PRESS && action != GLFW_REPEAT)
return false;
799 onKeyboardAction(key);
808 win->performLayout();
809 win->camera().setCameraPointing(8.0
f, .0
f, .0
f);
810 win->camera().setAzimuthDegrees(110.0
f);
811 win->camera().setElevationDegrees(15.0
f);
812 win->camera().setZoomDistance(50.0
f);
815 #define LOAD_CB_STATE(CB_NAME__) do_cb(CB_NAME__, #CB_NAME__)
816 #define SAVE_CB_STATE(CB_NAME__) \
817 appCfg.write("", #CB_NAME__, CB_NAME__->checked())
819 #define LOAD_SL_STATE(SL_NAME__) do_sl(SL_NAME__, #SL_NAME__)
820 #define SAVE_SL_STATE(SL_NAME__) \
821 appCfg.write("", #SL_NAME__, SL_NAME__->value())
823 auto load_UI_state_from_user_config = [&]()
825 auto do_cb = [&](nanogui::CheckBox* cb,
const std::string& name)
826 { cb->setChecked(appCfg.read_bool(
"", name, cb->checked())); };
827 auto do_sl = [&](nanogui::Slider* sl,
const std::string& name)
828 { sl->setValue(appCfg.read_float(
"", name, sl->value())); };
830 LOAD_CB_STATE(cbApplyGeoRef);
831 LOAD_CB_STATE(cbViewOrtho);
832 LOAD_CB_STATE(cbView2D);
833 LOAD_CB_STATE(cbViewVoxelsAsPoints);
834 LOAD_CB_STATE(cbViewVoxelsFreeSpace);
835 LOAD_CB_STATE(cbColorizeMap);
836 LOAD_CB_STATE(cbKeepOriginalCloudColors);
837 LOAD_CB_STATE(cbShowGroundGrid);
839 LOAD_SL_STATE(slPointSize);
840 LOAD_SL_STATE(slTrajectoryThickness);
841 LOAD_SL_STATE(slMidDepthField);
842 LOAD_SL_STATE(slThicknessDepthField);
843 LOAD_SL_STATE(slCameraFOV);
845 win->camera().setCameraPointing(
846 appCfg.read_float(
"",
"cam_x", win->camera().getCameraPointingX()),
847 appCfg.read_float(
"",
"cam_y", win->camera().getCameraPointingY()),
848 appCfg.read_float(
"",
"cam_z", win->camera().getCameraPointingZ()));
849 win->camera().setAzimuthDegrees(
850 appCfg.read_float(
"",
"cam_az", win->camera().getAzimuthDegrees()));
851 win->camera().setElevationDegrees(appCfg.read_float(
852 "",
"cam_el", win->camera().getElevationDegrees()));
853 win->camera().setZoomDistance(
854 appCfg.read_float(
"",
"cam_d", win->camera().getZoomDistance()));
856 auto save_UI_state_to_user_config = [&]()
858 SAVE_CB_STATE(cbApplyGeoRef);
859 SAVE_CB_STATE(cbViewOrtho);
860 SAVE_CB_STATE(cbView2D);
861 SAVE_CB_STATE(cbViewVoxelsAsPoints);
862 SAVE_CB_STATE(cbViewVoxelsFreeSpace);
863 SAVE_CB_STATE(cbColorizeMap);
864 SAVE_CB_STATE(cbKeepOriginalCloudColors);
865 SAVE_CB_STATE(cbShowGroundGrid);
867 SAVE_SL_STATE(slPointSize);
868 SAVE_SL_STATE(slTrajectoryThickness);
869 SAVE_SL_STATE(slMidDepthField);
870 SAVE_SL_STATE(slThicknessDepthField);
871 SAVE_SL_STATE(slCameraFOV);
873 appCfg.write(
"",
"cam_x", win->camera().getCameraPointingX());
874 appCfg.write(
"",
"cam_y", win->camera().getCameraPointingY());
875 appCfg.write(
"",
"cam_z", win->camera().getCameraPointingZ());
876 appCfg.write(
"",
"cam_az", win->camera().getAzimuthDegrees());
877 appCfg.write(
"",
"cam_el", win->camera().getElevationDegrees());
878 appCfg.write(
"",
"cam_d", win->camera().getZoomDistance());
882 load_UI_state_from_user_config();
890 win->setVisible(
true);
892 win->addLoopCallback(
895 updateMouseCoordinates();
896 updateCameraLookCoordinates();
897 observeViewOptions();
898 updateMiniCornerView();
899 processCameraTravelling();
902 nanogui::mainloop(1 , -1 );
907 save_UI_state_to_user_config();
914 void rebuild_3d_view()
916 using namespace std::string_literals;
918 lbMapStats[0]->setValue(theMapFileName);
924 std::optional<mrpt::math::TBoundingBoxf> mapBbox;
930 for (
const auto& [lyName, cb] : cbLayersByName)
933 cb->setCaption(lyName);
934 if (
auto itL = theMap.
layers.find(lyName); itL != theMap.
layers.end())
936 if (
auto pc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
942 mrpt::system::unitsFormat(
943 static_cast<double>(pc->size()), 2,
false) +
944 " points"s +
" | class="s +
945 pc->GetRuntimeClass()->className);
947 const auto bb = pc->boundingBox();
948 if (!mapBbox.has_value())
950 else { mapBbox = mapBbox->unionWith(bb); }
955 lyName +
" | class="s +
956 itL->second->GetRuntimeClass()->className);
961 if (!cb->checked())
continue;
965 rpL.pointSize = slPointSize->value();
966 rpL.render_voxelmaps_as_points = cbViewVoxelsAsPoints->checked();
967 rpL.render_voxelmaps_free_space = cbViewVoxelsFreeSpace->checked();
969 lbPointSize->setCaption(
"Point size: " + std::to_string(rpL.pointSize));
971 if (cbColorizeMap->checked())
973 auto& cm = rpL.colorMode.emplace();
974 cm.colorMap = mrpt::img::TColormap::cmJET;
977 if (cbKeepOriginalCloudColors->checked())
979 auto& cm = rpL.colorMode.emplace();
980 cm.keep_original_cloud_color =
true;
986 rp.color = mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
989 static std::optional<mp2p_icp::render_params_t> prevRenderParams;
991 if (!prevRenderParams.has_value() || prevRenderParams.value() != rpMap)
993 prevRenderParams = rpMap;
1000 mrpt::img::TColor(0xff, 0x00, 0x00, 0xff);
1002 glVizMap->insert(glPts);
1003 glVizMap->insert(glMapCorner);
1004 glVizMap->insert(glTrajectory);
1007 if (cbApplyGeoRef->checked() && theMap.
georeferencing.has_value())
1011 glENUCorner->setVisibility(
true);
1015 glVizMap->setPose(mrpt::poses::CPose3D::Identity());
1016 glGrid->setPose(mrpt::poses::CPose3D::Identity());
1017 glENUCorner->setVisibility(
false);
1023 glGrid->setPlaneLimits(
1024 mapBbox->min.x, mapBbox->max.x, mapBbox->min.y, mapBbox->max.y);
1026 glGrid->setVisibility(cbShowGroundGrid->checked());
1029 if (glTrajectory->empty() && trajectory.size() >= 2)
1031 const float trajCylRadius = std::exp(slTrajectoryThickness->value());
1032 lbTrajThick->setCaption(
1033 "Traj. thickness: " + std::to_string(trajCylRadius));
1035 std::optional<mrpt::math::TPose3D> prevPose;
1036 for (
const auto& [t, p] : trajectory)
1040 const auto& p0 = prevPose.value();
1042 auto glSegment = mrpt::opengl::CArrow::Create();
1043 glSegment->setArrowEnds(p0.translation(), p.translation());
1044 glSegment->setHeadRatio(.0);
1045 glSegment->setLargeRadius(trajCylRadius);
1046 glSegment->setSmallRadius(trajCylRadius);
1047 glSegment->setColor_u8(0x30, 0x30, 0x30, 0xff);
1049 glTrajectory->insert(glSegment);
1057 auto gl_view = win->background_scene->createViewport(
"small-view");
1059 gl_view->setViewportPosition(0, 0, 0.1, 0.1 * 16.0 / 9.0);
1060 gl_view->setTransparent(
true);
1062 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"X");
1063 obj->setLocation(1.1, 0, 0);
1064 gl_view->insert(obj);
1067 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"Y");
1068 obj->setLocation(0, 1.1, 0);
1069 gl_view->insert(obj);
1072 mrpt::opengl::CText::Ptr obj = mrpt::opengl::CText::Create(
"Z");
1073 obj->setLocation(0, 0, 1.1);
1074 gl_view->insert(obj);
1076 gl_view->insert(mrpt::opengl::stock_objects::CornerXYZ());
1081 std::lock_guard<std::mutex> lck(win->background_scene_mtx);
1082 win->camera().setCameraProjective(
1083 !cbViewOrtho->checked() && !cbView2D->checked());
1086 const auto depthFieldMid =
std::pow(10.0, slMidDepthField->value());
1087 const auto depthFieldThickness =
1088 std::pow(10.0, slThicknessDepthField->value());
1090 const auto clipNear =
1091 std::max(1e-2, depthFieldMid - 0.5 * depthFieldThickness);
1092 const auto clipFar = depthFieldMid + 0.5 * depthFieldThickness;
1094 const float cameraFOV = slCameraFOV->value();
1095 win->camera().setCameraFOV(cameraFOV);
1096 win->camera().setMaximumZoom(std::max<double>(1000, 3.0 * clipFar));
1098 lbDepthFieldValues->setCaption(
1099 mrpt::format(
"Depth field: near=%g far=%g", clipNear, clipFar));
1100 lbDepthFieldMid->setCaption(
1101 mrpt::format(
"Frustrum center: %.03g", depthFieldMid));
1102 lbDepthFieldThickness->setCaption(
1103 mrpt::format(
"Frustum thickness: %.03g", depthFieldThickness));
1105 lbDepthFieldValues->setCaption(
1106 mrpt::format(
"Frustum: near=%.02g far=%.02g", clipNear, clipFar));
1108 lbCameraFOV->setCaption(
1109 mrpt::format(
"Camera FOV: %.02f deg", cameraFOV));
1111 win->background_scene->getViewport()->setViewportClipDistances(
1119 nanogui::file_dialog({{
"txt",
"(*.txt)"}},
true );
1120 if (outFile.empty())
return;
1122 for (
const auto& [lyName, cb] : cbLayersByName)
1124 if (
auto itL = theMap.
layers.find(lyName); itL != theMap.
layers.end())
1126 itL->second->saveMetricMapRepresentationToFile(outFile);
1131 #else // MRPT_HAS_NANOGUI
1135 "This application requires a version of MRPT built with nanogui "
1139 #endif // MRPT_HAS_NANOGUI
1146 if (!
cmd.parse(argc, argv))
return 1;
1153 std::cout <<
"Loading plugin(s): " << plugins << std::endl;
1154 if (!mrpt::system::loadPluginModules(plugins, errMsg))
1156 std::cerr << errMsg << std::endl;
1165 bool trajectoryReadOk =
1167 ASSERT_(trajectoryReadOk);
1168 std::cout <<
"Read trajectory with " << trajectory.size()
1175 catch (std::exception& e)
1177 std::cerr <<
"Exit due to exception:\n"
1178 << mrpt::exception_to_str(e) << std::endl;