10 #include <mrpt/core/format.h>
11 #include <mrpt/core/get_env.h>
12 #include <mrpt/core/lock_helper.h>
13 #include <mrpt/core/round.h>
14 #include <mrpt/math/TLine3D.h>
15 #include <mrpt/math/TObject3D.h>
16 #include <mrpt/math/geometry.h>
17 #include <mrpt/obs/CObservation3DRangeScan.h>
18 #include <mrpt/obs/CObservationImage.h>
19 #include <mrpt/opengl/COpenGLScene.h>
20 #include <mrpt/version.h>
27 #if MRPT_VERSION >= 0x204
28 #include <mrpt/system/thread_name.h>
31 using namespace mvsim;
55 #if MRPT_VERSION >= 0x211
56 nanogui::Window* w = gui_win->createManagedSubWindow(
"Control");
58 nanogui::Window* w =
new nanogui::Window(gui_win.get(),
"Control");
62 gui_win->getSubWindowsUI()->setPosition({1, 1});
64 w->setPosition({1, 80});
66 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 5));
72 parent_.simulator_must_close(
true);
73 gui_win->setVisible(
false);
77 std::vector<std::string> lstVehicles;
78 lstVehicles.reserve(parent_.vehicles_.size() + 1);
80 lstVehicles.push_back(
"[none]");
81 for (
const auto& v : parent_.vehicles_) lstVehicles.push_back(v.first);
83 w->add<nanogui::Label>(
"Camera follows:");
84 auto cbFollowVeh = w->add<nanogui::ComboBox>(lstVehicles);
85 cbFollowVeh->setSelectedIndex(0);
86 cbFollowVeh->setCallback(
87 [
this, lstVehicles](
int idx)
90 parent_.guiOptions_.follow_vehicle.clear();
91 else if (idx <=
static_cast<int>(parent_.vehicles_.size()))
92 parent_.guiOptions_.follow_vehicle = lstVehicles[idx];
95 w->add<nanogui::CheckBox>(
96 "Orthogonal view", [&](
bool b) { gui_win->camera().setCameraProjective(!b); })
97 ->setChecked(parent_.guiOptions_.ortho);
99 #if MRPT_VERSION >= 0x270
100 w->add<nanogui::CheckBox>(
104 auto vv = parent_.worldVisual_->getViewport();
105 auto vp = parent_.worldPhysical_.getViewport();
106 vv->enableShadowCasting(b);
107 vp->enableShadowCasting(b);
108 parent_.lightOptions_.enable_shadows = b;
110 ->setChecked(parent_.lightOptions_.enable_shadows);
113 w->add<nanogui::Label>(
"Light azimuth:");
115 auto sl = w->add<nanogui::Slider>();
116 sl->setRange({-M_PI, M_PI});
117 sl->setValue(parent_.lightOptions_.light_azimuth);
121 parent_.lightOptions_.light_azimuth = v;
122 parent_.setLightDirectionFromAzimuthElevation(
123 parent_.lightOptions_.light_azimuth, parent_.lightOptions_.light_elevation);
126 w->add<nanogui::Label>(
"Light elevation:");
128 auto sl = w->add<nanogui::Slider>();
129 sl->setRange({0, M_PI * 0.5});
130 sl->setValue(parent_.lightOptions_.light_elevation);
134 parent_.lightOptions_.light_elevation = v;
135 parent_.setLightDirectionFromAzimuthElevation(
136 parent_.lightOptions_.light_azimuth, parent_.lightOptions_.light_elevation);
140 w->add<nanogui::CheckBox>(
"View forces", [&](
bool b) { parent_.guiOptions_.show_forces = b; })
141 ->setChecked(parent_.guiOptions_.show_forces);
143 w->add<nanogui::CheckBox>(
144 "View sensor pointclouds",
147 std::lock_guard<std::mutex> lck(gui_win->background_scene_mtx);
149 auto glVizSensors = std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
150 gui_win->background_scene->getByName(
"group_sensors_viz"));
151 ASSERT_(glVizSensors);
153 glVizSensors->setVisibility(b);
155 ->setChecked(parent_.guiOptions_.show_sensor_points);
157 w->add<nanogui::CheckBox>(
162 for (
const auto& o : *objs) o->setVisibility(b);
166 w->add<nanogui::CheckBox>(
171 for (
const auto& o : *objs) o->setVisibility(b);
175 w->add<nanogui::CheckBox>(
176 "View collision shapes",
179 auto lck = mrpt::lockHelper(parent_.simulableObjectsMtx_);
180 for (
auto&
s : parent_.simulableObjects_)
193 #if MRPT_VERSION >= 0x211
194 nanogui::Window* w = gui_win->createManagedSubWindow(
"Status");
196 nanogui::Window* w =
new nanogui::Window(gui_win.get(),
"Status");
199 w->setPosition({5, 455});
200 w->setLayout(
new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
201 w->setFixedWidth(320);
203 #if MRPT_VERSION < 0x211
206 ->setCallback([w]() { w->setVisible(
false); });
209 lbCpuUsage = w->add<nanogui::Label>(
" ");
210 lbStatuses.resize(12);
211 for (
size_t i = 0; i < lbStatuses.size(); i++) lbStatuses[i] = w->add<nanogui::Label>(
" ");
217 #if MRPT_VERSION >= 0x211
218 #if MRPT_VERSION >= 0x231
219 const auto subwinIdx = gui_win->getSubwindowCount();
221 nanogui::Window* w = gui_win->createManagedSubWindow(
"Editor");
223 nanogui::Window* w =
new nanogui::Window(gui_win.get(),
"Editor");
226 constexpr
int pnWidth = 300, pnHeight = 200;
227 constexpr
int COORDS_LABEL_WIDTH = 60;
228 constexpr
int slidersWidth = pnWidth - 80 - COORDS_LABEL_WIDTH;
230 w->setPosition({1, 230});
232 new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 3, 3));
233 w->setFixedWidth(pnWidth);
235 #if MRPT_VERSION < 0x211
238 ->setCallback([w]() { w->setVisible(
false); });
241 w->add<nanogui::Label>(
"Selected object",
"sans-bold");
246 static std::function<
void(
const mrpt::math::TPose3D)> onEntitySelected;
247 static std::function<
void(
const mrpt::math::TPose3D)> onEntityMoved;
249 auto lckListObjs = mrpt::lockHelper(parent_.getListOfSimulableObjectsMtx());
250 if (!parent_.getListOfSimulableObjects().empty())
252 auto tab = w->add<nanogui::TabWidget>();
254 constexpr
size_t NUM_TABS = 5;
256 std::array<nanogui::Widget*, NUM_TABS> tabs = {
257 tab->createTab(
"Vehicles"), tab->createTab(
"Sensors"), tab->createTab(
"Blocks"),
258 tab->createTab(
"Elements"), tab->createTab(
"Misc.")};
260 tab->setActiveTab(0);
263 t->setLayout(
new nanogui::BoxLayout(
264 nanogui::Orientation::Vertical, nanogui::Alignment::Minimum, 3, 3));
266 std::array<nanogui::VScrollPanel*, NUM_TABS> vscrolls;
267 for (
size_t i = 0; i < NUM_TABS; i++) vscrolls[i] = tabs[i]->add<nanogui::VScrollPanel>();
269 for (
auto vs : vscrolls) vs->setFixedSize({pnWidth, pnHeight});
273 std::array<nanogui::Widget*, NUM_TABS> wrappers;
274 for (
size_t i = 0; i < NUM_TABS; i++)
276 wrappers[i] = vscrolls[i]->add<nanogui::Widget>();
277 wrappers[i]->setFixedSize({pnWidth, pnHeight});
278 wrappers[i]->setLayout(
new nanogui::GridLayout(
279 nanogui::Orientation::Horizontal, 1 , nanogui::Alignment::Minimum, 3,
284 SimulableList listAllObjs = parent_.getListOfSimulableObjects();
287 for (
const auto& o : parent_.getListOfSimulableObjects())
289 if (
auto v =
dynamic_cast<VehicleBase*
>(o.second.get()); v)
291 auto& sensors = v->getSensors();
292 for (
auto& sensor : sensors)
294 const auto sensorFullName =
295 sensor->vehicle().getName() +
"."s + sensor->getName();
296 listAllObjs.insert({sensorFullName, sensor});
302 for (
const auto& o : listAllObjs)
306 const auto& name = o.first;
308 if (
auto v =
dynamic_cast<VehicleBase*
>(o.second.get()); v)
313 if (
auto v =
dynamic_cast<Block*
>(o.second.get()); v)
318 if (
auto v =
dynamic_cast<SensorBase*
>(o.second.get()); v)
331 if (wrapperIdx < 0)
continue;
333 auto wrapper = wrappers[wrapperIdx];
335 std::string label = name;
336 if (label.empty()) label =
"(unnamed)";
338 auto cb = wrapper->add<nanogui::CheckBox>(label);
341 gui_cbObjects.emplace_back(ipo);
343 cb->setChecked(
false);
345 [cb, ipo,
this](
bool check)
348 if (gui_selectedObject.visual)
349 gui_selectedObject.visual->showCollisionShape(
false);
350 if (gui_selectedObject.cb) gui_selectedObject.cb->setChecked(
false);
353 cb->setChecked(
check);
358 gui_selectedObject = ipo;
362 const bool btnsEnabled = !!gui_selectedObject.simulable;
363 for (
auto b : btns_selectedOps) b->setEnabled(btnsEnabled);
367 onEntitySelected(ipo.
simulable->getRelativePose());
380 const std::string outFile = nanogui::file_dialog(
381 {{
"3Dscene",
"MRPT 3D scene file (*.3Dsceme)"}},
true );
382 if (outFile.empty())
return;
384 auto lck = mrpt::lockHelper(parent_.physical_objects_mtx());
385 parent_.worldPhysical_.saveToFile(outFile);
387 std::cout <<
"[mvsim gui] Saved world scene to: " << outFile << std::endl;
389 catch (
const std::exception& e)
391 std::cerr <<
"[mvsim gui] Exception while saving 3D scene:\n"
392 << e.what() << std::endl;
397 w->add<nanogui::Label>(
" ");
401 btnReplaceObject->setFlags(nanogui::Button::Flags::ToggleButton);
402 btns_selectedOps.push_back(btnReplaceObject);
405 constexpr
float REPOSITION_SLIDER_RANGE = 1.0;
407 nanogui::Slider* slidersCoordScale =
nullptr;
408 nanogui::Label* slidersCoordScaleValue =
nullptr;
410 auto pn = w->add<nanogui::Widget>();
411 pn->setLayout(
new nanogui::BoxLayout(
412 nanogui::Orientation::Horizontal, nanogui::Alignment::Fill, 2, 2));
413 pn->add<nanogui::Label>(
"Change scale:");
415 auto slCoord = pn->add<nanogui::Slider>();
416 slidersCoordScale = slCoord;
418 slCoord->setRange({-4.0, 1.0});
420 slCoord->setCallback(
421 [
this]([[maybe_unused]]
float v)
424 if (!gui_selectedObject.simulable || !onEntitySelected)
return;
425 onEntitySelected(gui_selectedObject.simulable->getRelativePose());
427 slCoord->setFixedWidth(slidersWidth - 30);
428 btns_selectedOps.push_back(slCoord);
430 slidersCoordScaleValue = pn->add<nanogui::Label>(
" ");
431 slidersCoordScaleValue->setFixedWidth(70);
434 std::array<nanogui::Slider*, 6> slidersCoords;
435 std::array<nanogui::Label*, 6> slidersCoordsValues;
436 const std::array<const char*, 6> coordsNames = {
444 for (
int axis = 0; axis < 6; axis++)
446 auto pn = w->add<nanogui::Widget>();
447 pn->setLayout(
new nanogui::BoxLayout(
448 nanogui::Orientation::Horizontal, nanogui::Alignment::Fill, 2, 2));
449 pn->add<nanogui::Label>(coordsNames[axis]);
451 auto slCoord = pn->add<nanogui::Slider>();
452 slidersCoords[axis] = slCoord;
455 slCoord->setRange({-1.0, 1.0});
457 slCoord->setCallback(
458 [
this, axis](
float v)
460 if (!gui_selectedObject.simulable)
return;
461 auto p = gui_selectedObject.simulable->getRelativePose();
463 gui_selectedObject.simulable->setRelativePose(p);
466 slCoord->setFixedWidth(slidersWidth);
467 btns_selectedOps.push_back(slCoord);
469 slidersCoordsValues[axis] = pn->add<nanogui::Label>(
"(...)");
470 slidersCoordsValues[axis]->setFixedWidth(COORDS_LABEL_WIDTH);
476 [slidersCoords, slidersCoordScale, slidersCoordScaleValue](
const mrpt::math::TPose3D p)
478 ASSERT_(slidersCoordScale);
479 const double scale = std::pow(10.0, mrpt::round(slidersCoordScale->value()));
481 slidersCoordScaleValue->setCaption(mrpt::format(
"%.01e", scale));
484 for (
int i = 0; i < 3; i++)
486 slidersCoords[i]->setRange(
487 {p[i] - scale * REPOSITION_SLIDER_RANGE, p[i] + scale * REPOSITION_SLIDER_RANGE});
488 slidersCoords[i]->setValue(p[i]);
491 for (
int i = 0; i < 3; i++)
493 slidersCoords[i + 3]->setRange({p[i + 3] - scale * M_PI, p[i + 3] + scale * M_PI});
494 slidersCoords[i + 3]->setValue(p[i + 3]);
500 onEntityMoved = [slidersCoordsValues](
const mrpt::math::TPose3D p)
503 for (
int i = 0; i < 3; i++) slidersCoordsValues[i]->setCaption(mrpt::format(
"%.04f", p[i]));
505 for (
int i = 0; i < 3; i++)
506 slidersCoordsValues[i + 3]->setCaption(
507 mrpt::format(
"%.02f deg", mrpt::RAD2DEG(p[i + 3])));
511 auto btnPlaceCoords = w->add<
nanogui::Button>(
"Replace by coordinates...");
512 btns_selectedOps.push_back(btnPlaceCoords);
513 btnPlaceCoords->setCallback(
517 if (!gui_selectedObject.simulable)
return;
519 auto* formPose =
new nanogui::Window(gui_win.get(),
"Enter new pose");
520 formPose->setLayout(
new nanogui::GridLayout(
521 nanogui::Orientation::Horizontal, 2, nanogui::Alignment::Fill, 5));
523 nanogui::TextBox* lbs[6];
525 formPose->add<nanogui::Label>(
"x:");
526 lbs[0] = formPose->add<nanogui::TextBox>();
527 formPose->add<nanogui::Label>(
"y:");
528 lbs[1] = formPose->add<nanogui::TextBox>();
529 formPose->add<nanogui::Label>(
"z:");
530 lbs[2] = formPose->add<nanogui::TextBox>();
531 formPose->add<nanogui::Label>(
"Yaw:");
532 lbs[3] = formPose->add<nanogui::TextBox>();
533 formPose->add<nanogui::Label>(
"Pitch:");
534 lbs[4] = formPose->add<nanogui::TextBox>();
535 formPose->add<nanogui::Label>(
"Roll:");
536 lbs[5] = formPose->add<nanogui::TextBox>();
538 for (
int i = 0; i < 6; i++)
540 lbs[i]->setEditable(
true);
541 lbs[i]->setFixedSize({100, 20});
542 lbs[i]->setValue(
"0.0");
543 lbs[i]->setUnits(i >= 3 ?
"[deg]" :
"[m]");
544 lbs[i]->setDefaultValue(
"0.0");
545 lbs[i]->setFontSize(16);
546 lbs[i]->setFormat(
"[-]?[0-9]*\\.?[0-9]+");
549 const auto pos = gui_selectedObject.simulable->getRelativePose();
550 for (
int i = 0; i < 3; i++) lbs[i]->setValue(std::to_string(pos[i]));
552 for (
int i = 3; i < 6; i++) lbs[i]->setValue(std::to_string(mrpt::RAD2DEG(pos[i])));
554 formPose->add<nanogui::Label>(
"");
555 formPose->add<nanogui::Label>(
"");
558 { formPose->dispose(); });
561 [formPose,
this, lbs]()
563 const mrpt::math::TPose3D newPose = {
564 std::stod(lbs[0]->value()),
566 std::stod(lbs[1]->value()),
568 std::stod(lbs[2]->value()),
570 mrpt::DEG2RAD(std::stod(lbs[3]->value())),
572 mrpt::DEG2RAD(std::stod(lbs[4]->value())),
574 mrpt::DEG2RAD(std::stod(lbs[5]->value()))};
576 gui_selectedObject.simulable->setRelativePose(newPose);
577 onEntitySelected(newPose);
582 formPose->setModal(
true);
584 formPose->setVisible(
true);
588 for (
auto b : btns_selectedOps) b->setEnabled(
false);
591 #if MRPT_VERSION >= 0x231
592 gui_win->subwindowMinimize(subwinIdx);
594 if (
auto btnMinimize =
dynamic_cast<nanogui::Button*
>(w->buttonPanel()->children().at(0));
597 btnMinimize->callback()();
607 MRPT_LOG_DEBUG(
"[World::internal_GUI_thread] Started.");
612 mrpt::gui::CDisplayWindowGUI_Params cp;
613 cp.maximized = guiOptions_.start_maximized;
616 mrpt::gui::CDisplayWindowGUI::Create(
"mvsim", guiOptions_.win_w, guiOptions_.win_h, cp);
619 worldVisual_->getViewport()->setViewportClipDistances(
620 guiOptions_.clip_plane_min, guiOptions_.clip_plane_max);
629 worldVisual_->insert(glUserObjsViz_);
630 worldPhysical_.insert(glUserObjsPhysical_);
632 std::lock_guard<std::mutex> lck(gui_.gui_win->background_scene_mtx);
633 gui_.gui_win->background_scene = worldVisual_;
637 if (worldElements_.empty())
640 worldElements_.push_back(we);
644 gui_.prepare_control_window();
645 gui_.prepare_status_window();
646 gui_.prepare_editor_window();
649 gui_.gui_win->performLayout();
650 auto& cam = gui_.gui_win->camera();
652 cam.setCameraProjective(!guiOptions_.ortho);
653 cam.setZoomDistance(guiOptions_.camera_distance);
654 cam.setAzimuthDegrees(guiOptions_.camera_azimuth_deg);
655 cam.setElevationDegrees(guiOptions_.camera_elevation_deg);
656 cam.setCameraFOV(guiOptions_.fov_deg);
658 const auto p = this->worldRenderOffset() + guiOptions_.camera_point_to;
659 cam.setCameraPointing(p.x, p.y, p.z);
661 const auto& lo = lightOptions_;
663 setLightDirectionFromAzimuthElevation(lo.light_azimuth, lo.light_elevation);
665 #if MRPT_VERSION >= 0x270
666 auto vv = worldVisual_->getViewport();
667 auto vp = worldPhysical_.getViewport();
669 auto lambdaSetLightParams = [&lo](
const mrpt::opengl::COpenGLViewport::Ptr& v)
672 const int sms = lo.shadow_map_size;
673 v->enableShadowCasting(lo.enable_shadows, sms, sms);
676 const auto colf = mrpt::img::TColorf(lo.light_color);
678 auto& vlp = v->lightParameters();
682 #if MRPT_VERSION >= 0x2A0 // New in mrpt>=2.10.0
683 vlp.eyeDistance2lightShadowExtension = lo.eye_distance_to_shadow_map_extension;
685 vlp.minimum_shadow_map_extension_ratio = lo.minimum_shadow_map_extension_ratio;
688 v->setLightShadowClipDistances(lo.light_clip_plane_min, lo.light_clip_plane_max);
691 #if MRPT_VERSION >= 0x281
692 vlp.shadow_bias = lo.shadow_bias;
693 vlp.shadow_bias_cam2frag = lo.shadow_bias_cam2frag;
694 vlp.shadow_bias_normal = lo.shadow_bias_normal;
698 lambdaSetLightParams(vv);
699 lambdaSetLightParams(vp);
704 gui_.gui_win->drawAll();
705 gui_.gui_win->setVisible(
true);
708 #if MRPT_VERSION >= 0x232
709 gui_.gui_win->addKeyboardCallback(
711 gui_.gui_win->setKeyboardCallback(
713 [&](
int key,
int ,
int action,
int modifiers)
715 if (action != GLFW_PRESS && action != GLFW_REPEAT) return false;
717 auto lck = mrpt::lockHelper(lastKeyEventMtx_);
719 lastKeyEvent_.keycode = key;
720 lastKeyEvent_.modifierShift = (modifiers & GLFW_MOD_SHIFT) != 0;
721 lastKeyEvent_.modifierCtrl = (modifiers & GLFW_MOD_CONTROL) != 0;
722 lastKeyEvent_.modifierSuper = (modifiers & GLFW_MOD_SUPER) != 0;
723 lastKeyEvent_.modifierAlt = (modifiers & GLFW_MOD_ALT) != 0;
725 lastKeyEventValid_ = true;
730 gui_thread_running_ =
true;
734 auto lambdaLoopCallback = [](
World& me)
736 if (me.simulator_must_close()) nanogui::leave();
741 me.internalGraphicsLoopTasksForSimulation();
743 me.internal_process_pending_gui_user_tasks();
746 me.gui_.handle_mouse_operations();
748 catch (
const std::exception& e)
753 me.logStr(mrpt::system::LVL_ERROR, e.what());
760 #if MRPT_VERSION >= 0x232
761 gui_.gui_win->addLoopCallback(
763 gui_.gui_win->setLoopCallback(
765 [=]() { lambdaLoopCallback(*this); });
768 const auto lambdaOnObservation =
769 [
this](
const Simulable& veh,
const mrpt::obs::CObservation::Ptr& obs)
772 this->enqueue_task_to_run_in_gui_thread([this, obs, &veh]()
773 { internal_gui_on_observation(veh, obs); });
776 this->registerCallbackOnObservation(lambdaOnObservation);
779 const int refresh_ms = std::max(1, mrpt::round(1000 / guiOptions_.refresh_fps));
782 "[World::internal_GUI_thread] Using GUI FPS=%i (T=%i ms)", guiOptions_.refresh_fps,
785 #if MRPT_VERSION >= 0x253
786 const int idleLoopTasks_ms = 10;
788 nanogui::mainloop(idleLoopTasks_ms, refresh_ms);
790 nanogui::mainloop(refresh_ms);
793 MRPT_LOG_DEBUG(
"[World::internal_GUI_thread] Mainloop ended.");
796 simulator_must_close(
true);
802 auto lck = mrpt::lockHelper(gui_.gui_win->background_scene_mtx);
803 if (gui_.gui_win->background_scene)
804 gui_.gui_win->background_scene->freeOpenGLResources();
807 auto lckListObjs = mrpt::lockHelper(getListOfSimulableObjectsMtx());
809 for (
auto& obj : getListOfSimulableObjects()) obj.second->freeOpenGLResources();
811 lckListObjs.unlock();
816 gui_.gui_win.reset();
820 catch (
const std::exception& e)
822 MRPT_LOG_ERROR_STREAM(
"[internal_GUI_init] Exception: " << mrpt::exception_to_str(e));
824 gui_thread_running_ =
false;
827 void World::GUI::handle_mouse_operations()
832 mrpt::opengl::COpenGLViewport::Ptr vp;
834 auto lck = mrpt::lockHelper(
gui_win->background_scene_mtx);
835 if (!
gui_win->background_scene)
return;
836 vp =
gui_win->background_scene->getViewport();
840 const auto mousePt =
gui_win->mousePos();
841 mrpt::math::TLine3D ray;
842 vp->get3DRayForPixelCoord(mousePt.x(), mousePt.y(), ray);
845 const auto ground_plane = mrpt::math::TPlane::From3Points({0, 0, 0}, {1, 0, 0}, {0, 1, 0});
848 mrpt::math::TObject3D inters;
849 mrpt::math::intersect(ray, ground_plane, inters);
865 if (!zs.empty())
clickedPt.z = *zs.begin();
868 const auto screen =
gui_win->screen();
869 const bool leftClick = screen->mouseState() == 0x01;
874 static bool isReplacing =
false;
877 if (!isReplacing && !leftClick)
891 if (isReplacing && leftClick)
916 auto tle = mrpt::system::CTimeLoggerEntry(
timlogger_,
"internalRunSensorsOn3DScene");
919 for (
auto& sensor : v.second->getSensors())
920 if (sensor) sensor->simulateOn3DScene(physicalObjects);
927 mrpt::opengl::COpenGLScene& viz, mrpt::opengl::COpenGLScene& physical)
931 auto tle = mrpt::system::CTimeLoggerEntry(
timlogger_,
"update_GUI.2.map-elements");
941 for (
auto& v :
vehicles_) v.second->guiUpdate(viz, physical);
949 for (
auto& v :
blocks_) v.second->guiUpdate(viz, physical);
959 double cpu_usage_ratio = std::max(1e-10,
timlogger_.getMeanTime(
"run_simulation.cpu_dt")) /
960 std::max(1e-10,
timlogger_.getMeanTime(
"run_simulation.dt"));
963 "Time: %s (CPU usage: %.03f%%)",
964 mrpt::system::formatTimeInterval(
get_simul_time()).c_str(), cpu_usage_ratio * 100.0));
971 int nextStatusLine = 0;
972 if (!msg_lines.empty())
975 std::vector<std::string> lines;
976 mrpt::system::tokenize(msg_lines,
"\r\n", lines);
977 for (
const auto& l : lines)
gui_.
lbStatuses.at(nextStatusLine++)->setCaption(l);
980 ->setCaption(std::string(
"Mouse: ") +
gui_.
clickedPt.asString());
991 const auto pose = it->second->getCPose3D();
993 gui_.
gui_win->camera().setCameraPointing(p.x(), p.y(), p.z());
997 MRPT_LOG_THROTTLE_ERROR_FMT(
999 "GUI: Camera set to follow vehicle named '%s' which can't be "
1014 MRPT_LOG_DEBUG(
"[update_GUI] Launching GUI thread...");
1017 #if MRPT_VERSION >= 0x204
1018 mrpt::system::thread_name(
"guiThread",
gui_thread_);
1021 const int MVSIM_OPEN_GUI_TIMEOUT_MS =
1022 mrpt::get_env<int>(
"MVSIM_OPEN_GUI_TIMEOUT_MS", 3000);
1024 for (
int timeout = 0; timeout < MVSIM_OPEN_GUI_TIMEOUT_MS / 10; timeout++)
1026 std::this_thread::sleep_for(std::chrono::milliseconds(10));
1032 THROW_EXCEPTION(
"Timeout waiting for GUI to open!");
1036 MRPT_LOG_DEBUG(
"[update_GUI] GUI thread started.");
1043 MRPT_LOG_THROTTLE_WARN(
1045 "[World::update_GUI] GUI window has been closed, but note that "
1046 "simulation keeps running.");
1072 const Simulable& veh,
const mrpt::obs::CObservation::Ptr& obs)
1076 if (
auto obs3D = std::dynamic_pointer_cast<mrpt::obs::CObservation3DRangeScan>(obs); obs3D)
1080 else if (
auto obsIm = std::dynamic_pointer_cast<mrpt::obs::CObservationImage>(obs); obsIm)
1087 const Simulable& veh,
const std::shared_ptr<mrpt::obs::CObservation3DRangeScan>& obs)
1089 using namespace std::string_literals;
1093 mrpt::math::TPoint2D rgbImageWinSize = {0, 0};
1095 if (obs->hasIntensityImage)
1098 veh.
getName() +
"/"s + obs->sensorLabel +
"_rgb"s, obs->intensityImage, 5);
1100 if (obs->hasRangeImage)
1102 mrpt::math::CMatrixFloat
d;
1103 d = obs->rangeImage.asEigen().cast<
float>() * (obs->rangeUnits / obs->maxRange);
1105 mrpt::img::CImage imDepth;
1106 imDepth.setFromMatrix(
d,
true );
1109 veh.
getName() +
"/"s + obs->sensorLabel +
"_depth"s, imDepth,
1110 5 + 5 + rgbImageWinSize.x);
1115 const Simulable& veh,
const std::shared_ptr<mrpt::obs::CObservationImage>& obs)
1117 using namespace std::string_literals;
1119 if (!
gui_.
gui_win || !obs || obs->image.isEmpty())
return;
1121 mrpt::math::TPoint2D rgbImageWinSize = {0, 0};
1128 const std::string& label,
const mrpt::img::CImage& im,
int winPosX)
1130 mrpt::gui::MRPT2NanoguiGLCanvas* glControl;
1137 w->setLayout(
new nanogui::GridLayout(
1138 nanogui::Orientation::Vertical, 1, nanogui::Alignment::Fill, 2, 2));
1141 int winW = im.getWidth(), winH = im.getHeight();
1144 while (winW >= 512 || winH >= 512)
1150 glControl = w->add<mrpt::gui::MRPT2NanoguiGLCanvas>();
1151 glControl->setSize({winW, winH});
1152 glControl->setFixedSize({winW, winH});
1154 static std::map<int, int> numGuiWindows;
1155 w->setPosition({winPosX, 20 + (numGuiWindows[winPosX]++) * (winH + 10)});
1157 auto lck = mrpt::lockHelper(glControl->scene_mtx);
1159 glControl->scene = mrpt::opengl::COpenGLScene::Create();
1166 glControl =
dynamic_cast<mrpt::gui::MRPT2NanoguiGLCanvas*
>(w->children().at(1));
1167 ASSERT_(glControl !=
nullptr);
1169 auto lck = mrpt::lockHelper(glControl->scene_mtx);
1170 glControl->scene->getViewport()->setImageView(im);
1172 return mrpt::math::TPoint2D(w->size().x(), w->size().y());
1198 catch (
const std::exception& e)
1203 MRPT_LOG_ERROR(e.what());
1210 const mrpt::math::TPoint3Df dir = {
1211 -cos(azimuth) * cos(elevation), -sin(azimuth) * cos(elevation), -sin(elevation)};
1220 vv->lightParameters().direction = dir;
1221 vp->lightParameters().direction = dir;