#include <World.h>
Classes | |
struct | GUI |
struct | TGUI_Options |
struct | TGUIKeyEvent |
struct | TUpdateGUIParams |
Public Types | |
Public types | |
using | VehicleList = std::multimap< std::string, VehicleBase::Ptr > |
using | WorldElementList = std::list< WorldElementBase::Ptr > |
using | BlockList = std::multimap< std::string, Block::Ptr > |
using | SimulableList = std::multimap< std::string, Simulable::Ptr > |
Private Member Functions | |
void | insertBlock (const Block::Ptr &block) |
void | internal_one_timestep (double dt) |
void | process_load_walls (const rapidxml::xml_node< char > &node) |
Private Attributes | |
b2Body * | m_b2_ground_body = nullptr |
int | m_b2d_pos_iters = 3 |
int | m_b2d_vel_iters = 6 |
std::string | m_base_path {"."} |
BlockList | m_blocks |
std::unique_ptr< b2World > | m_box2d_world |
mvsim::Client | m_client {"World"} |
double | m_gravity = 9.81 |
GUI | m_gui {*this} |
gui state More... | |
TGUI_Options | m_gui_options |
const TParameterDefinitions | m_other_world_params |
double | m_simul_time = 0 |
double | m_simul_timestep = 10e-3 |
SimulableList | m_simulableObjects |
std::mutex | m_simulationStepRunningMtx |
mrpt::system::CTicTac | m_timer_iteration |
mrpt::system::CTimeLogger | m_timlogger |
VehicleList | m_vehicles |
std::recursive_mutex | m_world_cs |
first time the GUI window is created. More... | |
WorldElementList | m_world_elements |
Friends | |
class | Block |
class | VehicleBase |
Simulation execution | |
std::string | m_gui_msg_lines |
std::mutex | m_gui_msg_lines_mtx |
std::thread | m_gui_thread |
std::atomic_bool | m_gui_thread_running = false |
std::atomic_bool | m_gui_thread_must_close = false |
std::mutex | m_gui_thread_start_mtx |
std::vector< std::function< void(void)> > | m_gui_user_pending_tasks |
std::mutex | m_gui_user_pending_tasks_mtx |
TGUIKeyEvent | m_lastKeyEvent |
std::atomic_bool | m_lastKeyEventValid = false |
std::mutex | m_lastKeyEvent_mtx |
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=nullptr) |
const mrpt::gui::CDisplayWindowGUI::Ptr & | gui_window () const |
void | internalUpdate3DSceneObjects (mrpt::opengl::COpenGLScene::Ptr &gl_scene) |
void | internal_GUI_thread () |
void | internal_process_pending_gui_user_tasks () |
void | enqueue_task_to_run_in_gui_thread (const std::function< void(void)> &f) |
bool | is_GUI_open () const |
Forces closing the GUI window, if any. More... | |
void | close_GUI () |
a previous call to update_GUI() More... | |
Visitors API | |
using | vehicle_visitor_t = std::function< void(VehicleBase &)> |
using | world_element_visitor_t = std::function< void(WorldElementBase &)> |
void | runVisitorOnVehicles (const vehicle_visitor_t &v) |
void | runVisitorOnWorldElements (const world_element_visitor_t &v) |
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.
See: https://mvsimulator.readthedocs.io/en/latest/world.html
using mvsim::World::BlockList = std::multimap<std::string, Block::Ptr> |
Map 'block-name' => block object. See getListOfBlocks()
using mvsim::World::SimulableList = std::multimap<std::string, Simulable::Ptr> |
using mvsim::World::vehicle_visitor_t = std::function<void(VehicleBase&)> |
using mvsim::World::VehicleList = std::multimap<std::string, VehicleBase::Ptr> |
Map 'vehicle-name' => vehicle object. See getListOfVehicles()
using mvsim::World::world_element_visitor_t = std::function<void(WorldElementBase&)> |
using mvsim::World::WorldElementList = std::list<WorldElementBase::Ptr> |
void World::clear_all | ( | ) |
void World::close_GUI | ( | ) |
a previous call to update_GUI()
Forces closing the GUI window, if any.
Definition at line 44 of file World_gui.cpp.
|
inline |
|
inline |
void World::connectToServer | ( | ) |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
private |
void World::internal_GUI_thread | ( | ) |
Definition at line 339 of file World_gui.cpp.
|
private |
void World::internal_process_pending_gui_user_tasks | ( | ) |
Definition at line 536 of file World_gui.cpp.
void World::internalUpdate3DSceneObjects | ( | mrpt::opengl::COpenGLScene::Ptr & | gl_scene | ) |
Definition at line 549 of file World_gui.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 42 of file World_gui.cpp.
void World::load_from_XML | ( | const std::string & | xml_text, |
const std::string & | fileNameForPath = std::string(".") |
||
) |
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 |
Definition at line 28 of file World_load_xml.cpp.
|
inlinevirtual |
|
private |
Definition at line 122 of file World_walls.cpp.
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 | ( | const vehicle_visitor_t & | v | ) |
void World::runVisitorOnWorldElements | ( | const world_element_visitor_t & | v | ) |
|
inline |
|
inline |
void World::update_GUI | ( | TUpdateGUIParams * | params = nullptr | ) |
Updates (or sets-up upon first call) the GUI visualization of the scene.
[in,out] | params | Optional inputs/outputs to the GUI update process. See struct for details. |
Definition at line 633 of file World_gui.cpp.
std::string World::xmlPathToActualPath | ( | const std::string & | modelURI | ) | const |
|
friend |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
std::string mvsim::World::m_gui_msg_lines |
|
private |
std::atomic_bool mvsim::World::m_gui_thread_must_close = false |
TGUIKeyEvent mvsim::World::m_lastKeyEvent |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |