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>
38 #include <mrpt/version.h>
39 #if MRPT_VERSION >= 0x020f07
40 #include <mrpt/io/CCompressedOutputStream.h>
42 #include <mrpt/io/CFileGZOutputStream.h>
45 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
46 #include <mvsim/Comms/Client.h>
54 #include <unordered_map>
56 #if MVSIM_HAS_ZMQ && MVSIM_HAS_PROTOBUF
61 class SrvGetPoseAnswer;
63 class SrvSetPoseAnswer;
64 class SrvSetControllerTwist;
65 class SrvSetControllerTwistAnswer;
67 class SrvShutdownAnswer;
101 std::string bodyB_name;
105 mrpt::math::TPoint2D anchorB{0, 0};
109 float minLength = 0.0f;
110 float stiffness = 0.0f;
111 float damping = 0.0f;
116 float upperAngle_deg = 0.0f;
131 class World :
public mrpt::system::COutputLogger
157 void internal_initialize();
167 const std::string& xml_text,
const std::string& fileNameForPath = std::string(
"."));
176 auto lck = mrpt::lockHelper(simul_time_mtx_);
183 auto lck = mrpt::lockHelper(simul_time_mtx_);
184 simulTime_ = newSimulatedTime;
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());
222 void insert_vehicle(
const VehicleBase::Ptr& veh);
228 bool modifierShift =
false;
229 bool modifierCtrl =
false;
230 bool modifierAlt =
false;
231 bool modifierSuper =
false;
253 const mrpt::gui::CDisplayWindowGUI::Ptr& gui_window()
const {
return gui_.gui_win; }
255 const mrpt::math::TPoint3D& gui_mouse_point()
const {
return gui_.clickedPt; }
263 std::mutex guiUserObjectsMtx_;
270 void internalRunSensorsOn3DScene(mrpt::opengl::COpenGLScene& physicalObjects);
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();
277 std::mutex pendingRunSensorsOn3DSceneMtx_;
278 bool pendingRunSensorsOn3DScene_ =
false;
280 void mark_as_pending_running_sensors_on_3D_scene()
282 pendingRunSensorsOn3DSceneMtx_.lock();
283 pendingRunSensorsOn3DScene_ =
true;
284 pendingRunSensorsOn3DSceneMtx_.unlock();
286 void clear_pending_running_sensors_on_3D_scene()
288 pendingRunSensorsOn3DSceneMtx_.lock();
289 pendingRunSensorsOn3DScene_ =
false;
290 pendingRunSensorsOn3DSceneMtx_.unlock();
292 bool pending_running_sensors_on_3D_scene()
294 pendingRunSensorsOn3DSceneMtx_.lock();
295 bool ret = pendingRunSensorsOn3DScene_;
296 pendingRunSensorsOn3DSceneMtx_.unlock();
300 std::string guiMsgLines_;
301 std::mutex guiMsgLinesMtx_;
303 std::thread gui_thread_;
305 std::atomic_bool gui_thread_running_ =
false;
306 std::atomic_bool simulator_must_close_ =
false;
307 mutable std::mutex gui_thread_start_mtx_;
309 bool simulator_must_close()
const
311 gui_thread_start_mtx_.lock();
312 const bool v = simulator_must_close_;
313 gui_thread_start_mtx_.unlock();
316 void simulator_must_close(
bool value)
318 gui_thread_start_mtx_.lock();
319 simulator_must_close_ = value;
320 gui_thread_start_mtx_.unlock();
323 void enqueue_task_to_run_in_gui_thread(
const std::function<
void(
void)>& f)
325 guiUserPendingTasksMtx_.lock();
326 guiUserPendingTasks_.emplace_back(f);
327 guiUserPendingTasksMtx_.unlock();
330 std::vector<std::function<void(
void)>> guiUserPendingTasks_;
331 std::mutex guiUserPendingTasksMtx_;
333 GUIKeyEvent lastKeyEvent_;
334 std::atomic_bool lastKeyEventValid_ =
false;
335 std::mutex lastKeyEventMtx_;
354 using BlockList = std::multimap<std::string, Block::Ptr>;
361 using ActorList = std::multimap<std::string, HumanActor::Ptr>;
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_; }
376 const std::vector<WorldJoint>& getListOfJoints()
const {
return joints_; }
378 const ActorList& getListOfActors()
const {
return actors_; }
379 ActorList& getListOfActors() {
return actors_; }
384 auto& getListOfSimulableObjectsMtx() {
return simulableObjectsMtx_; }
386 mrpt::system::CTimeLogger& getTimeLogger() {
return timlogger_; }
406 using vehicle_visitor_t = std::function<void(
VehicleBase&)>;
408 using block_visitor_t = std::function<void(
Block&)>;
424 using on_observation_callback_t =
425 std::function<void(
const Simulable& ,
const mrpt::obs::CObservation::Ptr& )>;
427 void registerCallbackOnObservation(
const on_observation_callback_t& f)
429 callbacksOnObservation_.emplace_back(f);
441 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
446 void free_opengl_resources();
448 auto& physical_objects_mtx() {
return worldPhysicalMtx_; }
450 bool headless()
const {
return guiOptions_.headless; }
451 void headless(
bool setHeadless) { guiOptions_.headless = setHeadless; }
453 bool sensor_has_to_create_egl_context();
455 const std::map<std::string, std::string>& user_defined_variables()
const
457 return userDefinedVariables_;
468 float collisionThreshold()
const {
return collisionThreshold_; }
481 void internal_simul_pre_step_terrain_elevation();
488 const std::string& propertyName,
const mrpt::math::TPoint3D& worldXYZ)
const;
494 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
498 std::vector<on_observation_callback_t> callbacksOnObservation_;
503 double gravity_ = 9.81;
509 mutable double simulTimestep_ = 0;
511 mutable bool joystickEnabled_ =
false;
512 mutable std::optional<Joystick> joystick_;
515 int b2dVelIters_ = 8, b2dPosIters_ = 3;
518 float collisionThreshold_ = 0.03f;
520 std::string serverAddress_ =
"localhost";
523 std::string save_to_rawlog_;
525 double rawlog_odometry_rate_ = 10.0;
529 std::string save_ground_truth_trajectory_;
531 double ground_truth_rate_ = 50.0;
533 double max_slope_to_collide_ = 0.30;
534 double min_slope_to_collide_ = -0.50;
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_}},
554 std::map<std::string, std::string> userDefinedVariables_;
558 double simulTime_ = 0;
559 std::optional<double> simul_start_wallclock_time_;
560 std::mutex simul_time_mtx_;
563 std::string basePath_{
"."};
567 mrpt::opengl::CSetOfObjects::Ptr glUserObjsPhysical_ = mrpt::opengl::CSetOfObjects::Create();
568 mrpt::opengl::CSetOfObjects::Ptr glUserObjsViz_ = mrpt::opengl::CSetOfObjects::Create();
573 unsigned int win_w = 800, win_h = 600;
574 bool start_maximized =
true;
575 int refresh_fps = 20;
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;
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}},
610 TGUI_Options() =
default;
616 TGUI_Options guiOptions_;
620 LightOptions() =
default;
624 bool enable_shadows =
true;
625 int shadow_map_size = 2048;
627 double light_azimuth = mrpt::DEG2RAD(45.0);
628 double light_elevation = mrpt::DEG2RAD(70.0);
630 float light_clip_plane_min = 0.1f;
631 float light_clip_plane_max = 900.0f;
633 float shadow_bias = 1e-5;
634 float shadow_bias_cam2frag = 1e-5;
635 float shadow_bias_normal = 1e-4;
637 mrpt::img::TColor light_color = {0xff, 0xff, 0xff, 0xff};
638 float light_ambient = 0.5f;
640 float eye_distance_to_shadow_map_extension = 2.0f;
641 float minimum_shadow_map_extension_ratio = 0.005f;
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}},
661 LightOptions lightOptions_;
687 const TParameterDefinitions params = {
688 {
"latitude", {
"%lf", &
georefCoord.lat.decimal_value}},
689 {
"longitude", {
"%lf", &
georefCoord.lon.decimal_value}},
696 const GeoreferenceOptions& georeferenceOptions()
const {
return georeferenceOptions_; }
701 return worldRenderOffset_ ? *worldRenderOffset_ : mrpt::math::TVector3D(0, 0, 0);
703 mrpt::math::TPose3D applyWorldRenderOffset(mrpt::math::TPose3D p)
const
711 mrpt::poses::CPose3D applyWorldRenderOffset(mrpt::poses::CPose3D p)
const
722 if (!worldRenderOffset_)
724 worldRenderOffset_ = v;
730 GeoreferenceOptions georeferenceOptions_;
734 std::recursive_mutex world_cs_;
737 std::unique_ptr<b2World> box2d_world_;
740 b2Body* b2_ground_body_ =
nullptr;
748 std::vector<WorldJoint> joints_;
750 bool initialized_ =
false;
756 std::mutex simulableObjectsMtx_;
759 void internal_one_timestep(
double dt);
761 std::mutex simulationStepRunningMtx_;
764 struct lut_2d_coordinates_t
768 bool operator==(
const lut_2d_coordinates_t& o)
const noexcept
770 return (x == o.x && y == o.y);
774 static lut_2d_coordinates_t xy_to_lut_coords(
const mrpt::math::TPoint2Df& p);
778 std::size_t operator()(
const lut_2d_coordinates_t& p)
const noexcept
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));
785 const uint32_t* vec =
reinterpret_cast<const uint32_t*
>(&p);
786 return ((1 << 20) - 1) & (vec[0] * 73856093 ^ vec[1] * 19349663);
790 const lut_2d_coordinates_t& k1,
const lut_2d_coordinates_t& k2)
const noexcept
801 std::unordered_map<lut_2d_coordinates_t, std::vector<Simulable::Ptr>, LutIndexHash>;
804 const LUTCache& getLUTCacheOfObjects()
const;
806 mutable LUTCache lut2d_objects_;
807 mutable bool lut2d_objects_is_up_to_date_ =
false;
809 void internal_update_lut_cache()
const;
814 GUI(
World& parent) : parent_(parent) {}
816 mrpt::gui::CDisplayWindowGUI::Ptr gui_win;
817 nanogui::Label* lbCpuUsage =
nullptr;
818 std::vector<nanogui::Label*> lbStatuses;
819 nanogui::Button* btnReplaceObject =
nullptr;
823 nanogui::CheckBox* cb =
nullptr;
824 Simulable::Ptr simulable;
829 std::vector<nanogui::Widget*> btns_selectedOps;
830 std::vector<InfoPerObject> gui_cbObjects;
833 mrpt::math::TPoint3D clickedPt{0, 0, 0};
835 void prepare_control_window();
836 void prepare_status_window();
837 void prepare_editor_window();
839 void handle_mouse_operations();
849 mrpt::opengl::COpenGLScene::Ptr worldVisual_ = mrpt::opengl::COpenGLScene::Create();
856 mrpt::opengl::COpenGLScene worldPhysical_;
857 std::recursive_mutex worldPhysicalMtx_;
864 std::optional<mrpt::math::TVector3D> worldRenderOffset_;
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_;
872 std::set<std::string> reset_collision_flags_;
873 std::mutex reset_collision_flags_mtx_;
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);
881 mrpt::math::TPoint2D internal_gui_on_image(
882 const std::string& label,
const mrpt::img::CImage& im,
int winPosX);
884 std::map<std::string, nanogui::Window*> guiObsViz_;
888 void setLightDirectionFromAzimuthElevation(
const float azimuth,
const float elevation);
892 mrpt::system::CTimeLogger timlogger_{
true ,
"mvsim::World"};
893 mrpt::system::CTicTac timer_iteration_;
896 void insertBlock(
const Block::Ptr& block);
898 struct XmlParserContext
901 : node(n), currentBasePath(basePath)
906 const std::string currentBasePath;
910 void internal_recursive_parse_XML(
const XmlParserContext& ctx);
912 using xml_tag_parser_function_t = std::function<void(
const XmlParserContext&)>;
914 std::map<std::string, xml_tag_parser_function_t> xmlParsers_;
916 void register_standard_xml_tag_parsers();
918 void register_tag_parser(
const std::string& xmlTagName,
const xml_tag_parser_function_t& f)
920 xmlParsers_.emplace(xmlTagName, f);
922 void register_tag_parser(
923 const std::string& xmlTagName,
void (
World::*f)(
const XmlParserContext& ctx))
926 xmlTagName, [
this, f](
const XmlParserContext& ctx) { (this->*f)(ctx); });
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);
952 mutable RemoteResourcesManager remoteResources_;
954 void internalOnObservation(
const Simulable& veh,
const mrpt::obs::CObservation::Ptr& obs);
956 void internalPostSimulStepForRawlog();
957 void internalPostSimulStepForTrajectory();
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_;
963 std::map<std::string, std::shared_ptr<mrpt::io::CFileGZOutputStream>> rawlog_io_per_veh_;
965 std::optional<double> rawlog_last_odom_time_;
967 std::mutex gt_io_mtx_;
968 std::map<std::string, std::fstream> gt_io_per_veh_;
969 std::optional<double> gt_last_time_;
974 TFixturePtr() =
default;
975 b2Fixture* fixture =
nullptr;
977 struct TInfoPerCollidableobj
979 TInfoPerCollidableobj() =
default;
981 mrpt::poses::CPose3D pose;
982 b2Body* collide_body =
nullptr;
983 double representativeHeight = 0.01;
984 double maxWorkableStepHeight = 0.10;
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;
991 std::vector<std::optional<TInfoPerCollidableobj>> obstacles_for_each_obj_;
995 void internal_advertiseServices();
997 #if MVSIM_HAS_ZMQ && MVSIM_HAS_PROTOBUF
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);
Definition: Simulable.h:40
Definition: VehicleBase.h:44
Definition: VisualObject.h:36
Definition: WorldElementBase.h:28
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
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
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)
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)
int keycode
0=no Key. Otherwise, ASCII code.
Definition: World.h:227
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
std::string msg_lines
Messages to show.
Definition: World.h:239
GUIKeyEvent keyevent
Keystrokes in the window are returned here.
Definition: World.h:238