#include <World.h>
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 | |
b2World * | getBox2DWorld () |
const b2World * | getBox2DWorld () const |
b2Body * | getBox2DGroundBody () |
const TListVehicles & | getListOfVehicles () const |
TListVehicles & | getListOfVehicles () |
const TListBlocks & | getListOfBlocks () const |
TListBlocks & | getListOfBlocks () |
const TListWorldElements & | getListOfWorldElements () 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 | |
b2Body * | m_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 |
b2World * | m_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 |
CTicTac | m_timer_iteration |
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 |
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.
typedef std::multimap<std::string, Block*> mvsim::World::TListBlocks |
typedef std::multimap<std::string, VehicleBase*> mvsim::World::TListVehicles |
typedef std::list<WorldElementBase*> mvsim::World::TListWorldElements |
World::World | ( | ) |
World::~World | ( | ) |
void World::clear_all | ( | bool | acquire_mt_lock = true | ) |
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] |
double mvsim::World::get_simul_time | ( | ) | const [inline] |
double mvsim::World::get_simul_timestep | ( | ) | const [inline] |
b2Body* mvsim::World::getBox2DGroundBody | ( | ) | [inline] |
b2World* mvsim::World::getBox2DWorld | ( | ) | [inline] |
const b2World* mvsim::World::getBox2DWorld | ( | ) | const [inline] |
const TListBlocks& mvsim::World::getListOfBlocks | ( | ) | const [inline] |
TListBlocks& mvsim::World::getListOfBlocks | ( | ) | [inline] |
const TListVehicles& mvsim::World::getListOfVehicles | ( | ) | const [inline] |
TListVehicles& mvsim::World::getListOfVehicles | ( | ) | [inline] |
const TListWorldElements& mvsim::World::getListOfWorldElements | ( | ) | const [inline] |
CTimeLogger& mvsim::World::getTimeLogger | ( | ) | [inline] |
void World::internal_one_timestep | ( | double | dt | ) | [private] |
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.
[in] | fileNameForPath | Optionally, provide the full path to an XML file from which to take relative paths. |
std::exception | On any error, with what() giving a descriptive error message |
Load an entire world description into this object from a specification in XML format.
std::exception | On 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 | ||
) | [inline, virtual] |
std::string World::resolvePath | ( | const std::string & | s_in | ) | const |
void World::run_simulation | ( | double | dt | ) |
Runs the simulation for a given time interval (in seconds)
Runs the simulation for a given time interval (in seconds)
void World::runVisitorOnVehicles | ( | VehicleVisitorBase & | v | ) |
void mvsim::World::set_gravity | ( | double | accel | ) | [inline] |
void mvsim::World::set_simul_timestep | ( | double | timestep | ) | [inline] |
void World::update_GUI | ( | TUpdateGUIParams * | guiparams = NULL | ) |
Updates (or sets-up upon first call) the GUI visualization of the scene.
inout] | params Optional inputs/outputs to the GUI update process. See struct for details. |
Updates (or sets-up upon first call) the GUI visualization of the scene.
Definition at line 68 of file World_gui.cpp.
friend class VehicleBase [friend] |
b2Body* mvsim::World::m_b2_ground_body [private] |
int mvsim::World::m_b2d_pos_iters [private] |
int mvsim::World::m_b2d_vel_iters [private] |
std::string mvsim::World::m_base_path [private] |
TListBlocks mvsim::World::m_blocks [private] |
b2World* mvsim::World::m_box2d_world [private] |
double mvsim::World::m_gravity [private] |
TGUI_Options mvsim::World::m_gui_options [private] |
mrpt::gui::CDisplayWindow3D::Ptr mvsim::World::m_gui_win [private] |
double mvsim::World::m_simul_time [private] |
double mvsim::World::m_simul_timestep [private] |
CTicTac mvsim::World::m_timer_iteration [private] |
CTimeLogger mvsim::World::m_timlogger [private] |
TListVehicles mvsim::World::m_vehicles [private] |
std::mutex mvsim::World::m_world_cs [private] |