Classes | Private Member Functions | Private Attributes | Friends
mvsim::World Class Reference

#include <World.h>

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

List of all members.

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()
typedef std::multimap
< std::string, Block * > 
TListBlocks

Public Member Functions

Initialization, simulation set-up
 World ()
 Default ctor: inits an empty world.
 ~World ()
 Dtor.
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.
double get_simul_timestep () const
 Simulation fixed-time interval for numerical integration.
void set_simul_timestep (double timestep)
 Simulation fixed-time interval for numerical integration.
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.
void close_GUI ()
 a previous call to update_GUI()
Access inner working objects
b2WorldgetBox2DWorld ()
const b2WorldgetBox2DWorld () const
b2BodygetBox2DGroundBody ()
const TListVehiclesgetListOfVehicles () const
TListVehiclesgetListOfVehicles ()
const TListBlocksgetListOfBlocks () const
TListBlocksgetListOfBlocks ()
const TListWorldElementsgetListOfWorldElements () const
mrpt::utils::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.
int m_b2d_pos_iters
 Velocity and position iteration count (Box2D)
int m_b2d_vel_iters
 integration.
std::string m_base_path
 Path from which to take relative directories.
TListBlocks m_blocks
b2Worldm_box2d_world
 objects from multithreading access.
double m_gravity
TGUI_Options m_gui_options
mrpt::gui::CDisplayWindow3D::Ptr m_gui_win
double m_simul_time
 evaluate weights for friction, etc.
double m_simul_timestep
mrpt::utils::CTicTac m_timer_iteration
mrpt::utils::CTimeLogger m_timlogger
TListVehicles m_vehicles
std::mutex m_world_cs
 first time the GUI window is created.
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 39 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 144 of file World.h.

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

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

Definition at line 139 of file World.h.

getListOfVehicles()

See getListOfWorldElements()

Definition at line 142 of file World.h.


Constructor & Destructor Documentation

Default ctor: inits an empty world.

Definition at line 23 of file World.cpp.

Dtor.

Definition at line 36 of file World.cpp.


Member Function Documentation

void World::clear_all ( bool  acquire_mt_lock = true)

Resets the entire

Definition at line 44 of file World.cpp.

void World::close_GUI ( )

a previous call to update_GUI()

Forces closing the GUI window, if any.

Definition at line 56 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 85 of file World.h.

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

Simulation wall-clock time.

Definition at line 71 of file World.h.

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

Simulation fixed-time interval for numerical integration.

Definition at line 76 of file World.h.

Definition at line 152 of file World.h.

Definition at line 150 of file World.h.

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

Definition at line 151 of file World.h.

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

Definition at line 155 of file World.h.

Definition at line 156 of file World.h.

Definition at line 153 of file World.h.

Definition at line 154 of file World.h.

Definition at line 157 of file World.h.

mrpt::utils::CTimeLogger& mvsim::World::getTimeLogger ( ) [inline]

Definition at line 162 of file World.h.

void World::internal_one_timestep ( double  dt) [private]

Runs one individual time step

Definition at line 110 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 54 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 33 of file World_load_xml.cpp.

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

Definition at line 192 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 211 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 90 of file World.cpp.

Run the user-provided visitor on each vehicle

Definition at line 241 of file World.cpp.

Run the user-provided visitor on each world element

Definition at line 249 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 90 of file World.h.

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

Simulation fixed-time interval for numerical integration.

Definition at line 80 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:
inout]params Optional 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 61 of file World_gui.cpp.


Friends And Related Function Documentation

friend class Block [friend]

Definition at line 207 of file World.h.

friend class VehicleBase [friend]

Definition at line 206 of file World.h.


Member Data Documentation

Used to declare friction between vehicles-ground.

Definition at line 246 of file World.h.

Velocity and position iteration count (Box2D)

Definition at line 217 of file World.h.

integration.

Definition at line 217 of file World.h.

std::string mvsim::World::m_base_path [private]

Path from which to take relative directories.

Definition at line 219 of file World.h.

Definition at line 250 of file World.h.

objects from multithreading access.

Box2D dynamic simulator instance

Definition at line 244 of file World.h.

double mvsim::World::m_gravity [private]

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

Definition at line 210 of file World.h.

Some of these options are only used the

Definition at line 237 of file World.h.

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

Definition at line 256 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 212 of file World.h.

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

Definition at line 215 of file World.h.

mrpt::utils::CTicTac mvsim::World::m_timer_iteration [private]

Definition at line 259 of file World.h.

mrpt::utils::CTimeLogger mvsim::World::m_timlogger [private]

Definition at line 258 of file World.h.

Definition at line 248 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 241 of file World.h.

Definition at line 249 of file World.h.


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


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