Classes | Private Member Functions | Private Attributes | Friends | List of all members
mvsim::World Class Reference

#include <World.h>

Inheritance diagram for mvsim::World:
Inheritance graph
[legend]

Classes

struct  TGUI_Options
 
struct  TGUIKeyEvent
 
struct  TUpdateGUIParams
 
struct  VehicleVisitorBase
 
struct  WorldElementVisitorBase
 

Public Types

Public types
typedef std::multimap< std::string, VehicleBase * > TListVehicles
 
typedef std::list< WorldElementBase * > TListWorldElements
 getListOfVehicles() More...
 
typedef std::multimap< std::string, Block * > TListBlocks
 

Public Member Functions

Initialization, simulation set-up
 World ()
 Default ctor: inits an empty world. More...
 
 ~World ()
 Dtor. More...
 
void clear_all (bool acquire_mt_lock=true)
 
void load_from_XML (const std::string &xml_text, const std::string &fileNameForPath=std::string("."))
 
Simulation execution
double get_simul_time () const
 Simulation wall-clock time. More...
 
double get_simul_timestep () const
 Simulation fixed-time interval for numerical integration. More...
 
void set_simul_timestep (double timestep)
 Simulation fixed-time interval for numerical integration. More...
 
double get_gravity () const
 
void set_gravity (double accel)
 
void run_simulation (double dt)
 
void update_GUI (TUpdateGUIParams *params=NULL)
 
bool is_GUI_open () const
 Forces closing the GUI window, if any. More...
 
void close_GUI ()
 a previous call to update_GUI() More...
 
Access inner working objects
b2WorldgetBox2DWorld ()
 
const b2WorldgetBox2DWorld () const
 
b2BodygetBox2DGroundBody ()
 
const TListVehiclesgetListOfVehicles () const
 
TListVehiclesgetListOfVehicles ()
 
const TListBlocksgetListOfBlocks () const
 
TListBlocksgetListOfBlocks ()
 
const TListWorldElementsgetListOfWorldElements () const
 
CTimeLogger & getTimeLogger ()
 
std::string resolvePath (const std::string &in_path) const
 
Visitors API
void runVisitorOnVehicles (VehicleVisitorBase &v)
 
void runVisitorOnWorldElements (WorldElementVisitorBase &v)
 
Optional user hooks
virtual void onNewObservation (const VehicleBase &veh, const mrpt::slam::CObservation *obs)
 

Private Member Functions

void internal_one_timestep (double dt)
 

Private Attributes

b2Bodym_b2_ground_body
 Used to declare friction between vehicles-ground. More...
 
int m_b2d_pos_iters
 Velocity and position iteration count (Box2D) More...
 
int m_b2d_vel_iters
 integration. More...
 
std::string m_base_path
 Path from which to take relative directories. More...
 
TListBlocks m_blocks
 
b2Worldm_box2d_world
 objects from multithreading access. More...
 
double m_gravity
 
TGUI_Options m_gui_options
 
mrpt::gui::CDisplayWindow3D::Ptr m_gui_win
 
double m_simul_time
 evaluate weights for friction, etc. More...
 
double m_simul_timestep
 
CTicTac m_timer_iteration
 
CTimeLogger m_timlogger
 
TListVehicles m_vehicles
 
std::mutex m_world_cs
 first time the GUI window is created. More...
 
TListWorldElements m_world_elements
 

Friends

class Block
 
class VehicleBase
 

Detailed Description

Simulation happens inside a World object. This is the central class for usage from user code, running the simulation, loading XML models, managing GUI visualization, etc. The ROS node acts as a bridge between this class and the ROS subsystem.

Definition at line 67 of file World.h.

Member Typedef Documentation

typedef std::multimap<std::string, Block*> mvsim::World::TListBlocks

Map 'block-name' => block object. See

Definition at line 172 of file World.h.

typedef std::multimap<std::string, VehicleBase*> mvsim::World::TListVehicles

Map 'vehicle-name' => vehicle object. See

Definition at line 167 of file World.h.

getListOfVehicles()

See getListOfWorldElements()

Definition at line 170 of file World.h.

Constructor & Destructor Documentation

World::World ( )

Default ctor: inits an empty world.

Definition at line 22 of file World.cpp.

World::~World ( )

Dtor.

Definition at line 35 of file World.cpp.

Member Function Documentation

void World::clear_all ( bool  acquire_mt_lock = true)

Resets the entire

Definition at line 43 of file World.cpp.

void World::close_GUI ( )

a previous call to update_GUI()

Forces closing the GUI window, if any.

Definition at line 63 of file World_gui.cpp.

double mvsim::World::get_gravity ( ) const
inline

Gravity acceleration (Default=9.8 m/s^2). Used to evaluate weights for friction, etc.

Definition at line 113 of file World.h.

double mvsim::World::get_simul_time ( ) const
inline

Simulation wall-clock time.

Definition at line 99 of file World.h.

double mvsim::World::get_simul_timestep ( ) const
inline

Simulation fixed-time interval for numerical integration.

Definition at line 104 of file World.h.

b2Body* mvsim::World::getBox2DGroundBody ( )
inline

Definition at line 180 of file World.h.

b2World* mvsim::World::getBox2DWorld ( )
inline

Definition at line 178 of file World.h.

const b2World* mvsim::World::getBox2DWorld ( ) const
inline

Definition at line 179 of file World.h.

const TListBlocks& mvsim::World::getListOfBlocks ( ) const
inline

Definition at line 183 of file World.h.

TListBlocks& mvsim::World::getListOfBlocks ( )
inline

Definition at line 184 of file World.h.

const TListVehicles& mvsim::World::getListOfVehicles ( ) const
inline

Definition at line 181 of file World.h.

TListVehicles& mvsim::World::getListOfVehicles ( )
inline

Definition at line 182 of file World.h.

const TListWorldElements& mvsim::World::getListOfWorldElements ( ) const
inline

Definition at line 185 of file World.h.

CTimeLogger& mvsim::World::getTimeLogger ( )
inline

Definition at line 190 of file World.h.

void World::internal_one_timestep ( double  dt)
private

Runs one individual time step

Definition at line 109 of file World.cpp.

bool World::is_GUI_open ( ) const

Forces closing the GUI window, if any.

Return true if the GUI window is open, after

Definition at line 61 of file World_gui.cpp.

void World::load_from_XML ( const std::string &  xml_text,
const std::string &  fileNameForPath = std::string(".") 
)

simulation environment to an empty world. acquire_mt_lock determines whether to lock the multithreading semaphore before (set to false only if it's already acquired). Load an entire world description into this object from a specification in XML format.

Parameters
[in]fileNameForPathOptionally, provide the full path to an XML file from which to take relative paths.
Exceptions
std::exceptionOn any error, with what() giving a descriptive error message

Load an entire world description into this object from a specification in XML format.

Exceptions
std::exceptionOn any error, with what() giving a descriptive error message

Definition at line 38 of file World_load_xml.cpp.

virtual void mvsim::World::onNewObservation ( const VehicleBase veh,
const mrpt::slam::CObservation *  obs 
)
inlinevirtual

Definition at line 220 of file World.h.

std::string World::resolvePath ( const std::string &  s_in) const

Replace macros, prefix the base_path if input filename is relative, etc.

Definition at line 210 of file World.cpp.

void World::run_simulation ( double  dt)

Runs the simulation for a given time interval (in seconds)

Note
The minimum simulation time is the timestep set (e.g. via set_simul_timestep()), even if time advanced further than the provided "dt".

Runs the simulation for a given time interval (in seconds)

Definition at line 89 of file World.cpp.

void World::runVisitorOnVehicles ( VehicleVisitorBase v)

Run the user-provided visitor on each vehicle

Definition at line 240 of file World.cpp.

void World::runVisitorOnWorldElements ( WorldElementVisitorBase v)

Run the user-provided visitor on each world element

Definition at line 248 of file World.cpp.

void mvsim::World::set_gravity ( double  accel)
inline

Gravity acceleration (Default=9.8 m/s^2). Used to evaluate weights for friction, etc.

Definition at line 118 of file World.h.

void mvsim::World::set_simul_timestep ( double  timestep)
inline

Simulation fixed-time interval for numerical integration.

Definition at line 108 of file World.h.

void World::update_GUI ( TUpdateGUIParams guiparams = NULL)

Updates (or sets-up upon first call) the GUI visualization of the scene.

Parameters
[in,out]paramsOptional inputs/outputs to the GUI update process. See struct for details.
Note
This method is prepared to be called concurrently with the simulation, and doing so is recommended to assure a smooth multi-threading simulation.

Updates (or sets-up upon first call) the GUI visualization of the scene.

Note
This method is prepared to be called concurrently with the simulation, and doing so is recommended to assure a smooth multi-threading simulation.

Definition at line 68 of file World_gui.cpp.

Friends And Related Function Documentation

friend class Block
friend

Definition at line 235 of file World.h.

friend class VehicleBase
friend

Definition at line 234 of file World.h.

Member Data Documentation

b2Body* mvsim::World::m_b2_ground_body
private

Used to declare friction between vehicles-ground.

Definition at line 274 of file World.h.

int mvsim::World::m_b2d_pos_iters
private

Velocity and position iteration count (Box2D)

Definition at line 245 of file World.h.

int mvsim::World::m_b2d_vel_iters
private

integration.

Definition at line 245 of file World.h.

std::string mvsim::World::m_base_path
private

Path from which to take relative directories.

Definition at line 247 of file World.h.

TListBlocks mvsim::World::m_blocks
private

Definition at line 278 of file World.h.

b2World* mvsim::World::m_box2d_world
private

objects from multithreading access.

Box2D dynamic simulator instance

Definition at line 272 of file World.h.

double mvsim::World::m_gravity
private

Gravity acceleration (Default=9.8 m/s^2). Used to

Definition at line 238 of file World.h.

TGUI_Options mvsim::World::m_gui_options
private

Some of these options are only used the

Definition at line 265 of file World.h.

mrpt::gui::CDisplayWindow3D::Ptr mvsim::World::m_gui_win
private

Definition at line 284 of file World.h.

double mvsim::World::m_simul_time
private

evaluate weights for friction, etc.

In seconds, real simulation time since beginning

Definition at line 240 of file World.h.

double mvsim::World::m_simul_timestep
private

(may be different than wall-clock time because of time warp, etc.) Simulation fixed-time interval for numerical

Definition at line 243 of file World.h.

CTicTac mvsim::World::m_timer_iteration
private

Definition at line 287 of file World.h.

CTimeLogger mvsim::World::m_timlogger
private

Definition at line 286 of file World.h.

TListVehicles mvsim::World::m_vehicles
private

Definition at line 276 of file World.h.

std::mutex mvsim::World::m_world_cs
private

first time the GUI window is created.

The main semaphore to protect simulation

Definition at line 269 of file World.h.

TListWorldElements mvsim::World::m_world_elements
private

Definition at line 277 of file World.h.


The documentation for this class was generated from the following files:


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 19:36:41