World_gui.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2024 Jose Luis Blanco Claraco |
5  | Copyright (C) 2017 Borys Tymchenko (Odessa Polytechnic University) |
6  | Distributed under 3-clause BSD License |
7  | See COPYING |
8  +-------------------------------------------------------------------------+ */
9 
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>
21 #include <mvsim/World.h>
22 
23 #include <cmath> // cos(), sin()
24 #include <rapidxml.hpp>
25 
26 #include "xml_utils.h"
27 #if MRPT_VERSION >= 0x204
28 #include <mrpt/system/thread_name.h>
29 #endif
30 
31 using namespace mvsim;
32 using namespace std;
33 
35  const rapidxml::xml_node<char>& node, mrpt::system::COutputLogger& logger)
36 {
37  parse_xmlnode_children_as_param(node, params, {}, "[World::TGUI_Options]", &logger);
38 }
39 
41  const rapidxml::xml_node<char>& node, mrpt::system::COutputLogger& logger)
42 {
43  parse_xmlnode_children_as_param(node, params, {}, "[World::LightOptions]", &logger);
44 }
45 
48 bool World::is_GUI_open() const { return !!gui_.gui_win; }
50 void World::close_GUI() { gui_.gui_win.reset(); }
51 
52 // Add top menu subwindow:
54 {
55 #if MRPT_VERSION >= 0x211
56  nanogui::Window* w = gui_win->createManagedSubWindow("Control");
57 #else
58  nanogui::Window* w = new nanogui::Window(gui_win.get(), "Control");
59 #endif
60 
61  // Place control UI at the top-left corner:
62  gui_win->getSubWindowsUI()->setPosition({1, 1});
63 
64  w->setPosition({1, 80});
65  w->setLayout(
66  new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 5));
67 
68  w->add<nanogui::Button>("Quit", ENTYPO_ICON_ARROW_BOLD_LEFT)
69  ->setCallback(
70  [this]()
71  {
72  parent_.simulator_must_close(true);
73  gui_win->setVisible(false);
74  nanogui::leave();
75  });
76 
77  std::vector<std::string> lstVehicles;
78  lstVehicles.reserve(parent_.vehicles_.size() + 1);
79 
80  lstVehicles.push_back("[none]"); // None
81  for (const auto& v : parent_.vehicles_) lstVehicles.push_back(v.first);
82 
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)
88  {
89  if (idx == 0)
90  parent_.guiOptions_.follow_vehicle.clear();
91  else if (idx <= static_cast<int>(parent_.vehicles_.size()))
92  parent_.guiOptions_.follow_vehicle = lstVehicles[idx];
93  });
94 
95  w->add<nanogui::CheckBox>(
96  "Orthogonal view", [&](bool b) { gui_win->camera().setCameraProjective(!b); })
97  ->setChecked(parent_.guiOptions_.ortho);
98 
99 #if MRPT_VERSION >= 0x270
100  w->add<nanogui::CheckBox>(
101  "Enable shadows",
102  [&](bool b)
103  {
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;
109  })
110  ->setChecked(parent_.lightOptions_.enable_shadows);
111 #endif
112 
113  w->add<nanogui::Label>("Light azimuth:");
114  {
115  auto sl = w->add<nanogui::Slider>();
116  sl->setRange({-M_PI, M_PI});
117  sl->setValue(parent_.lightOptions_.light_azimuth);
118  sl->setCallback(
119  [this](float v)
120  {
121  parent_.lightOptions_.light_azimuth = v;
122  parent_.setLightDirectionFromAzimuthElevation(
123  parent_.lightOptions_.light_azimuth, parent_.lightOptions_.light_elevation);
124  });
125  }
126  w->add<nanogui::Label>("Light elevation:");
127  {
128  auto sl = w->add<nanogui::Slider>();
129  sl->setRange({0, M_PI * 0.5});
130  sl->setValue(parent_.lightOptions_.light_elevation);
131  sl->setCallback(
132  [this](float v)
133  {
134  parent_.lightOptions_.light_elevation = v;
135  parent_.setLightDirectionFromAzimuthElevation(
136  parent_.lightOptions_.light_azimuth, parent_.lightOptions_.light_elevation);
137  });
138  }
139 
140  w->add<nanogui::CheckBox>("View forces", [&](bool b) { parent_.guiOptions_.show_forces = b; })
141  ->setChecked(parent_.guiOptions_.show_forces);
142 
143  w->add<nanogui::CheckBox>(
144  "View sensor pointclouds",
145  [&](bool b)
146  {
147  std::lock_guard<std::mutex> lck(gui_win->background_scene_mtx);
148 
149  auto glVizSensors = std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
150  gui_win->background_scene->getByName("group_sensors_viz"));
151  ASSERT_(glVizSensors);
152 
153  glVizSensors->setVisibility(b);
154  })
155  ->setChecked(parent_.guiOptions_.show_sensor_points);
156 
157  w->add<nanogui::CheckBox>(
158  "View sensor poses",
159  [&](bool b)
160  {
161  const auto& objs = SensorBase::GetAllSensorsOriginViz();
162  for (const auto& o : *objs) o->setVisibility(b);
163  })
164  ->setChecked(false);
165 
166  w->add<nanogui::CheckBox>(
167  "View sensor FOVs",
168  [&](bool b)
169  {
170  const auto& objs = SensorBase::GetAllSensorsFOVViz();
171  for (const auto& o : *objs) o->setVisibility(b);
172  })
173  ->setChecked(false);
174 
175  w->add<nanogui::CheckBox>(
176  "View collision shapes",
177  [&](bool b)
178  {
179  auto lck = mrpt::lockHelper(parent_.simulableObjectsMtx_);
180  for (auto& s : parent_.simulableObjects_)
181  {
182  auto* vis = dynamic_cast<VisualObject*>(s.second.get());
183  if (!vis) continue;
184  vis->showCollisionShape(b);
185  }
186  })
187  ->setChecked(false);
188 }
189 
190 // Add Status window
192 {
193 #if MRPT_VERSION >= 0x211
194  nanogui::Window* w = gui_win->createManagedSubWindow("Status");
195 #else
196  nanogui::Window* w = new nanogui::Window(gui_win.get(), "Status");
197 #endif
198 
199  w->setPosition({5, 455});
200  w->setLayout(new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill));
201  w->setFixedWidth(320);
202 
203 #if MRPT_VERSION < 0x211
204  w->buttonPanel()
205  ->add<nanogui::Button>("", ENTYPO_ICON_CROSS)
206  ->setCallback([w]() { w->setVisible(false); });
207 #endif
208 
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>(" ");
212 }
213 
214 // Add editor window
216 {
217 #if MRPT_VERSION >= 0x211
218 #if MRPT_VERSION >= 0x231
219  const auto subwinIdx = gui_win->getSubwindowCount();
220 #endif
221  nanogui::Window* w = gui_win->createManagedSubWindow("Editor");
222 #else
223  nanogui::Window* w = new nanogui::Window(gui_win.get(), "Editor");
224 #endif
225 
226  constexpr int pnWidth = 300, pnHeight = 200;
227  constexpr int COORDS_LABEL_WIDTH = 60;
228  constexpr int slidersWidth = pnWidth - 80 - COORDS_LABEL_WIDTH;
229 
230  w->setPosition({1, 230});
231  w->setLayout(
232  new nanogui::BoxLayout(nanogui::Orientation::Vertical, nanogui::Alignment::Fill, 3, 3));
233  w->setFixedWidth(pnWidth);
234 
235 #if MRPT_VERSION < 0x211
236  w->buttonPanel()
237  ->add<nanogui::Button>("", ENTYPO_ICON_CROSS)
238  ->setCallback([w]() { w->setVisible(false); });
239 #endif
240 
241  w->add<nanogui::Label>("Selected object", "sans-bold");
242 
243  // Auxiliary lambda placeholder for when the user clicks on an object
244  // being able to load its current pose in the GUI controls yet to be
245  // constructed later on:
246  static std::function<void(const mrpt::math::TPose3D)> onEntitySelected;
247  static std::function<void(const mrpt::math::TPose3D)> onEntityMoved;
248 
249  auto lckListObjs = mrpt::lockHelper(parent_.getListOfSimulableObjectsMtx());
250  if (!parent_.getListOfSimulableObjects().empty())
251  {
252  auto tab = w->add<nanogui::TabWidget>();
253 
254  constexpr size_t NUM_TABS = 5;
255 
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.")};
259 
260  tab->setActiveTab(0);
261 
262  for (auto t : tabs)
263  t->setLayout(new nanogui::BoxLayout(
264  nanogui::Orientation::Vertical, nanogui::Alignment::Minimum, 3, 3));
265 
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>();
268 
269  for (auto vs : vscrolls) vs->setFixedSize({pnWidth, pnHeight});
270 
271  // vscroll should only have *ONE* child. this is what `wrapper`
272  // is for
273  std::array<nanogui::Widget*, NUM_TABS> wrappers;
274  for (size_t i = 0; i < NUM_TABS; i++)
275  {
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 /*columns */, nanogui::Alignment::Minimum, 3,
280  3));
281  }
282 
283  // Extend the list of world objects with the robot sensors:
284  SimulableList listAllObjs = parent_.getListOfSimulableObjects();
285  // Yes: we iterate over parent.getList...(), *not* the local copy, since
286  // it will be modified within the loop.
287  for (const auto& o : parent_.getListOfSimulableObjects())
288  {
289  if (auto v = dynamic_cast<VehicleBase*>(o.second.get()); v)
290  {
291  auto& sensors = v->getSensors();
292  for (auto& sensor : sensors)
293  {
294  const auto sensorFullName =
295  sensor->vehicle().getName() + "."s + sensor->getName();
296  listAllObjs.insert({sensorFullName, sensor});
297  }
298  }
299  }
300 
301  // Now, fill the editor list with all the existing objects:
302  for (const auto& o : listAllObjs)
303  {
304  InfoPerObject ipo;
305 
306  const auto& name = o.first;
307  int wrapperIdx = -1; // default. The tag "page" to show this at.
308  if (auto v = dynamic_cast<VehicleBase*>(o.second.get()); v)
309  {
310  wrapperIdx = 0;
311  ipo.visual = dynamic_cast<VisualObject*>(v);
312  }
313  if (auto v = dynamic_cast<Block*>(o.second.get()); v)
314  {
315  wrapperIdx = 2;
316  ipo.visual = dynamic_cast<VisualObject*>(v);
317  }
318  if (auto v = dynamic_cast<SensorBase*>(o.second.get()); v)
319  {
320  wrapperIdx = 1;
321  ipo.visual = dynamic_cast<VisualObject*>(v);
322  }
323  // bool isWorldElement = false;
324  if (auto v = dynamic_cast<WorldElementBase*>(o.second.get()); v)
325  {
326  // isWorldElement = true;
327  wrapperIdx = 3;
328  ipo.visual = dynamic_cast<VisualObject*>(v);
329  }
330 
331  if (wrapperIdx < 0) continue; // unknown / non-editable item.
332 
333  auto wrapper = wrappers[wrapperIdx];
334 
335  std::string label = name;
336  if (label.empty()) label = "(unnamed)";
337 
338  auto cb = wrapper->add<nanogui::CheckBox>(label);
339  ipo.cb = cb;
340  ipo.simulable = o.second;
341  gui_cbObjects.emplace_back(ipo);
342 
343  cb->setChecked(false);
344  cb->setCallback(
345  [cb, ipo, this](bool check)
346  {
347  // deselect former one:
348  if (gui_selectedObject.visual)
349  gui_selectedObject.visual->showCollisionShape(false);
350  if (gui_selectedObject.cb) gui_selectedObject.cb->setChecked(false);
351  gui_selectedObject = InfoPerObject();
352 
353  cb->setChecked(check);
354 
355  // If checked, show bounding box:
356  if (ipo.visual && check)
357  {
358  gui_selectedObject = ipo;
359  ipo.visual->showCollisionShape(true);
360  }
361 
362  const bool btnsEnabled = !!gui_selectedObject.simulable;
363  for (auto b : btns_selectedOps) b->setEnabled(btnsEnabled);
364 
365  // Set current coordinates in controls:
366  if (ipo.simulable && onEntitySelected)
367  onEntitySelected(ipo.simulable->getRelativePose());
368  });
369  }
370 
371  // "misc." tab
372  // --------------
373  wrappers[4]
374  ->add<nanogui::Button>("Save 3D scene...", ENTYPO_ICON_EXPORT)
375  ->setCallback(
376  [this]()
377  {
378  try
379  {
380  const std::string outFile = nanogui::file_dialog(
381  {{"3Dscene", "MRPT 3D scene file (*.3Dsceme)"}}, true /*save*/);
382  if (outFile.empty()) return;
383 
384  auto lck = mrpt::lockHelper(parent_.physical_objects_mtx());
385  parent_.worldPhysical_.saveToFile(outFile);
386 
387  std::cout << "[mvsim gui] Saved world scene to: " << outFile << std::endl;
388  }
389  catch (const std::exception& e)
390  {
391  std::cerr << "[mvsim gui] Exception while saving 3D scene:\n"
392  << e.what() << std::endl;
393  }
394  });
395  }
396 
397  w->add<nanogui::Label>(" ");
398 
399  // Replace with mouse:
400  btnReplaceObject = w->add<nanogui::Button>("Click to replace...");
401  btnReplaceObject->setFlags(nanogui::Button::Flags::ToggleButton);
402  btns_selectedOps.push_back(btnReplaceObject);
403 
404  // Reorient (yaw/pitch/roll):
405  constexpr float REPOSITION_SLIDER_RANGE = 1.0; // Meters
406 
407  nanogui::Slider* slidersCoordScale = nullptr;
408  nanogui::Label* slidersCoordScaleValue = nullptr;
409  {
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:");
414 
415  auto slCoord = pn->add<nanogui::Slider>();
416  slidersCoordScale = slCoord;
417 
418  slCoord->setRange({-4.0, 1.0});
419 
420  slCoord->setCallback(
421  [this]([[maybe_unused]] float v)
422  {
423  // Re-generate the other 6 sliders with this new scale:
424  if (!gui_selectedObject.simulable || !onEntitySelected) return;
425  onEntitySelected(gui_selectedObject.simulable->getRelativePose());
426  });
427  slCoord->setFixedWidth(slidersWidth - 30);
428  btns_selectedOps.push_back(slCoord);
429 
430  slidersCoordScaleValue = pn->add<nanogui::Label>(" ");
431  slidersCoordScaleValue->setFixedWidth(70);
432  }
433 
434  std::array<nanogui::Slider*, 6> slidersCoords;
435  std::array<nanogui::Label*, 6> slidersCoordsValues;
436  const std::array<const char*, 6> coordsNames = {
437  " Move 'x':", //
438  " Move 'y':", //
439  " Move 'z':", //
440  "Rotate yaw:", //
441  "Rotate pitch:", //
442  "Rotate roll:"};
443 
444  for (int axis = 0; axis < 6; axis++)
445  {
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]);
450 
451  auto slCoord = pn->add<nanogui::Slider>();
452  slidersCoords[axis] = slCoord;
453 
454  // Dummy. Correct ones set in onEntitySelected()
455  slCoord->setRange({-1.0, 1.0});
456 
457  slCoord->setCallback(
458  [this, axis](float v)
459  {
460  if (!gui_selectedObject.simulable) return;
461  auto p = gui_selectedObject.simulable->getRelativePose();
462  p[axis] = v;
463  gui_selectedObject.simulable->setRelativePose(p);
464  onEntityMoved(p);
465  });
466  slCoord->setFixedWidth(slidersWidth);
467  btns_selectedOps.push_back(slCoord);
468 
469  slidersCoordsValues[axis] = pn->add<nanogui::Label>("(...)");
470  slidersCoordsValues[axis]->setFixedWidth(COORDS_LABEL_WIDTH);
471  }
472 
473  // Now, we can define the lambda for filling in the current object pose in
474  // the GUI controls:
475  onEntitySelected =
476  [slidersCoords, slidersCoordScale, slidersCoordScaleValue](const mrpt::math::TPose3D p)
477  {
478  ASSERT_(slidersCoordScale);
479  const double scale = std::pow(10.0, mrpt::round(slidersCoordScale->value()));
480 
481  slidersCoordScaleValue->setCaption(mrpt::format("%.01e", scale));
482 
483  // Positions:
484  for (int i = 0; i < 3; i++)
485  {
486  slidersCoords[i]->setRange(
487  {p[i] - scale * REPOSITION_SLIDER_RANGE, p[i] + scale * REPOSITION_SLIDER_RANGE});
488  slidersCoords[i]->setValue(p[i]);
489  }
490  // Angles:
491  for (int i = 0; i < 3; i++)
492  {
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]);
495  }
496 
497  onEntityMoved(p);
498  };
499 
500  onEntityMoved = [slidersCoordsValues](const mrpt::math::TPose3D p)
501  {
502  // Positions:
503  for (int i = 0; i < 3; i++) slidersCoordsValues[i]->setCaption(mrpt::format("%.04f", p[i]));
504  // Angles:
505  for (int i = 0; i < 3; i++)
506  slidersCoordsValues[i + 3]->setCaption(
507  mrpt::format("%.02f deg", mrpt::RAD2DEG(p[i + 3])));
508  };
509 
510  // Replace with coordinates:
511  auto btnPlaceCoords = w->add<nanogui::Button>("Replace by coordinates...");
512  btns_selectedOps.push_back(btnPlaceCoords);
513  btnPlaceCoords->setCallback(
514  [this]()
515  {
516  //
517  if (!gui_selectedObject.simulable) return;
518 
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));
522 
523  nanogui::TextBox* lbs[6];
524 
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>();
537 
538  for (int i = 0; i < 6; i++)
539  {
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]+");
547  }
548 
549  const auto pos = gui_selectedObject.simulable->getRelativePose();
550  for (int i = 0; i < 3; i++) lbs[i]->setValue(std::to_string(pos[i]));
551 
552  for (int i = 3; i < 6; i++) lbs[i]->setValue(std::to_string(mrpt::RAD2DEG(pos[i])));
553 
554  formPose->add<nanogui::Label>("");
555  formPose->add<nanogui::Label>("");
556 
557  formPose->add<nanogui::Button>("Cancel")->setCallback([formPose]()
558  { formPose->dispose(); });
559 
560  formPose->add<nanogui::Button>("Accept")->setCallback(
561  [formPose, this, lbs]()
562  {
563  const mrpt::math::TPose3D newPose = {// X:
564  std::stod(lbs[0]->value()),
565  // Y:
566  std::stod(lbs[1]->value()),
567  // Z:
568  std::stod(lbs[2]->value()),
569  // Yaw
570  mrpt::DEG2RAD(std::stod(lbs[3]->value())),
571  // Pitch
572  mrpt::DEG2RAD(std::stod(lbs[4]->value())),
573  // Roll:
574  mrpt::DEG2RAD(std::stod(lbs[5]->value()))};
575 
576  gui_selectedObject.simulable->setRelativePose(newPose);
577  onEntitySelected(newPose);
578 
579  formPose->dispose();
580  });
581 
582  formPose->setModal(true);
583  formPose->center();
584  formPose->setVisible(true);
585  });
586 
587  // Disable all edit-controls since no object is selected:
588  for (auto b : btns_selectedOps) b->setEnabled(false);
589 
590  // Minimize subwindow:
591 #if MRPT_VERSION >= 0x231
592  gui_win->subwindowMinimize(subwinIdx);
593 #else
594  if (auto btnMinimize = dynamic_cast<nanogui::Button*>(w->buttonPanel()->children().at(0));
595  btnMinimize)
596  {
597  btnMinimize->callback()(); // "push" button
598  }
599 #endif
600 
601 } // end "editor" window
602 
604 {
605  try
606  {
607  MRPT_LOG_DEBUG("[World::internal_GUI_thread] Started.");
608 
609  // Start GUI:
610  nanogui::init();
611 
612  mrpt::gui::CDisplayWindowGUI_Params cp;
613  cp.maximized = guiOptions_.start_maximized;
614 
615  gui_.gui_win =
616  mrpt::gui::CDisplayWindowGUI::Create("mvsim", guiOptions_.win_w, guiOptions_.win_h, cp);
617 
618  // zmin / zmax of opengl viewport:
619  worldVisual_->getViewport()->setViewportClipDistances(
620  guiOptions_.clip_plane_min, guiOptions_.clip_plane_max);
621 
622  // Add a background scene:
623  {
624  // we use the member scene worldVisual_ as the placeholder for the
625  // visual 3D scene:
626 
627  // add the placeholders for user-provided objects, both for pure
628  // visualization only, and physical objects:
629  worldVisual_->insert(glUserObjsViz_);
630  worldPhysical_.insert(glUserObjsPhysical_);
631 
632  std::lock_guard<std::mutex> lck(gui_.gui_win->background_scene_mtx);
633  gui_.gui_win->background_scene = worldVisual_;
634  }
635 
636  // Only if the world is empty: at least introduce a ground grid:
637  if (worldElements_.empty())
638  {
639  auto we = WorldElementBase::factory(this, nullptr, "ground_grid");
640  worldElements_.push_back(we);
641  }
642 
643  // Windows:
644  gui_.prepare_control_window();
645  gui_.prepare_status_window();
646  gui_.prepare_editor_window();
647 
648  // Finish GUI setup:
649  gui_.gui_win->performLayout();
650  auto& cam = gui_.gui_win->camera();
651 
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);
657 
658  const auto p = this->worldRenderOffset() + guiOptions_.camera_point_to;
659  cam.setCameraPointing(p.x, p.y, p.z);
660 
661  const auto& lo = lightOptions_;
662 
663  setLightDirectionFromAzimuthElevation(lo.light_azimuth, lo.light_elevation);
664 
665 #if MRPT_VERSION >= 0x270
666  auto vv = worldVisual_->getViewport();
667  auto vp = worldPhysical_.getViewport();
668 
669  auto lambdaSetLightParams = [&lo](const mrpt::opengl::COpenGLViewport::Ptr& v)
670  {
671  // enable shadows and set the shadow map texture size:
672  const int sms = lo.shadow_map_size;
673  v->enableShadowCasting(lo.enable_shadows, sms, sms);
674 
675  // light color:
676  const auto colf = mrpt::img::TColorf(lo.light_color);
677 
678  auto& vlp = v->lightParameters();
679 
680  vlp.color = colf;
681 
682 #if MRPT_VERSION >= 0x2A0 // New in mrpt>=2.10.0
683  vlp.eyeDistance2lightShadowExtension = lo.eye_distance_to_shadow_map_extension;
684 
685  vlp.minimum_shadow_map_extension_ratio = lo.minimum_shadow_map_extension_ratio;
686 #endif
687  // light view frustrum near/far planes:
688  v->setLightShadowClipDistances(lo.light_clip_plane_min, lo.light_clip_plane_max);
689 
690  // Shadow bias should be proportional to clip range:
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;
695 #endif
696  };
697 
698  lambdaSetLightParams(vv);
699  lambdaSetLightParams(vp);
700 #endif
701 
702  // Main GUI loop
703  // ---------------------
704  gui_.gui_win->drawAll();
705  gui_.gui_win->setVisible(true);
706 
707  // Listen for keyboard events:
708 #if MRPT_VERSION >= 0x232
709  gui_.gui_win->addKeyboardCallback(
710 #else
711  gui_.gui_win->setKeyboardCallback(
712 #endif
713  [&](int key, int /*scancode*/, int action, int modifiers)
714  {
715  if (action != GLFW_PRESS && action != GLFW_REPEAT) return false;
716 
717  auto lck = mrpt::lockHelper(lastKeyEventMtx_);
718 
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;
724 
725  lastKeyEventValid_ = true;
726 
727  return false;
728  });
729 
730  gui_thread_running_ = true;
731 
732  // The GUI must be closed from this same thread. Use a shared atomic
733  // bool:
734  auto lambdaLoopCallback = [](World& me)
735  {
736  if (me.simulator_must_close()) nanogui::leave();
737 
738  try
739  {
740  // Update 3D vehicles, sensors, run render-based sensors, etc:
741  me.internalGraphicsLoopTasksForSimulation();
742 
743  me.internal_process_pending_gui_user_tasks();
744 
745  // handle mouse operations:
746  me.gui_.handle_mouse_operations();
747  }
748  catch (const std::exception& e)
749  {
750  // In case of an exception in the functions above,
751  // abort. Otherwise, the error may repeat over and over forever
752  // and the main thread will never know about it.
753  me.logStr(mrpt::system::LVL_ERROR, e.what());
754  me.simulator_must_close(true);
755  me.gui_.gui_win->setVisible(false);
756  nanogui::leave();
757  }
758  };
759 
760 #if MRPT_VERSION >= 0x232
761  gui_.gui_win->addLoopCallback(
762 #else
763  gui_.gui_win->setLoopCallback(
764 #endif
765  [=]() { lambdaLoopCallback(*this); });
766 
767  // Register observation callback:
768  const auto lambdaOnObservation =
769  [this](const Simulable& veh, const mrpt::obs::CObservation::Ptr& obs)
770  {
771  // obs->getDescriptionAsText(std::cout);
772  this->enqueue_task_to_run_in_gui_thread([this, obs, &veh]()
773  { internal_gui_on_observation(veh, obs); });
774  };
775 
776  this->registerCallbackOnObservation(lambdaOnObservation);
777 
778  // ============= Mainloop =============
779  const int refresh_ms = std::max(1, mrpt::round(1000 / guiOptions_.refresh_fps));
780 
781  MRPT_LOG_DEBUG_FMT(
782  "[World::internal_GUI_thread] Using GUI FPS=%i (T=%i ms)", guiOptions_.refresh_fps,
783  refresh_ms);
784 
785 #if MRPT_VERSION >= 0x253
786  const int idleLoopTasks_ms = 10;
787 
788  nanogui::mainloop(idleLoopTasks_ms, refresh_ms);
789 #else
790  nanogui::mainloop(refresh_ms);
791 #endif
792 
793  MRPT_LOG_DEBUG("[World::internal_GUI_thread] Mainloop ended.");
794 
795  // to let other threads know that we are closing:
796  simulator_must_close(true);
797 
798  // Make sure opengl resources are freed from this thread, not from
799  // the main one upon destruction of the last ref to shared_ptr's to
800  // opengl classes.
801  {
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();
805  }
806 
807  auto lckListObjs = mrpt::lockHelper(getListOfSimulableObjectsMtx());
808 
809  for (auto& obj : getListOfSimulableObjects()) obj.second->freeOpenGLResources();
810 
811  lckListObjs.unlock();
812 
814 
815  // Now, destroy window:
816  gui_.gui_win.reset();
817 
818  nanogui::shutdown();
819  }
820  catch (const std::exception& e)
821  {
822  MRPT_LOG_ERROR_STREAM("[internal_GUI_init] Exception: " << mrpt::exception_to_str(e));
823  }
824  gui_thread_running_ = false;
825 }
826 
827 void World::GUI::handle_mouse_operations()
828 {
829  MRPT_START
830  if (!gui_win) return;
831 
832  mrpt::opengl::COpenGLViewport::Ptr vp;
833  {
834  auto lck = mrpt::lockHelper(gui_win->background_scene_mtx);
835  if (!gui_win->background_scene) return;
836  vp = gui_win->background_scene->getViewport();
837  }
838  ASSERT_(vp);
839 
840  const auto mousePt = gui_win->mousePos();
841  mrpt::math::TLine3D ray;
842  vp->get3DRayForPixelCoord(mousePt.x(), mousePt.y(), ray);
843 
844  // Create a 3D plane, i.e. Z=0
845  const auto ground_plane = mrpt::math::TPlane::From3Points({0, 0, 0}, {1, 0, 0}, {0, 1, 0});
846 
847  // Intersection of the line with the plane:
848  mrpt::math::TObject3D inters;
849  mrpt::math::intersect(ray, ground_plane, inters);
850 
851  // Interpret the intersection as a point, if there is an
852  // intersection:
853  if (inters.getPoint(clickedPt))
854  {
855  // Apply world offset:
856  // P_GL = P_REAL + Off
857  // P_REAL = P_GL - Off
858  const auto dp = parent_.worldRenderOffset();
859  clickedPt.x -= dp.x;
860  clickedPt.y -= dp.y;
861  clickedPt.z -= dp.z;
862 
863  // Find out the "z": get first elevation if many exist.
864  const auto zs = parent_.getElevationsAt(mrpt::math::TPoint2Df(clickedPt.x, clickedPt.y));
865  if (!zs.empty()) clickedPt.z = *zs.begin();
866  }
867 
868  const auto screen = gui_win->screen();
869  const bool leftClick = screen->mouseState() == 0x01;
870 
871  // Replace object?
872  if (btnReplaceObject && btnReplaceObject->pushed())
873  {
874  static bool isReplacing = false;
875 
876  // Start of replace? When the button push is released:
877  if (!isReplacing && !leftClick)
878  {
879  isReplacing = true;
880  }
882  {
883  // btnReplaceObject->screen()->setCursor()
884 
885  mrpt::math::TPose3D p = gui_selectedObject.simulable->getPose();
886  p.x = clickedPt.x;
887  p.y = clickedPt.y;
888 
889  gui_selectedObject.simulable->setPose(p);
890  }
891  if (isReplacing && leftClick)
892  {
893  isReplacing = false;
894  btnReplaceObject->setPushed(false);
895  }
896  }
897 
898  MRPT_END
899 }
900 
902 {
904 
905  for (const auto& task : guiUserPendingTasks_)
906  {
907  task();
908  }
909  guiUserPendingTasks_.clear();
910 
911  guiUserPendingTasksMtx_.unlock();
912 }
913 
914 void World::internalRunSensorsOn3DScene(mrpt::opengl::COpenGLScene& physicalObjects)
915 {
916  auto tle = mrpt::system::CTimeLoggerEntry(timlogger_, "internalRunSensorsOn3DScene");
917 
918  for (auto& v : vehicles_)
919  for (auto& sensor : v.second->getSensors())
920  if (sensor) sensor->simulateOn3DScene(physicalObjects);
921 
922  // clear the flag of pending 3D simulation required:
924 }
925 
927  mrpt::opengl::COpenGLScene& viz, mrpt::opengl::COpenGLScene& physical)
928 {
929  // Update view of map elements
930  // -----------------------------
931  auto tle = mrpt::system::CTimeLoggerEntry(timlogger_, "update_GUI.2.map-elements");
932 
933  for (auto& e : worldElements_) e->guiUpdate(viz, physical);
934 
935  tle.stop();
936 
937  // Update view of vehicles
938  // -----------------------------
939  timlogger_.enter("update_GUI.3.vehicles");
940 
941  for (auto& v : vehicles_) v.second->guiUpdate(viz, physical);
942 
943  timlogger_.leave("update_GUI.3.vehicles");
944 
945  // Update view of blocks
946  // -----------------------------
947  timlogger_.enter("update_GUI.4.blocks");
948 
949  for (auto& v : blocks_) v.second->guiUpdate(viz, physical);
950 
951  timlogger_.leave("update_GUI.4.blocks");
952 
953  // Other messages
954  // -----------------------------
955  timlogger_.enter("update_GUI.5.text-msgs");
956  if (gui_.lbCpuUsage)
957  {
958  // 1st line: time
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"));
961 
962  gui_.lbCpuUsage->setCaption(mrpt::format(
963  "Time: %s (CPU usage: %.03f%%)",
964  mrpt::system::formatTimeInterval(get_simul_time()).c_str(), cpu_usage_ratio * 100.0));
965 
966  // User supplied-lines:
967  guiMsgLinesMtx_.lock();
968  const std::string msg_lines = guiMsgLines_;
969  guiMsgLinesMtx_.unlock();
970 
971  int nextStatusLine = 0;
972  if (!msg_lines.empty())
973  {
974  // split lines:
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);
978  }
979  gui_.lbStatuses.at(nextStatusLine++)
980  ->setCaption(std::string("Mouse: ") + gui_.clickedPt.asString());
981  }
982 
983  timlogger_.leave("update_GUI.5.text-msgs");
984 
985  // Camera follow modes:
986  // -----------------------
987  if (!guiOptions_.follow_vehicle.empty())
988  {
989  if (auto it = vehicles_.find(guiOptions_.follow_vehicle); it != vehicles_.end())
990  {
991  const auto pose = it->second->getCPose3D();
992  const auto p = applyWorldRenderOffset(pose);
993  gui_.gui_win->camera().setCameraPointing(p.x(), p.y(), p.z());
994  }
995  else
996  {
997  MRPT_LOG_THROTTLE_ERROR_FMT(
998  5.0,
999  "GUI: Camera set to follow vehicle named '%s' which can't be "
1000  "found!",
1001  guiOptions_.follow_vehicle.c_str());
1002  }
1003  }
1004 }
1005 
1007 {
1008  // First call?
1009  // -----------------------
1010  {
1011  auto lock = mrpt::lockHelper(gui_thread_start_mtx_);
1012  if (!gui_thread_running_ && !gui_thread_.joinable())
1013  {
1014  MRPT_LOG_DEBUG("[update_GUI] Launching GUI thread...");
1015 
1016  gui_thread_ = std::thread(&World::internal_GUI_thread, this);
1017 #if MRPT_VERSION >= 0x204
1018  mrpt::system::thread_name("guiThread", gui_thread_);
1019 #endif
1020 
1021  const int MVSIM_OPEN_GUI_TIMEOUT_MS =
1022  mrpt::get_env<int>("MVSIM_OPEN_GUI_TIMEOUT_MS", 3000);
1023 
1024  for (int timeout = 0; timeout < MVSIM_OPEN_GUI_TIMEOUT_MS / 10; timeout++)
1025  {
1026  std::this_thread::sleep_for(std::chrono::milliseconds(10));
1027  if (gui_thread_running_) break;
1028  }
1029 
1030  if (!gui_thread_running_)
1031  {
1032  THROW_EXCEPTION("Timeout waiting for GUI to open!");
1033  }
1034  else
1035  {
1036  MRPT_LOG_DEBUG("[update_GUI] GUI thread started.");
1037  }
1038  }
1039  }
1040 
1041  if (!gui_.gui_win)
1042  {
1043  MRPT_LOG_THROTTLE_WARN(
1044  5.0,
1045  "[World::update_GUI] GUI window has been closed, but note that "
1046  "simulation keeps running.");
1047  return;
1048  }
1049 
1050  timlogger_.enter("update_GUI"); // Don't count initialization, since that
1051  // is a total outlier and lacks interest!
1052 
1053  guiMsgLinesMtx_.lock();
1054  guiMsgLines_ = guiparams->msg_lines;
1055  guiMsgLinesMtx_.unlock();
1056 
1057  timlogger_.leave("update_GUI");
1058 
1059  // Key-strokes:
1060  // -----------------------
1061  if (guiparams && lastKeyEventValid_)
1062  {
1063  auto lck = mrpt::lockHelper(lastKeyEventMtx_);
1064 
1065  guiparams->keyevent = std::move(lastKeyEvent_);
1066  lastKeyEventValid_ = false;
1067  }
1068 }
1069 
1070 // This method is ensured to be run in the GUI thread
1072  const Simulable& veh, const mrpt::obs::CObservation::Ptr& obs)
1073 {
1074  if (!obs) return;
1075 
1076  if (auto obs3D = std::dynamic_pointer_cast<mrpt::obs::CObservation3DRangeScan>(obs); obs3D)
1077  {
1079  }
1080  else if (auto obsIm = std::dynamic_pointer_cast<mrpt::obs::CObservationImage>(obs); obsIm)
1081  {
1083  }
1084 }
1085 
1087  const Simulable& veh, const std::shared_ptr<mrpt::obs::CObservation3DRangeScan>& obs)
1088 {
1089  using namespace std::string_literals;
1090 
1091  if (!gui_.gui_win || !obs) return;
1092 
1093  mrpt::math::TPoint2D rgbImageWinSize = {0, 0};
1094 
1095  if (obs->hasIntensityImage)
1096  {
1097  rgbImageWinSize = internal_gui_on_image(
1098  veh.getName() + "/"s + obs->sensorLabel + "_rgb"s, obs->intensityImage, 5);
1099  }
1100  if (obs->hasRangeImage)
1101  {
1102  mrpt::math::CMatrixFloat d;
1103  d = obs->rangeImage.asEigen().cast<float>() * (obs->rangeUnits / obs->maxRange);
1104 
1105  mrpt::img::CImage imDepth;
1106  imDepth.setFromMatrix(d, true /* in range [0,1] */);
1107 
1109  veh.getName() + "/"s + obs->sensorLabel + "_depth"s, imDepth,
1110  5 + 5 + rgbImageWinSize.x);
1111  }
1112 }
1113 
1115  const Simulable& veh, const std::shared_ptr<mrpt::obs::CObservationImage>& obs)
1116 {
1117  using namespace std::string_literals;
1118 
1119  if (!gui_.gui_win || !obs || obs->image.isEmpty()) return;
1120 
1121  mrpt::math::TPoint2D rgbImageWinSize = {0, 0};
1122 
1123  rgbImageWinSize =
1124  internal_gui_on_image(veh.getName() + "/"s + obs->sensorLabel + "_rgb"s, obs->image, 5);
1125 }
1126 
1127 mrpt::math::TPoint2D World::internal_gui_on_image(
1128  const std::string& label, const mrpt::img::CImage& im, int winPosX)
1129 {
1130  mrpt::gui::MRPT2NanoguiGLCanvas* glControl;
1131 
1132  // Once creation:
1133  if (!guiObsViz_.count(label))
1134  {
1135  auto& w = guiObsViz_[label] = gui_.gui_win->createManagedSubWindow(label);
1136 
1137  w->setLayout(new nanogui::GridLayout(
1138  nanogui::Orientation::Vertical, 1, nanogui::Alignment::Fill, 2, 2));
1139 
1140  // Guess window size:
1141  int winW = im.getWidth(), winH = im.getHeight();
1142 
1143  // Guess if we need to decimate subwindow size:
1144  while (winW >= 512 || winH >= 512)
1145  {
1146  winW /= 2;
1147  winH /= 2;
1148  }
1149 
1150  glControl = w->add<mrpt::gui::MRPT2NanoguiGLCanvas>();
1151  glControl->setSize({winW, winH});
1152  glControl->setFixedSize({winW, winH});
1153 
1154  static std::map<int, int> numGuiWindows;
1155  w->setPosition({winPosX, 20 + (numGuiWindows[winPosX]++) * (winH + 10)});
1156 
1157  auto lck = mrpt::lockHelper(glControl->scene_mtx);
1158 
1159  glControl->scene = mrpt::opengl::COpenGLScene::Create();
1160  gui_.gui_win->performLayout();
1161  }
1162 
1163  // Update from sensor data:
1164  auto& w = guiObsViz_[label];
1165 
1166  glControl = dynamic_cast<mrpt::gui::MRPT2NanoguiGLCanvas*>(w->children().at(1));
1167  ASSERT_(glControl != nullptr);
1168 
1169  auto lck = mrpt::lockHelper(glControl->scene_mtx);
1170  glControl->scene->getViewport()->setImageView(im);
1171 
1172  return mrpt::math::TPoint2D(w->size().x(), w->size().y());
1173 }
1174 
1176 {
1177  try
1178  {
1179  // Update all GUI elements:
1180  ASSERT_(worldVisual_);
1181 
1182  auto lckPhys = mrpt::lockHelper(physical_objects_mtx());
1183 
1185 
1187 
1188  lckPhys.unlock();
1189 
1190  // handle user custom 3D visual objects:
1191  {
1192  const auto lck = mrpt::lockHelper(guiUserObjectsMtx_);
1193  // replace list of smart pointers (fast):
1196  }
1197  }
1198  catch (const std::exception& e)
1199  {
1200  // In case of an exception in the functions above,
1201  // abort. Otherwise, the error may repeat over and over forever
1202  // and the main thread will never know about it.
1203  MRPT_LOG_ERROR(e.what());
1204  simulator_must_close(true);
1205  }
1206 }
1207 
1208 void World::setLightDirectionFromAzimuthElevation(const float azimuth, const float elevation)
1209 {
1210  const mrpt::math::TPoint3Df dir = {
1211  -cos(azimuth) * cos(elevation), -sin(azimuth) * cos(elevation), -sin(elevation)};
1212 
1213  ASSERT_(worldVisual_);
1214 
1215  auto lckPhys = mrpt::lockHelper(physical_objects_mtx());
1216 
1217  auto vv = worldVisual_->getViewport();
1218  auto vp = worldPhysical_.getViewport();
1219 
1220  vv->lightParameters().direction = dir;
1221  vp->lightParameters().direction = dir;
1222 }
mvsim::World::TGUI_Options::follow_vehicle
std::string follow_vehicle
Vehicle name to follow (empty=none)
Definition: World.h:515
check
ROSCPP_DECL bool check()
mvsim
Definition: Client.h:21
mvsim::World::worldVisual_
mrpt::opengl::COpenGLScene::Ptr worldVisual_
Definition: World.h:767
mvsim::World::TGUI_Options::parse_from
void parse_from(const rapidxml::xml_node< char > &node, COutputLogger &logger)
Definition: World_gui.cpp:34
mvsim::Simulable::getName
const std::string & getName() const
Definition: Simulable.h:107
mvsim::World::setLightDirectionFromAzimuthElevation
void setLightDirectionFromAzimuthElevation(const float azimuth, const float elevation)
Definition: World_gui.cpp:1208
mvsim::World::internalGraphicsLoopTasksForSimulation
void internalGraphicsLoopTasksForSimulation()
Definition: World_gui.cpp:1175
mvsim::World::GUI::gui_selectedObject
InfoPerObject gui_selectedObject
Definition: World.h:749
mvsim::World::internalUpdate3DSceneObjects
void internalUpdate3DSceneObjects(mrpt::opengl::COpenGLScene &viz, mrpt::opengl::COpenGLScene &physical)
Definition: World_gui.cpp:926
mvsim::World::lastKeyEventValid_
std::atomic_bool lastKeyEventValid_
Definition: World.h:277
mvsim::World::GUI::prepare_editor_window
void prepare_editor_window()
Definition: World_gui.cpp:215
ImGui::Button
IMGUI_API bool Button(const char *label, const ImVec2 &size=ImVec2(0, 0))
Definition: imgui_widgets.cpp:575
mvsim::World::is_GUI_open
bool is_GUI_open() const
s
XmlRpcServer s
mvsim::World::internal_GUI_thread
void internal_GUI_thread()
Definition: World_gui.cpp:603
mvsim::parse_xmlnode_children_as_param
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const TParameterDefinitions &params, const std::map< std::string, std::string > &variableNamesValues={}, const char *functionNameContext="", mrpt::system::COutputLogger *logger=nullptr)
Definition: xml_utils.cpp:215
mvsim::VisualObject::FreeOpenGLResources
static void FreeOpenGLResources()
Definition: VisualObject.cpp:153
mvsim::World::guiOptions_
TGUI_Options guiOptions_
Definition: World.h:544
mvsim::World::GUI::lbCpuUsage
nanogui::Label * lbCpuUsage
Definition: World.h:735
mvsim::World::applyWorldRenderOffset
mrpt::math::TPose3D applyWorldRenderOffset(mrpt::math::TPose3D p) const
Definition: World.h:631
World.h
mvsim::World::physical_objects_mtx
auto & physical_objects_mtx()
Definition: World.h:383
mvsim::World::internal_process_pending_gui_user_tasks
void internal_process_pending_gui_user_tasks()
Definition: World_gui.cpp:901
mvsim::SensorBase
Virtual base class for all sensors.
Definition: SensorBase.h:34
simple-obstacle-avoidance.action
action
Definition: simple-obstacle-avoidance.py:35
mvsim::World::worldRenderOffset
mrpt::math::TVector3D worldRenderOffset() const
(See docs for worldRenderOffset_)
Definition: World.h:627
mvsim::World::GUI::InfoPerObject::visual
VisualObject * visual
Definition: World.h:743
mvsim::World::internal_gui_on_observation
void internal_gui_on_observation(const Simulable &veh, const mrpt::obs::CObservation::Ptr &obs)
Definition: World_gui.cpp:1071
mvsim::SensorBase::GetAllSensorsOriginViz
static std::shared_ptr< mrpt::opengl::CSetOfObjects > GetAllSensorsOriginViz()
Definition: SensorBase.cpp:61
mvsim::WorldElementBase::factory
static Ptr factory(World *parent, const rapidxml::xml_node< char > *xml_node, const char *class_name=nullptr)
Definition: WorldElementBase.cpp:49
xml_utils.h
mvsim::World::TUpdateGUIParams::msg_lines
std::string msg_lines
Messages to show.
Definition: World.h:182
mvsim::World::LightOptions::parse_from
void parse_from(const rapidxml::xml_node< char > &node, COutputLogger &logger)
mvsim::World::guiMsgLinesMtx_
std::mutex guiMsgLinesMtx_
Definition: World.h:244
mvsim::World::GUI::gui_win
mrpt::gui::CDisplayWindowGUI::Ptr gui_win
Definition: World.h:734
mvsim::World::internal_gui_on_observation_image
void internal_gui_on_observation_image(const Simulable &veh, const std::shared_ptr< mrpt::obs::CObservationImage > &obs)
Definition: World_gui.cpp:1114
mvsim::World::guiMsgLines_
std::string guiMsgLines_
Definition: World.h:243
mvsim::World::guiUserObjectsPhysical_
mrpt::opengl::CSetOfObjects::Ptr guiUserObjectsPhysical_
Definition: World.h:205
void
typedef void(GLAD_API_PTR *GLDEBUGPROC)(GLenum source
mvsim::World::gui_thread_
std::thread gui_thread_
Definition: World.h:246
mvsim::VisualObject::showCollisionShape
void showCollisionShape(bool show)
Definition: VisualObject.cpp:244
mvsim::World::GUI::InfoPerObject::simulable
Simulable::Ptr simulable
Definition: World.h:742
mvsim::World::get_simul_time
double get_simul_time() const
Definition: World.h:119
mvsim::World::TUpdateGUIParams
Definition: World.h:179
d
d
mvsim::World::TUpdateGUIParams::keyevent
TGUIKeyEvent keyevent
Keystrokes in the window are returned here.
Definition: World.h:181
mvsim::World::GUI::InfoPerObject::cb
nanogui::CheckBox * cb
Definition: World.h:741
mvsim::World::guiUserObjectsMtx_
std::mutex guiUserObjectsMtx_
Definition: World.h:206
mvsim::World::blocks_
BlockList blocks_
Definition: World.h:669
mvsim::Block
Definition: Block.h:50
mvsim::World::vehicles_
VehicleList vehicles_
Definition: World.h:667
mvsim::World::gui_thread_start_mtx_
std::mutex gui_thread_start_mtx_
Definition: World.h:250
mvsim::World::GUI::prepare_status_window
void prepare_status_window()
Definition: World_gui.cpp:191
mvsim::World::lastKeyEvent_
TGUIKeyEvent lastKeyEvent_
Definition: World.h:276
mvsim::World
Definition: World.h:82
mvsim::World::guiObsViz_
std::map< std::string, nanogui::Window * > guiObsViz_
by sensorLabel
Definition: World.h:802
mvsim::World::guiUserPendingTasks_
std::vector< std::function< void(void)> > guiUserPendingTasks_
Definition: World.h:273
mvsim::SensorBase::GetAllSensorsFOVViz
static std::shared_ptr< mrpt::opengl::CSetOfObjects > GetAllSensorsFOVViz()
Definition: SensorBase.cpp:67
mvsim::VehicleBase
Definition: VehicleBase.h:44
rapidxml::xml_node< char >
mvsim::World::worldPhysical_
mrpt::opengl::COpenGLScene worldPhysical_
Definition: World.h:774
mvsim::World::update_GUI
void update_GUI(TUpdateGUIParams *params=nullptr)
Definition: World_gui.cpp:1006
mvsim::World::worldElements_
WorldElementList worldElements_
Definition: World.h:668
mvsim::World::GUI::prepare_control_window
void prepare_control_window()
Definition: World_gui.cpp:53
mvsim::Simulable
Definition: Simulable.h:39
std
mvsim::World::GUI::clickedPt
mrpt::math::TPoint3D clickedPt
Definition: World.h:751
mvsim::World::getElevationsAt
std::set< float > getElevationsAt(const mrpt::math::TPoint2D &worldXY) const
Definition: World.cpp:275
mvsim::World::GUI::parent_
World & parent_
Definition: World.h:760
mvsim::World::internalRunSensorsOn3DScene
void internalRunSensorsOn3DScene(mrpt::opengl::COpenGLScene &physicalObjects)
Definition: World_gui.cpp:914
mvsim::World::GUI::btnReplaceObject
nanogui::Button * btnReplaceObject
Definition: World.h:737
mvsim::World::SimulableList
std::multimap< std::string, Simulable::Ptr > SimulableList
Definition: World.h:301
mvsim::World::guiUserPendingTasksMtx_
std::mutex guiUserPendingTasksMtx_
Definition: World.h:274
mvsim::World::guiUserObjectsViz_
mrpt::opengl::CSetOfObjects::Ptr guiUserObjectsViz_
Definition: World.h:205
mvsim::World::close_GUI
void close_GUI()
a previous call to update_GUI()
Definition: World_gui.cpp:50
mvsim::World::GUI::lbStatuses
std::vector< nanogui::Label * > lbStatuses
Definition: World.h:736
mvsim::World::gui_thread_running_
std::atomic_bool gui_thread_running_
Definition: World.h:248
mvsim::World::glUserObjsPhysical_
mrpt::opengl::CSetOfObjects::Ptr glUserObjsPhysical_
Definition: World.h:495
mvsim::World::internal_gui_on_image
mrpt::math::TPoint2D internal_gui_on_image(const std::string &label, const mrpt::img::CImage &im, int winPosX)
Definition: World_gui.cpp:1127
mvsim::World::GUI::InfoPerObject
Definition: World.h:739
mvsim::World::timlogger_
mrpt::system::CTimeLogger timlogger_
Definition: World.h:810
rapidxml.hpp
mvsim::World::clear_pending_running_sensors_on_3D_scene
void clear_pending_running_sensors_on_3D_scene()
Definition: World.h:229
mvsim::World::glUserObjsViz_
mrpt::opengl::CSetOfObjects::Ptr glUserObjsViz_
Definition: World.h:496
mvsim::World::simulator_must_close
bool simulator_must_close() const
Definition: World.h:252
mvsim::VisualObject
Definition: VisualObject.h:35
mvsim::WorldElementBase
Definition: WorldElementBase.h:27
t
geometry_msgs::TransformStamped t
mvsim::World::gui_
GUI gui_
gui state
Definition: World.h:762
mvsim::World::internal_gui_on_observation_3Dscan
void internal_gui_on_observation_3Dscan(const Simulable &veh, const std::shared_ptr< mrpt::obs::CObservation3DRangeScan > &obs)
Definition: World_gui.cpp:1086
mvsim::World::lastKeyEventMtx_
std::mutex lastKeyEventMtx_
Definition: World.h:278


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:08