World.h
Go to the documentation of this file.
00001 /*+-------------------------------------------------------------------------+
00002   |                       MultiVehicle simulator (libmvsim)                 |
00003   |                                                                         |
00004   | Copyright (C) 2014  Jose Luis Blanco Claraco (University of Almeria)    |
00005   | Copyright (C) 2017  Borys Tymchenko (Odessa Polytechnic University)     |
00006   | Distributed under GNU General Public License version 3                  |
00007   |   See <http://www.gnu.org/licenses/>                                    |
00008   +-------------------------------------------------------------------------+ */
00009 
00010 #pragma once
00011 
00012 #include <mvsim/VehicleBase.h>
00013 #include <mvsim/WorldElements/WorldElementBase.h>
00014 #include <mvsim/Block.h>
00015 
00016 #include <mrpt/utils/CTimeLogger.h>
00017 #include <mrpt/utils/CTicTac.h>
00018 #include <mrpt/gui/CDisplayWindow3D.h>
00019 
00020 #include <mrpt/version.h>
00021 #if MRPT_VERSION >= 0x130
00022 #include <mrpt/obs/CObservation.h>
00023 #else
00024 #include <mrpt/slam/CObservation.h>
00025 #endif
00026 
00027 #include <Box2D/Dynamics/b2World.h>
00028 #include <Box2D/Dynamics/b2Body.h>
00029 
00030 #include <list>
00031 
00032 namespace mvsim
00033 {
00039 class World
00040 {
00041    public:
00044         World();  
00045         ~World();  
00046 
00047         void clear_all(bool acquire_mt_lock = true);  
00048 
00049 
00050 
00051 
00052 
00053 
00054 
00055 
00063         void load_from_XML(
00064                 const std::string& xml_text,
00065                 const std::string& fileNameForPath = std::string("."));
00071         double get_simul_time() const
00072         {
00073                 return m_simul_time;
00074         }  
00075 
00076         double get_simul_timestep() const
00077         {
00078                 return m_simul_timestep;
00079         }  
00080         void set_simul_timestep(double timestep)
00081         {
00082                 m_simul_timestep = timestep;
00083         }  
00084 
00085         double get_gravity() const
00086         {
00087                 return m_gravity;
00088         }  
00089 
00090         void set_gravity(double accel)
00091         {
00092                 m_gravity = accel;
00093         }  
00094 
00095 
00101         void run_simulation(double dt);
00102 
00104         struct TGUIKeyEvent
00105         {
00106                 int keycode;  
00107                 mrpt::gui::mrptKeyModifier key_modifier;
00108 
00109                 TGUIKeyEvent() : keycode(0) {}
00110         };
00111 
00112         struct TUpdateGUIParams
00113         {
00114                 TGUIKeyEvent keyevent;  
00115                 std::string msg_lines;  
00116 
00117                 TUpdateGUIParams();
00118         };
00119 
00127         void update_GUI(TUpdateGUIParams* params = NULL);
00128 
00129         bool is_GUI_open() const;  
00130 
00131 
00132         void close_GUI();  
00133 
00138         typedef std::multimap<std::string, VehicleBase*>
00139                 TListVehicles;  
00140 
00141         typedef std::list<WorldElementBase*>
00142                 TListWorldElements;  
00143         typedef std::multimap<std::string, Block*>
00144                 TListBlocks;  
00145 
00146 
00150         b2World* getBox2DWorld() { return m_box2d_world; }
00151         const b2World* getBox2DWorld() const { return m_box2d_world; }
00152         b2Body* getBox2DGroundBody() { return m_b2_ground_body; }
00153         const TListVehicles& getListOfVehicles() const { return m_vehicles; }
00154         TListVehicles& getListOfVehicles() { return m_vehicles; }
00155         const TListBlocks& getListOfBlocks() const { return m_blocks; }
00156         TListBlocks& getListOfBlocks() { return m_blocks; }
00157         const TListWorldElements& getListOfWorldElements() const
00158         {
00159                 return m_world_elements;
00160         }
00161 
00162         mrpt::utils::CTimeLogger& getTimeLogger() { return m_timlogger; }
00165         std::string resolvePath(const std::string& in_path) const;
00166 
00172         struct VehicleVisitorBase
00173         {
00174                 virtual void visit(VehicleBase* obj) = 0;
00175         };
00177         struct WorldElementVisitorBase
00178         {
00179                 virtual void visit(WorldElementBase* obj) = 0;
00180         };
00181 
00183         void runVisitorOnVehicles(VehicleVisitorBase& v);
00184 
00186         void runVisitorOnWorldElements(WorldElementVisitorBase& v);
00187 
00192         virtual void onNewObservation(
00193                 const VehicleBase& veh,
00194 #if MRPT_VERSION >= 0x130
00195                 const mrpt::obs::CObservation* obs
00196 #else
00197                 const mrpt::slam::CObservation* obs
00198 #endif
00199                 )
00200         {
00201                 /* default: do nothing */
00202         }
00205    private:
00206         friend class VehicleBase;
00207         friend class Block;
00208 
00209         // -------- World Params ----------
00210         double m_gravity;  
00211 
00212         double m_simul_time;  
00213 
00214 
00215         double m_simul_timestep;  
00216 
00217         int m_b2d_vel_iters,
00218                 m_b2d_pos_iters;  
00219         std::string m_base_path;  
00220 
00221         // ------- GUI options -----
00222         struct TGUI_Options
00223         {
00224                 unsigned int win_w, win_h;
00225                 bool ortho;
00226                 bool show_forces;
00227                 double force_scale;  
00228                 double camera_distance;
00229                 double fov_deg;
00230                 std::string
00231                         follow_vehicle;  
00232 
00233                 TGUI_Options();
00234                 void parse_from(const rapidxml::xml_node<char>& node);
00235         };
00236 
00237         TGUI_Options m_gui_options;  
00238 
00239 
00240         // -------- World contents ----------
00241         std::mutex m_world_cs;  
00242 
00243 
00244         b2World* m_box2d_world;  
00245         b2Body*
00246                 m_b2_ground_body;  
00247 
00248         TListVehicles m_vehicles;
00249         TListWorldElements m_world_elements;
00250         TListBlocks m_blocks;
00251 
00253         void internal_one_timestep(double dt);
00254 
00255         // -------- GUI stuff ----------
00256         mrpt::gui::CDisplayWindow3D::Ptr m_gui_win;
00257 
00258         mrpt::utils::CTimeLogger m_timlogger;
00259         mrpt::utils::CTicTac m_timer_iteration;
00260 };
00261 }


mvsim
Author(s):
autogenerated on Thu Sep 7 2017 09:27:48