Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009 #include <mvsim/World.h>
00010
00011 #include <mrpt/utils/utils_defs.h>
00012 #include <mrpt/system/filesystem.h>
00013
00014 #include <iostream>
00015 #include <algorithm>
00016 #include <stdexcept>
00017 #include <map>
00018
00019 using namespace mvsim;
00020 using namespace std;
00021
00022
00023 World::World()
00024 : m_gravity(9.81),
00025 m_simul_time(0.0),
00026 m_simul_timestep(0.010),
00027 m_b2d_vel_iters(6),
00028 m_b2d_pos_iters(3),
00029 m_base_path("."),
00030 m_box2d_world(NULL)
00031 {
00032 this->clear_all();
00033 }
00034
00035
00036 World::~World()
00037 {
00038 this->clear_all();
00039 delete m_box2d_world;
00040 m_box2d_world = NULL;
00041 }
00042
00043
00044 void World::clear_all(bool acquire_mt_lock)
00045 {
00046 try
00047 {
00048 if (acquire_mt_lock) m_world_cs.lock();
00049
00050
00051 m_simul_time = 0.0;
00052
00053
00054
00055 delete m_box2d_world;
00056 m_box2d_world = new b2World(b2Vec2_zero);
00057
00058
00059 b2BodyDef groundBodyDef;
00060 m_b2_ground_body = m_box2d_world->CreateBody(&groundBodyDef);
00061
00062
00063
00064 for (TListVehicles::iterator it = m_vehicles.begin();
00065 it != m_vehicles.end(); ++it)
00066 delete it->second;
00067 m_vehicles.clear();
00068
00069 for (std::list<WorldElementBase*>::iterator it =
00070 m_world_elements.begin();
00071 it != m_world_elements.end(); ++it)
00072 delete *it;
00073 m_world_elements.clear();
00074
00075 for (TListBlocks::iterator it = m_blocks.begin(); it != m_blocks.end();
00076 ++it)
00077 delete it->second;
00078 m_blocks.clear();
00079
00080 if (acquire_mt_lock) m_world_cs.unlock();
00081 }
00082 catch (std::exception&)
00083 {
00084 if (acquire_mt_lock) m_world_cs.unlock();
00085 throw;
00086 }
00087 }
00088
00090 void World::run_simulation(double dt)
00091 {
00092 m_timlogger.registerUserMeasure("run_simulation.dt", dt);
00093
00094
00095 ASSERT_(dt > 0)
00096 ASSERT_(m_simul_timestep > 0)
00097
00098
00099 const double end_time = m_simul_time + dt;
00100 const double timetol =
00101 1e-6;
00102 while (m_simul_time < (end_time - timetol))
00103 {
00104
00105 internal_one_timestep(m_simul_timestep);
00106 }
00107 }
00108
00110 void World::internal_one_timestep(double dt)
00111 {
00112 m_timer_iteration.Tic();
00113
00114 TSimulContext context;
00115 context.b2_world = m_box2d_world;
00116 context.simul_time = m_simul_time;
00117 context.dt = dt;
00118
00119
00120 {
00121 mrpt::utils::CTimeLoggerEntry tle(m_timlogger, "timestep.0.prestep");
00122 for (TListVehicles::iterator it = m_vehicles.begin();
00123 it != m_vehicles.end(); ++it)
00124 it->second->simul_pre_timestep(context);
00125
00126 for (TListVehicles::iterator it = m_vehicles.begin();
00127 it != m_vehicles.end(); ++it)
00128 {
00129 VehicleBase::TListSensors& sensors = it->second->getSensors();
00130 for (VehicleBase::TListSensors::iterator itSen = sensors.begin();
00131 itSen != sensors.end(); ++itSen)
00132 {
00133 (*itSen)->simul_pre_timestep(context);
00134 }
00135 }
00136
00137 for (TListBlocks::iterator it = m_blocks.begin(); it != m_blocks.end();
00138 ++it)
00139 it->second->simul_pre_timestep(context);
00140
00141 for (std::list<WorldElementBase*>::iterator it =
00142 m_world_elements.begin();
00143 it != m_world_elements.end(); ++it)
00144 (*it)->simul_pre_timestep(context);
00145 }
00146
00147
00148 {
00149 mrpt::utils::CTimeLoggerEntry tle(
00150 m_timlogger, "timestep.1.dynamics_integrator");
00151
00152 m_box2d_world->Step(dt, m_b2d_vel_iters, m_b2d_pos_iters);
00153 m_simul_time += dt;
00154 }
00155
00156
00157 {
00158 mrpt::utils::CTimeLoggerEntry tle(
00159 m_timlogger, "timestep.3.save_dynstate");
00160
00161 context.simul_time = m_simul_time;
00162 for (TListVehicles::iterator it = m_vehicles.begin();
00163 it != m_vehicles.end(); ++it)
00164 {
00165 it->second->simul_post_timestep_common(context);
00166 it->second->simul_post_timestep(context);
00167 }
00168 for (TListBlocks::iterator it = m_blocks.begin(); it != m_blocks.end();
00169 ++it)
00170 {
00171 it->second->simul_post_timestep_common(context);
00172 it->second->simul_post_timestep(context);
00173 }
00174 }
00175
00176
00177 {
00178 mrpt::utils::CTimeLoggerEntry tle(m_timlogger, "timestep.4.poststep");
00179 for (TListVehicles::iterator it = m_vehicles.begin();
00180 it != m_vehicles.end(); ++it)
00181 it->second->simul_post_timestep(context);
00182
00183 for (TListVehicles::iterator it = m_vehicles.begin();
00184 it != m_vehicles.end(); ++it)
00185 {
00186 VehicleBase::TListSensors& sensors = it->second->getSensors();
00187 for (VehicleBase::TListSensors::iterator itSen = sensors.begin();
00188 itSen != sensors.end(); ++itSen)
00189 {
00190 (*itSen)->simul_post_timestep(context);
00191 }
00192 }
00193
00194 for (TListBlocks::iterator it = m_blocks.begin(); it != m_blocks.end();
00195 ++it)
00196 it->second->simul_post_timestep(context);
00197
00198 for (std::list<WorldElementBase*>::iterator it =
00199 m_world_elements.begin();
00200 it != m_world_elements.end(); ++it)
00201 (*it)->simul_post_timestep(context);
00202 }
00203
00204 const double ts = m_timer_iteration.Tac();
00205 m_timlogger.registerUserMeasure(
00206 (ts > dt ? "timestep_too_slow_alert" : "timestep"), ts);
00207 }
00208
00211 std::string World::resolvePath(const std::string& s_in) const
00212 {
00213 std::string ret;
00214 const std::string s = mrpt::system::trim(s_in);
00215
00216
00217
00218
00219 bool is_relative = true;
00220 if (s.size() > 2 && s[1] == ':' && (s[2] == '/' || s[2] == '\\'))
00221 is_relative = false;
00222 if (s.size() > 0 && (s[0] == '/' || s[0] == '\\')) is_relative = false;
00223 if (is_relative)
00224 {
00225 ret = m_base_path;
00226 if (!ret.empty() && ret[ret.size() - 1] != '/' &&
00227 ret[ret.size() - 1] != '\\')
00228 ret += string("/");
00229 ret += s;
00230 }
00231 else
00232 ret = s;
00233
00234
00235
00236
00237 return mrpt::system::filePathSeparatorsToNative(ret);
00238 }
00239
00241 void World::runVisitorOnVehicles(VehicleVisitorBase& v)
00242 {
00243 for (TListVehicles::iterator it = m_vehicles.begin();
00244 it != m_vehicles.end(); ++it)
00245 v.visit(it->second);
00246 }
00247
00249 void World::runVisitorOnWorldElements(WorldElementVisitorBase& v)
00250 {
00251 for (std::list<WorldElementBase*>::iterator it = m_world_elements.begin();
00252 it != m_world_elements.end(); ++it)
00253 v.visit(*it);
00254 }