MVSim
Lightweight simulator for 2.5D vehicles and robots
World.h
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2026 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 #pragma once
11 
12 #include <box2d/b2_body.h>
13 #include <box2d/b2_distance_joint.h>
14 #include <box2d/b2_revolute_joint.h>
15 #include <box2d/b2_world.h>
16 #include <mrpt/core/bits_math.h>
17 #include <mrpt/core/format.h>
18 #include <mrpt/gui/CDisplayWindowGUI.h>
19 #include <mrpt/img/CImage.h>
20 #include <mrpt/img/TColor.h>
21 #include <mrpt/math/TPoint3D.h>
22 #include <mrpt/obs/CObservation.h>
23 #include <mrpt/obs/CObservationImage.h>
24 #include <mrpt/obs/obs_frwds.h>
25 #include <mrpt/system/COutputLogger.h>
26 #include <mrpt/system/CTicTac.h>
27 #include <mrpt/system/CTimeLogger.h>
28 #include <mrpt/topography/data_types.h>
29 #include <mvsim/Block.h>
30 #include <mvsim/HumanActor.h>
31 #include <mvsim/Joystick.h>
32 #include <mvsim/RemoteResourcesManager.h>
33 #include <mvsim/TParameterDefinitions.h>
34 #include <mvsim/VehicleBase.h>
35 #include <mvsim/WorldElements/WorldElementBase.h>
36 
37 //
38 #include <mrpt/version.h>
39 #if MRPT_VERSION >= 0x020f07
40 #include <mrpt/io/CCompressedOutputStream.h>
41 #else
42 #include <mrpt/io/CFileGZOutputStream.h>
43 #endif
44 
45 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
46 #include <mvsim/Comms/Client.h>
47 #endif
48 
49 #include <any>
50 #include <functional>
51 #include <list>
52 #include <map>
53 #include <set>
54 #include <unordered_map>
55 
56 #if MVSIM_HAS_ZMQ && MVSIM_HAS_PROTOBUF
57 // forward declarations:
58 namespace mvsim_msgs
59 {
60 class SrvGetPose;
61 class SrvGetPoseAnswer;
62 class SrvSetPose;
63 class SrvSetPoseAnswer;
64 class SrvSetControllerTwist;
65 class SrvSetControllerTwistAnswer;
66 class SrvShutdown;
67 class SrvShutdownAnswer;
68 } // namespace mvsim_msgs
69 #endif
70 
71 namespace mvsim
72 {
89 struct WorldJoint
90 {
91  enum class Type : uint8_t
92  {
93  Distance = 0,
94  Revolute
95  };
96 
97  Type type = Type::Distance;
98 
100  std::string bodyA_name;
101  std::string bodyB_name;
102 
104  mrpt::math::TPoint2D anchorA{0, 0};
105  mrpt::math::TPoint2D anchorB{0, 0};
106 
108  float maxLength = 5.0f;
109  float minLength = 0.0f;
110  float stiffness = 0.0f;
111  float damping = 0.0f;
112 
114  bool enableLimit = false;
115  float lowerAngle_deg = 0.0f;
116  float upperAngle_deg = 0.0f;
117 
119  b2Joint* b2joint = nullptr;
120 };
121 
131 class World : public mrpt::system::COutputLogger
132 {
133  public:
136  World();
137  ~World();
138 
139  // Rule of Five: explicitly delete copy operations, allow move operations
140  World(const World&) = delete;
141  World& operator=(const World&) = delete;
142  World(World&&) = delete;
143  World& operator=(World&&) = delete;
144 
147  void clear_all();
148 
155  void load_from_XML_file(const std::string& xmlFileNamePath);
156 
157  void internal_initialize();
158 
167  const std::string& xml_text, const std::string& fileNameForPath = std::string("."));
174  double get_simul_time() const
175  {
176  auto lck = mrpt::lockHelper(simul_time_mtx_);
177  return simulTime_;
178  }
179 
181  void force_set_simul_time(double newSimulatedTime)
182  {
183  auto lck = mrpt::lockHelper(simul_time_mtx_);
184  simulTime_ = newSimulatedTime;
185  }
186 
192  mrpt::Clock::time_point get_simul_timestamp() const
193  {
194  auto lck = mrpt::lockHelper(simul_time_mtx_);
195  ASSERT_(simul_start_wallclock_time_.has_value());
196  return mrpt::Clock::fromDouble(simulTime_ + simul_start_wallclock_time_.value());
197  }
198 
200  double get_simul_timestep() const;
201 
205  void set_simul_timestep(double timestep) { simulTimestep_ = timestep; }
206 
209  double get_gravity() const { return gravity_; }
210 
213  void set_gravity(double accel) { gravity_ = accel; }
214 
220  void run_simulation(double dt);
221 
222  void insert_vehicle(const VehicleBase::Ptr& veh);
223 
225  struct GUIKeyEvent
226  {
227  int keycode = 0;
228  bool modifierShift = false;
229  bool modifierCtrl = false;
230  bool modifierAlt = false;
231  bool modifierSuper = false;
232 
233  GUIKeyEvent() = default;
234  };
235 
237  {
239  std::string msg_lines;
240 
241  TUpdateGUIParams() = default;
242  };
243 
251  void update_GUI(TUpdateGUIParams* params = nullptr);
252 
253  const mrpt::gui::CDisplayWindowGUI::Ptr& gui_window() const { return gui_.gui_win; }
254 
255  const mrpt::math::TPoint3D& gui_mouse_point() const { return gui_.clickedPt; }
256 
262  mrpt::opengl::CSetOfObjects::Ptr guiUserObjectsPhysical_, guiUserObjectsViz_;
263  std::mutex guiUserObjectsMtx_;
264 
269 
270  void internalRunSensorsOn3DScene(mrpt::opengl::COpenGLScene& physicalObjects);
271 
272  void internalUpdate3DSceneObjects(
273  mrpt::opengl::COpenGLScene& viz, mrpt::opengl::COpenGLScene& physical);
274  void internal_GUI_thread();
275  void internal_process_pending_gui_user_tasks();
276 
277  std::mutex pendingRunSensorsOn3DSceneMtx_;
278  bool pendingRunSensorsOn3DScene_ = false;
279 
280  void mark_as_pending_running_sensors_on_3D_scene()
281  {
282  pendingRunSensorsOn3DSceneMtx_.lock();
283  pendingRunSensorsOn3DScene_ = true;
284  pendingRunSensorsOn3DSceneMtx_.unlock();
285  }
286  void clear_pending_running_sensors_on_3D_scene()
287  {
288  pendingRunSensorsOn3DSceneMtx_.lock();
289  pendingRunSensorsOn3DScene_ = false;
290  pendingRunSensorsOn3DSceneMtx_.unlock();
291  }
292  bool pending_running_sensors_on_3D_scene()
293  {
294  pendingRunSensorsOn3DSceneMtx_.lock();
295  bool ret = pendingRunSensorsOn3DScene_;
296  pendingRunSensorsOn3DSceneMtx_.unlock();
297  return ret;
298  }
299 
300  std::string guiMsgLines_;
301  std::mutex guiMsgLinesMtx_;
302 
303  std::thread gui_thread_;
304 
305  std::atomic_bool gui_thread_running_ = false;
306  std::atomic_bool simulator_must_close_ = false;
307  mutable std::mutex gui_thread_start_mtx_;
308 
309  bool simulator_must_close() const
310  {
311  gui_thread_start_mtx_.lock();
312  const bool v = simulator_must_close_;
313  gui_thread_start_mtx_.unlock();
314  return v;
315  }
316  void simulator_must_close(bool value)
317  {
318  gui_thread_start_mtx_.lock();
319  simulator_must_close_ = value;
320  gui_thread_start_mtx_.unlock();
321  }
322 
323  void enqueue_task_to_run_in_gui_thread(const std::function<void(void)>& f)
324  {
325  guiUserPendingTasksMtx_.lock();
326  guiUserPendingTasks_.emplace_back(f);
327  guiUserPendingTasksMtx_.unlock();
328  }
329 
330  std::vector<std::function<void(void)>> guiUserPendingTasks_;
331  std::mutex guiUserPendingTasksMtx_;
332 
333  GUIKeyEvent lastKeyEvent_;
334  std::atomic_bool lastKeyEventValid_ = false;
335  std::mutex lastKeyEventMtx_;
336 
337  bool is_GUI_open() const;
339 
340  void close_GUI();
341 
348  using VehicleList = std::multimap<std::string, VehicleBase::Ptr>;
349 
351  using WorldElementList = std::list<WorldElementBase::Ptr>;
352 
354  using BlockList = std::multimap<std::string, Block::Ptr>;
355 
358  using SimulableList = std::multimap<std::string, Simulable::Ptr>;
359 
361  using ActorList = std::multimap<std::string, HumanActor::Ptr>;
362 
367  std::unique_ptr<b2World>& getBox2DWorld() { return box2d_world_; }
368  const std::unique_ptr<b2World>& getBox2DWorld() const { return box2d_world_; }
369  b2Body* getBox2DGroundBody() { return b2_ground_body_; }
370  const VehicleList& getListOfVehicles() const { return vehicles_; }
371  VehicleList& getListOfVehicles() { return vehicles_; }
372  const BlockList& getListOfBlocks() const { return blocks_; }
373  BlockList& getListOfBlocks() { return blocks_; }
374  const WorldElementList& getListOfWorldElements() const { return worldElements_; }
375 
376  const std::vector<WorldJoint>& getListOfJoints() const { return joints_; }
377 
378  const ActorList& getListOfActors() const { return actors_; }
379  ActorList& getListOfActors() { return actors_; }
380 
382  SimulableList& getListOfSimulableObjects() { return simulableObjects_; }
383  const SimulableList& getListOfSimulableObjects() const { return simulableObjects_; }
384  auto& getListOfSimulableObjectsMtx() { return simulableObjectsMtx_; }
385 
386  mrpt::system::CTimeLogger& getTimeLogger() { return timlogger_; }
387 
391  std::string local_to_abs_path(const std::string& in_path) const;
392 
399  std::string xmlPathToActualPath(const std::string& modelURI) const;
400 
406  using vehicle_visitor_t = std::function<void(VehicleBase&)>;
407  using world_element_visitor_t = std::function<void(WorldElementBase&)>;
408  using block_visitor_t = std::function<void(Block&)>;
409 
411  void runVisitorOnVehicles(const vehicle_visitor_t& v);
412 
414  void runVisitorOnWorldElements(const world_element_visitor_t& v);
415 
417  void runVisitorOnBlocks(const block_visitor_t& v);
418 
424  using on_observation_callback_t =
425  std::function<void(const Simulable& /*veh*/, const mrpt::obs::CObservation::Ptr& /*obs*/)>;
426 
427  void registerCallbackOnObservation(const on_observation_callback_t& f)
428  {
429  callbacksOnObservation_.emplace_back(f);
430  }
431 
433  void dispatchOnObservation(const Simulable& veh, const mrpt::obs::CObservation::Ptr& obs);
434 
440 
441 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
442  mvsim::Client& commsClient() { return client_; }
443  const mvsim::Client& commsClient() const { return client_; }
444 #endif
445 
446  void free_opengl_resources();
447 
448  auto& physical_objects_mtx() { return worldPhysicalMtx_; }
449 
450  bool headless() const { return guiOptions_.headless; }
451  void headless(bool setHeadless) { guiOptions_.headless = setHeadless; }
452 
453  bool sensor_has_to_create_egl_context();
454 
455  const std::map<std::string, std::string>& user_defined_variables() const
456  {
457  return userDefinedVariables_;
458  }
459 
464  std::optional<mvsim::TJoyStickEvent> getJoystickState() const;
465 
466  bool evaluate_tag_if(const rapidxml::xml_node<char>& node) const;
467 
468  float collisionThreshold() const { return collisionThreshold_; }
469 
475  std::set<float> getElevationsAt(const mrpt::math::TPoint2D& worldXY) const;
476 
479  float getHighestElevationUnder(const mrpt::math::TPoint3Df& queryPt) const;
480 
481  void internal_simul_pre_step_terrain_elevation();
482 
487  std::optional<std::any> getPropertyAt(
488  const std::string& propertyName, const mrpt::math::TPoint3D& worldXYZ) const;
489 
490  private:
491  friend class VehicleBase;
492  friend class Block;
493 
494 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
495  mvsim::Client client_{"World"};
496 #endif
497 
498  std::vector<on_observation_callback_t> callbacksOnObservation_;
499 
500  // -------- World Params ----------
503  double gravity_ = 9.81;
504 
509  mutable double simulTimestep_ = 0;
510 
511  mutable bool joystickEnabled_ = false;
512  mutable std::optional<Joystick> joystick_;
513 
515  int b2dVelIters_ = 8, b2dPosIters_ = 3;
516 
518  float collisionThreshold_ = 0.03f;
519 
520  std::string serverAddress_ = "localhost";
521 
523  std::string save_to_rawlog_;
524 
525  double rawlog_odometry_rate_ = 10.0;
526 
529  std::string save_ground_truth_trajectory_;
530 
531  double ground_truth_rate_ = 50.0;
532 
533  double max_slope_to_collide_ = 0.30;
534  double min_slope_to_collide_ = -0.50;
535 
536  const TParameterDefinitions otherWorldParams_ = {
537  {"server_address", {"%s", &serverAddress_}},
538  {"gravity", {"%lf", &gravity_}},
539  {"simul_timestep", {"%lf", &simulTimestep_}},
540  {"b2d_vel_iters", {"%i", &b2dVelIters_}},
541  {"b2d_pos_iters", {"%i", &b2dPosIters_}},
542  {"collision_threshold", {"%f", &collisionThreshold_}},
543  {"joystick_enabled", {"%bool", &joystickEnabled_}},
544  {"save_to_rawlog", {"%s", &save_to_rawlog_}},
545  {"rawlog_odometry_rate", {"%lf", &rawlog_odometry_rate_}},
546  {"save_ground_truth_trajectory", {"%s", &save_ground_truth_trajectory_}},
547  {"ground_truth_rate", {"%lf", &ground_truth_rate_}},
548  {"max_slope_to_collide", {"%lf", &max_slope_to_collide_}},
549  {"min_slope_to_collide", {"%lf", &min_slope_to_collide_}},
550  };
551 
554  std::map<std::string, std::string> userDefinedVariables_;
555 
558  double simulTime_ = 0;
559  std::optional<double> simul_start_wallclock_time_;
560  std::mutex simul_time_mtx_;
561 
563  std::string basePath_{"."};
564 
567  mrpt::opengl::CSetOfObjects::Ptr glUserObjsPhysical_ = mrpt::opengl::CSetOfObjects::Create();
568  mrpt::opengl::CSetOfObjects::Ptr glUserObjsViz_ = mrpt::opengl::CSetOfObjects::Create();
569 
570  // ------- GUI options -----
571  struct TGUI_Options
572  {
573  unsigned int win_w = 800, win_h = 600;
574  bool start_maximized = true;
575  int refresh_fps = 20;
576  bool ortho = false;
577  bool show_forces = false;
578  bool show_sensor_points = true;
579  double force_scale = 0.01;
580  double camera_distance = 80.0;
581  double camera_azimuth_deg = 45.0;
582  double camera_elevation_deg = 40.0;
583  double fov_deg = 60.0;
584  float clip_plane_min = 0.05f;
585  float clip_plane_max = 10e3f;
586  mrpt::math::TPoint3D camera_point_to{0, 0, 0};
587  std::string follow_vehicle;
588  bool headless = false;
589 
590  const TParameterDefinitions params = {
591  {"win_w", {"%u", &win_w}},
592  {"win_h", {"%u", &win_h}},
593  {"ortho", {"%bool", &ortho}},
594  {"show_forces", {"%bool", &show_forces}},
595  {"show_sensor_points", {"%bool", &show_sensor_points}},
596  {"force_scale", {"%lf", &force_scale}},
597  {"fov_deg", {"%lf", &fov_deg}},
598  {"follow_vehicle", {"%s", &follow_vehicle}},
599  {"start_maximized", {"%bool", &start_maximized}},
600  {"refresh_fps", {"%i", &refresh_fps}},
601  {"headless", {"%bool", &headless}},
602  {"clip_plane_min", {"%f", &clip_plane_min}},
603  {"clip_plane_max", {"%f", &clip_plane_max}},
604  {"cam_distance", {"%lf", &camera_distance}},
605  {"cam_azimuth", {"%lf", &camera_azimuth_deg}},
606  {"cam_elevation", {"%lf", &camera_elevation_deg}},
607  {"cam_point_to", {"%point3d", &camera_point_to}},
608  };
609 
610  TGUI_Options() = default;
611  void parse_from(const rapidxml::xml_node<char>& node, COutputLogger& logger);
612  };
613 
616  TGUI_Options guiOptions_;
617 
618  struct LightOptions
619  {
620  LightOptions() = default;
621 
622  void parse_from(const rapidxml::xml_node<char>& node, COutputLogger& logger);
623 
624  bool enable_shadows = true;
625  int shadow_map_size = 2048;
626 
627  double light_azimuth = mrpt::DEG2RAD(45.0);
628  double light_elevation = mrpt::DEG2RAD(70.0);
629 
630  float light_clip_plane_min = 0.1f;
631  float light_clip_plane_max = 900.0f;
632 
633  float shadow_bias = 1e-5;
634  float shadow_bias_cam2frag = 1e-5;
635  float shadow_bias_normal = 1e-4;
636 
637  mrpt::img::TColor light_color = {0xff, 0xff, 0xff, 0xff};
638  float light_ambient = 0.5f;
639 
640  float eye_distance_to_shadow_map_extension = 2.0f;
641  float minimum_shadow_map_extension_ratio = 0.005f;
642 
643  const TParameterDefinitions params = {
644  {"enable_shadows", {"%bool", &enable_shadows}},
645  {"shadow_map_size", {"%i", &shadow_map_size}},
646  {"light_azimuth_deg", {"%lf_deg", &light_azimuth}},
647  {"light_elevation_deg", {"%lf_deg", &light_elevation}},
648  {"light_clip_plane_min", {"%f", &light_clip_plane_min}},
649  {"light_clip_plane_max", {"%f", &light_clip_plane_max}},
650  {"light_color", {"%color", &light_color}},
651  {"shadow_bias", {"%f", &shadow_bias}},
652  {"shadow_bias_cam2frag", {"%f", &shadow_bias_cam2frag}},
653  {"shadow_bias_normal", {"%f", &shadow_bias_normal}},
654  {"light_ambient", {"%f", &light_ambient}},
655  {"eye_distance_to_shadow_map_extension", {"%f", &eye_distance_to_shadow_map_extension}},
656  {"minimum_shadow_map_extension_ratio", {"%f", &minimum_shadow_map_extension_ratio}},
657  };
658  };
659 
661  LightOptions lightOptions_;
662 
663  public:
664  // Options for simulating GNSS (GPS) sensors.
666  {
667  GeoreferenceOptions() = default;
668 
669  void parse_from(const rapidxml::xml_node<char>& node, COutputLogger& logger);
670 
672  mrpt::topography::TGeodeticCoords georefCoord;
673 
678 
680  bool world_is_utm = false;
681 
683  mrpt::topography::TUTMCoords utmRef;
684  int utm_zone = 0; // auto calculated
685  char utm_band = 'X'; // auto calculated
686 
687  const TParameterDefinitions params = {
688  {"latitude", {"%lf", &georefCoord.lat.decimal_value}},
689  {"longitude", {"%lf", &georefCoord.lon.decimal_value}},
690  {"height", {"%lf", &georefCoord.height}},
691  {"world_to_enu_rotation_deg", {"%lf_deg", &world_to_enu_rotation}},
692  {"world_is_utm", {"%bool", &world_is_utm}},
693  };
694  };
695 
696  const GeoreferenceOptions& georeferenceOptions() const { return georeferenceOptions_; }
697 
699  mrpt::math::TVector3D worldRenderOffset() const
700  {
701  return worldRenderOffset_ ? *worldRenderOffset_ : mrpt::math::TVector3D(0, 0, 0);
702  }
703  mrpt::math::TPose3D applyWorldRenderOffset(mrpt::math::TPose3D p) const
704  {
705  const auto t = worldRenderOffset();
706  p.x += t.x;
707  p.y += t.y;
708  p.z += t.z;
709  return p;
710  }
711  mrpt::poses::CPose3D applyWorldRenderOffset(mrpt::poses::CPose3D p) const
712  {
713  const auto t = worldRenderOffset();
714  p.x_incr(t.x);
715  p.y_incr(t.y);
716  p.z_incr(t.z);
717  return p;
718  }
720  void worldRenderOffsetPropose(const mrpt::math::TVector3D& v)
721  {
722  if (!worldRenderOffset_)
723  {
724  worldRenderOffset_ = v;
725  }
726  }
727 
728  private:
730  GeoreferenceOptions georeferenceOptions_;
731 
732  // -------- World contents ----------
734  std::recursive_mutex world_cs_;
735 
737  std::unique_ptr<b2World> box2d_world_;
738 
740  b2Body* b2_ground_body_ = nullptr;
741 
742  VehicleList vehicles_;
743  WorldElementList worldElements_;
744  BlockList blocks_;
745  ActorList actors_;
746 
748  std::vector<WorldJoint> joints_;
749 
750  bool initialized_ = false;
751 
752  // List of all objects above (vehicles, world_elements, blocks), but as
753  // shared_ptr to their Simulable interfaces, so we can easily iterate on
754  // this list only for common tasks:
755  SimulableList simulableObjects_;
756  std::mutex simulableObjectsMtx_;
757 
759  void internal_one_timestep(double dt);
760 
761  std::mutex simulationStepRunningMtx_;
762 
763  // A 2D-hash table of objects
764  struct lut_2d_coordinates_t
765  {
766  int32_t x, y;
767 
768  bool operator==(const lut_2d_coordinates_t& o) const noexcept
769  {
770  return (x == o.x && y == o.y);
771  }
772  };
773 
774  static lut_2d_coordinates_t xy_to_lut_coords(const mrpt::math::TPoint2Df& p);
775 
776  struct LutIndexHash
777  {
778  std::size_t operator()(const lut_2d_coordinates_t& p) const noexcept
779  {
780  // These are the implicit assumptions of the reinterpret cast below:
781  static_assert(sizeof(int32_t) == sizeof(uint32_t));
782  static_assert(offsetof(lut_2d_coordinates_t, x) == 0 * sizeof(uint32_t));
783  static_assert(offsetof(lut_2d_coordinates_t, y) == 1 * sizeof(uint32_t));
784 
785  const uint32_t* vec = reinterpret_cast<const uint32_t*>(&p);
786  return ((1 << 20) - 1) & (vec[0] * 73856093 ^ vec[1] * 19349663);
787  }
789  bool operator()(
790  const lut_2d_coordinates_t& k1, const lut_2d_coordinates_t& k2) const noexcept
791  {
792  if (k1.x != k2.x)
793  {
794  return k1.x < k2.x;
795  }
796  return k1.y < k2.y;
797  }
798  };
799 
800  using LUTCache =
801  std::unordered_map<lut_2d_coordinates_t, std::vector<Simulable::Ptr>, LutIndexHash>;
802 
804  const LUTCache& getLUTCacheOfObjects() const;
805 
806  mutable LUTCache lut2d_objects_;
807  mutable bool lut2d_objects_is_up_to_date_ = false;
808 
809  void internal_update_lut_cache() const;
810 
812  struct GUI
813  {
814  GUI(World& parent) : parent_(parent) {}
815 
816  mrpt::gui::CDisplayWindowGUI::Ptr gui_win;
817  nanogui::Label* lbCpuUsage = nullptr;
818  std::vector<nanogui::Label*> lbStatuses;
819  nanogui::Button* btnReplaceObject = nullptr;
820 
822  {
823  nanogui::CheckBox* cb = nullptr;
824  Simulable::Ptr simulable;
825  VisualObject* visual = nullptr;
826  };
827 
828  // Buttons that must be {dis,en}abled when there is a selected object:
829  std::vector<nanogui::Widget*> btns_selectedOps;
830  std::vector<InfoPerObject> gui_cbObjects;
831  InfoPerObject gui_selectedObject;
832 
833  mrpt::math::TPoint3D clickedPt{0, 0, 0};
834 
835  void prepare_control_window();
836  void prepare_status_window();
837  void prepare_editor_window();
838 
839  void handle_mouse_operations();
840 
841  private:
842  World& parent_;
843  };
844  GUI gui_{*this};
845 
849  mrpt::opengl::COpenGLScene::Ptr worldVisual_ = mrpt::opengl::COpenGLScene::Create();
850 
856  mrpt::opengl::COpenGLScene worldPhysical_;
857  std::recursive_mutex worldPhysicalMtx_;
858 
864  std::optional<mrpt::math::TVector3D> worldRenderOffset_;
865 
867  std::map<std::string, mrpt::math::TPose3D> copy_of_objects_dynstate_pose_;
868  std::map<std::string, mrpt::math::TTwist2D> copy_of_objects_dynstate_twist_;
869  std::set<std::string> copy_of_objects_had_collision_;
870  std::recursive_mutex copy_of_objects_dynstate_mtx_;
871 
872  std::set<std::string> reset_collision_flags_;
873  std::mutex reset_collision_flags_mtx_;
874 
875  void internal_gui_on_observation(const Simulable& veh, const mrpt::obs::CObservation::Ptr& obs);
876  void internal_gui_on_observation_3Dscan(
877  const Simulable& veh, const std::shared_ptr<mrpt::obs::CObservation3DRangeScan>& obs);
878  void internal_gui_on_observation_image(
879  const Simulable& veh, const std::shared_ptr<mrpt::obs::CObservationImage>& obs);
880 
881  mrpt::math::TPoint2D internal_gui_on_image(
882  const std::string& label, const mrpt::img::CImage& im, int winPosX);
883 
884  std::map<std::string, nanogui::Window*> guiObsViz_;
885 
888  void setLightDirectionFromAzimuthElevation(const float azimuth, const float elevation);
889  // end GUI stuff
891 
892  mrpt::system::CTimeLogger timlogger_{true /*enabled*/, "mvsim::World"};
893  mrpt::system::CTicTac timer_iteration_;
894 
895  void process_load_walls(const rapidxml::xml_node<char>& node);
896  void insertBlock(const Block::Ptr& block);
897 
898  struct XmlParserContext
899  {
900  XmlParserContext(const rapidxml::xml_node<char>* n, const std::string& basePath)
901  : node(n), currentBasePath(basePath)
902  {
903  }
904 
905  const rapidxml::xml_node<char>* node = nullptr;
906  const std::string currentBasePath;
907  };
908 
910  void internal_recursive_parse_XML(const XmlParserContext& ctx);
911 
912  using xml_tag_parser_function_t = std::function<void(const XmlParserContext&)>;
913 
914  std::map<std::string, xml_tag_parser_function_t> xmlParsers_;
915 
916  void register_standard_xml_tag_parsers();
917 
918  void register_tag_parser(const std::string& xmlTagName, const xml_tag_parser_function_t& f)
919  {
920  xmlParsers_.emplace(xmlTagName, f);
921  }
922  void register_tag_parser(
923  const std::string& xmlTagName, void (World::*f)(const XmlParserContext& ctx))
924  {
925  xmlParsers_.emplace(
926  xmlTagName, [this, f](const XmlParserContext& ctx) { (this->*f)(ctx); });
927  }
928 
929  // ======== XML parser tags ========
930  void parse_tag_element(const XmlParserContext& ctx);
931  void parse_tag_vehicle(const XmlParserContext& ctx);
933  void parse_tag_vehicle_class(const XmlParserContext& ctx);
934  void parse_tag_sensor(const XmlParserContext& ctx);
935  void parse_tag_block(const XmlParserContext& ctx);
936  void parse_tag_block_class(const XmlParserContext& ctx);
937  void parse_tag_gui(const XmlParserContext& ctx);
938  void parse_tag_lights(const XmlParserContext& ctx);
939  void parse_tag_georeference(const XmlParserContext& ctx);
940  void parse_tag_walls(const XmlParserContext& ctx);
941  void parse_tag_include(const XmlParserContext& ctx);
942  void parse_tag_variable(const XmlParserContext& ctx);
943  void parse_tag_for(const XmlParserContext& ctx);
944  void parse_tag_if(const XmlParserContext& ctx);
945  void parse_tag_marker(const XmlParserContext& ctx);
946  void parse_tag_joint(const XmlParserContext& ctx);
947  void parse_tag_actor(const XmlParserContext& ctx);
948  void parse_tag_actor_class(const XmlParserContext& ctx);
949 
950  // ======== end of XML parser tags ========
951 
952  mutable RemoteResourcesManager remoteResources_;
953 
954  void internalOnObservation(const Simulable& veh, const mrpt::obs::CObservation::Ptr& obs);
955 
956  void internalPostSimulStepForRawlog();
957  void internalPostSimulStepForTrajectory();
958 
959  std::mutex rawlog_io_mtx_;
960 #if MRPT_VERSION >= 0x020f07
961  std::map<std::string, std::shared_ptr<mrpt::io::CCompressedOutputStream>> rawlog_io_per_veh_;
962 #else
963  std::map<std::string, std::shared_ptr<mrpt::io::CFileGZOutputStream>> rawlog_io_per_veh_;
964 #endif
965  std::optional<double> rawlog_last_odom_time_;
966 
967  std::mutex gt_io_mtx_;
968  std::map<std::string, std::fstream> gt_io_per_veh_;
969  std::optional<double> gt_last_time_;
970 
971  // ============ Elevation Field Collision artifacts ==============
972  struct TFixturePtr
973  {
974  TFixturePtr() = default;
975  b2Fixture* fixture = nullptr;
976  };
977  struct TInfoPerCollidableobj
978  {
979  TInfoPerCollidableobj() = default;
980 
981  mrpt::poses::CPose3D pose;
982  b2Body* collide_body = nullptr;
983  double representativeHeight = 0.01;
984  double maxWorkableStepHeight = 0.10;
985  double speed = .0;
986  mrpt::math::TPolygon2D contour;
987  const std::vector<float>* wheel_heights = nullptr;
988  std::vector<float> contour_heights;
989  std::vector<TFixturePtr> collide_fixtures;
990  };
991  std::vector<std::optional<TInfoPerCollidableobj>> obstacles_for_each_obj_;
992  // ============ end of elevation field collision =================
993 
994  // Services:
995  void internal_advertiseServices(); // called from connectToServer()
996 
997 #if MVSIM_HAS_ZMQ && MVSIM_HAS_PROTOBUF
998 
999  mvsim_msgs::SrvSetPoseAnswer srv_set_pose(const mvsim_msgs::SrvSetPose& req);
1000  mvsim_msgs::SrvGetPoseAnswer srv_get_pose(const mvsim_msgs::SrvGetPose& req);
1001  mvsim_msgs::SrvSetControllerTwistAnswer srv_set_controller_twist(
1002  const mvsim_msgs::SrvSetControllerTwist& req);
1003  mvsim_msgs::SrvShutdownAnswer srv_shutdown(const mvsim_msgs::SrvShutdown& req);
1004 #endif
1005 };
1006 } // namespace mvsim
Definition: Block.h:51
Definition: Client.h:49
Definition: Simulable.h:40
Definition: VehicleBase.h:44
Definition: VisualObject.h:36
Definition: WorldElementBase.h:28
Definition: World.h:132
bool is_GUI_open() const
std::multimap< std::string, HumanActor::Ptr > ActorList
Definition: World.h:361
void internalGraphicsLoopTasksForSimulation()
std::multimap< std::string, Simulable::Ptr > SimulableList
Definition: World.h:358
float getHighestElevationUnder(const mrpt::math::TPoint3Df &queryPt) const
void force_set_simul_time(double newSimulatedTime)
Normally should not be called by users, for internal use only.
Definition: World.h:181
SimulableList & getListOfSimulableObjects()
Always lock/unlock getListOfSimulableObjectsMtx() before using this:
Definition: World.h:382
void connectToServer()
mrpt::Clock::time_point get_simul_timestamp() const
Definition: World.h:192
void runVisitorOnVehicles(const vehicle_visitor_t &v)
mrpt::opengl::CSetOfObjects::Ptr guiUserObjectsPhysical_
Definition: World.h:262
mrpt::math::TVector3D worldRenderOffset() const
(See docs for worldRenderOffset_)
Definition: World.h:699
double get_simul_time() const
Definition: World.h:174
void runVisitorOnBlocks(const block_visitor_t &v)
std::optional< std::any > getPropertyAt(const std::string &propertyName, const mrpt::math::TPoint3D &worldXYZ) const
void worldRenderOffsetPropose(const mrpt::math::TVector3D &v)
(See docs for worldRenderOffset_)
Definition: World.h:720
void update_GUI(TUpdateGUIParams *params=nullptr)
void dispatchOnObservation(const Simulable &veh, const mrpt::obs::CObservation::Ptr &obs)
void load_from_XML_file(const std::string &xmlFileNamePath)
double get_gravity() const
Definition: World.h:209
std::multimap< std::string, VehicleBase::Ptr > VehicleList
Definition: World.h:348
void close_GUI()
Forces closing the GUI window, if any.
double get_simul_timestep() const
Simulation fixed-time interval for numerical integration.
std::string xmlPathToActualPath(const std::string &modelURI) const
std::set< float > getElevationsAt(const mrpt::math::TPoint2D &worldXY) const
std::string local_to_abs_path(const std::string &in_path) const
void clear_all()
std::multimap< std::string, Block::Ptr > BlockList
Definition: World.h:354
std::optional< mvsim::TJoyStickEvent > getJoystickState() const
World()
Default ctor: inits an empty world.
void set_gravity(double accel)
Definition: World.h:213
void set_simul_timestep(double timestep)
Definition: World.h:205
void load_from_XML(const std::string &xml_text, const std::string &fileNameForPath=std::string("."))
std::list< WorldElementBase::Ptr > WorldElementList
Definition: World.h:351
void run_simulation(double dt)
void runVisitorOnWorldElements(const world_element_visitor_t &v)
Definition: World.h:90
std::string bodyA_name
Names of the two connected Simulable objects (vehicles, blocks, etc.)
Definition: World.h:100
mrpt::math::TPoint2D anchorA
Local anchor points on each body (in body-local coordinates)
Definition: World.h:104
bool enableLimit
Revolute joint parameters:
Definition: World.h:114
float maxLength
Distance joint parameters (only used when type == Distance):
Definition: World.h:108
b2Joint * b2joint
Runtime Box2D joint (owned by the b2World, do NOT delete manually)
Definition: World.h:119
float lowerAngle_deg
Parsed in degrees, converted to radians.
Definition: World.h:115
Type
Definition: World.h:92
@ Distance
b2DistanceJoint (rope-like max length constraint)
@ Revolute
b2RevoluteJoint (pin/hinge)
Definition: World.h:226
int keycode
0=no Key. Otherwise, ASCII code.
Definition: World.h:227
Definition: World.h:822
Definition: World.h:666
mrpt::topography::TGeodeticCoords georefCoord
Latitude/longitude/height of the world (0,0,0) frame.
Definition: World.h:672
double world_to_enu_rotation
Definition: World.h:677
mrpt::topography::TUTMCoords utmRef
Definition: World.h:683
bool world_is_utm
Definition: World.h:680
Definition: World.h:237
std::string msg_lines
Messages to show.
Definition: World.h:239
GUIKeyEvent keyevent
Keystrokes in the window are returned here.
Definition: World.h:238