#include <World.h>
Classes | |
struct | GUI |
struct | LightOptions |
struct | TGUI_Options |
struct | TGUIKeyEvent |
struct | TUpdateGUIParams |
struct | XmlParserContext |
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 > |
Public Member Functions | |
mvsim::Client & | commsClient () |
const mvsim::Client & | commsClient () const |
void | connectToServer () |
void | free_opengl_resources () |
bool | headless () const |
void | headless (bool setHeadless) |
auto & | physical_objects_mtx () |
bool | sensor_has_to_create_egl_context () |
const std::map< std::string, std::string > & | user_defined_variables () const |
Initialization, simulation set-up | |
World () | |
Default ctor: inits an empty world. More... | |
~World () | |
Dtor. More... | |
void | clear_all () |
void | load_from_XML_file (const std::string &xmlFileNamePath) |
void | internal_initialize () |
void | load_from_XML (const std::string &xml_text, const std::string &fileNameForPath=std::string(".")) |
Access inner working objects | |
std::unique_ptr< b2World > & | getBox2DWorld () |
const std::unique_ptr< b2World > & | getBox2DWorld () const |
b2Body * | getBox2DGroundBody () |
const VehicleList & | getListOfVehicles () const |
VehicleList & | getListOfVehicles () |
const BlockList & | getListOfBlocks () const |
BlockList & | getListOfBlocks () |
const WorldElementList & | getListOfWorldElements () const |
SimulableList & | getListOfSimulableObjects () |
Always lock/unlock getListOfSimulableObjectsMtx() before using this: More... | |
const SimulableList & | getListOfSimulableObjects () const |
auto & | getListOfSimulableObjectsMtx () |
mrpt::system::CTimeLogger & | getTimeLogger () |
std::string | local_to_abs_path (const std::string &in_path) const |
std::string | xmlPathToActualPath (const std::string &modelURI) const |
Private Types | |
using | xml_tag_parser_function_t = std::function< void(const XmlParserContext &)> |
Friends | |
class | Block |
class | VehicleBase |
Simulation execution | |
mrpt::opengl::CSetOfObjects::Ptr | guiUserObjectsPhysical_ |
mrpt::opengl::CSetOfObjects::Ptr | guiUserObjectsViz_ |
std::mutex | guiUserObjectsMtx_ |
std::mutex | pendingRunSensorsOn3DSceneMtx_ |
bool | pendingRunSensorsOn3DScene_ = false |
std::string | guiMsgLines_ |
std::mutex | guiMsgLinesMtx_ |
std::thread | gui_thread_ |
std::atomic_bool | gui_thread_running_ = false |
std::atomic_bool | simulator_must_close_ = false |
std::mutex | gui_thread_start_mtx_ |
std::vector< std::function< void(void)> > | guiUserPendingTasks_ |
std::mutex | guiUserPendingTasksMtx_ |
TGUIKeyEvent | lastKeyEvent_ |
std::atomic_bool | lastKeyEventValid_ = false |
std::mutex | lastKeyEventMtx_ |
double | get_simul_time () const |
void | force_set_simul_time (double newSimulatedTime) |
Normally should not be called by users, for internal use only. More... | |
mrpt::Clock::time_point | get_simul_timestamp () const |
double | get_simul_timestep () const |
Simulation fixed-time interval for numerical integration. More... | |
void | set_simul_timestep (double timestep) |
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 |
const mrpt::math::TPoint3D & | gui_mouse_point () const |
void | internalGraphicsLoopTasksForSimulation () |
void | internalRunSensorsOn3DScene (mrpt::opengl::COpenGLScene &physicalObjects) |
void | internalUpdate3DSceneObjects (mrpt::opengl::COpenGLScene &viz, mrpt::opengl::COpenGLScene &physical) |
void | internal_GUI_thread () |
void | internal_process_pending_gui_user_tasks () |
void | mark_as_pending_running_sensors_on_3D_scene () |
void | clear_pending_running_sensors_on_3D_scene () |
bool | pending_running_sensors_on_3D_scene () |
bool | simulator_must_close () const |
void | simulator_must_close (bool value) |
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 &)> |
using | block_visitor_t = std::function< void(Block &)> |
void | runVisitorOnVehicles (const vehicle_visitor_t &v) |
void | runVisitorOnWorldElements (const world_element_visitor_t &v) |
void | runVisitorOnBlocks (const block_visitor_t &v) |
Optional user hooks | |
using | on_observation_callback_t = std::function< void(const Simulable &, const mrpt::obs::CObservation::Ptr &)> |
void | registerCallbackOnObservation (const on_observation_callback_t &f) |
void | dispatchOnObservation (const Simulable &veh, const mrpt::obs::CObservation::Ptr &obs) |
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::block_visitor_t = std::function<void(Block&)> |
using mvsim::World::BlockList = std::multimap<std::string, Block::Ptr> |
Map 'block-name' => block object. See getListOfBlocks()
using mvsim::World::on_observation_callback_t = std::function<void( const Simulable& , const mrpt::obs::CObservation::Ptr& )> |
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> |
|
private |
void World::clear_all | ( | ) |
|
inline |
void World::close_GUI | ( | ) |
a previous call to update_GUI()
Forces closing the GUI window, if any.
Definition at line 52 of file World_gui.cpp.
|
inline |
|
inline |
void World::connectToServer | ( | ) |
|
inline |
|
inline |
|
inline |
Seconds since start of simulation.
|
inline |
Get the current simulation full timestamp, computed as the real wall clock timestamp at the beginning of the simulation, plus the number of seconds simulation has run.
double World::get_simul_timestep | ( | ) | const |
|
inline |
|
inline |
|
inline |
|
inline |
Always lock/unlock getListOfSimulableObjectsMtx() before using this:
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
private |
|
private |
Definition at line 190 of file World_services.cpp.
|
private |
Definition at line 985 of file World_gui.cpp.
|
private |
Definition at line 921 of file World_gui.cpp.
|
private |
Definition at line 940 of file World_gui.cpp.
|
private |
Definition at line 971 of file World_gui.cpp.
void World::internal_GUI_thread | ( | ) |
Definition at line 444 of file World_gui.cpp.
|
private |
void World::internal_process_pending_gui_user_tasks | ( | ) |
Definition at line 744 of file World_gui.cpp.
|
private |
This will parse a main XML file, or its included.
Definition at line 119 of file World_load_xml.cpp.
void World::internalGraphicsLoopTasksForSimulation | ( | ) |
Update 3D vehicles, sensors, run render-based sensors, etc: Called from World_gui thread in normal mode, or mvsim-cli in headless mode.
Definition at line 1036 of file World_gui.cpp.
void World::internalRunSensorsOn3DScene | ( | mrpt::opengl::COpenGLScene & | physicalObjects | ) |
Definition at line 757 of file World_gui.cpp.
void World::internalUpdate3DSceneObjects | ( | mrpt::opengl::COpenGLScene & | viz, |
mrpt::opengl::COpenGLScene & | physical | ||
) |
Definition at line 771 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 50 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 34 of file World_load_xml.cpp.
void World::load_from_XML_file | ( | const std::string & | xmlFileNamePath | ) |
Load an entire world description into this object from a specification in XML format.
[in] | xmlFileNamePath | The relative or full path to the XML file. |
std::exception | On any error, with what() giving a descriptive error message |
Definition at line 28 of file World_load_xml.cpp.
std::string World::local_to_abs_path | ( | const std::string & | s_in | ) | const |
Replace macros, prefix the base_path if input filename is relative, etc.
Replace macros, prefix the base_path if input filename is relative, etc.
|
inline |
|
private |
Definition at line 203 of file World_load_xml.cpp.
|
private |
Definition at line 210 of file World_load_xml.cpp.
|
private |
<element>
Definition at line 153 of file World_load_xml.cpp.
|
private |
Definition at line 282 of file World_load_xml.cpp.
|
private |
Definition at line 216 of file World_load_xml.cpp.
|
private |
Definition at line 321 of file World_load_xml.cpp.
|
private |
Definition at line 233 of file World_load_xml.cpp.
|
private |
Definition at line 222 of file World_load_xml.cpp.
|
private |
<sensor>
Definition at line 188 of file World_load_xml.cpp.
|
private |
Definition at line 263 of file World_load_xml.cpp.
|
private |
<vehicle>
Definition at line 164 of file World_load_xml.cpp.
|
private |
<vehicle:class>
Definition at line 182 of file World_load_xml.cpp.
|
private |
Definition at line 228 of file World_load_xml.cpp.
|
inline |
|
private |
Definition at line 122 of file World_walls.cpp.
|
private |
Definition at line 98 of file World_load_xml.cpp.
|
inlineprivate |
|
inlineprivate |
|
inline |
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::runVisitorOnBlocks | ( | const block_visitor_t & | v | ) |
void World::runVisitorOnVehicles | ( | const vehicle_visitor_t & | v | ) |
void World::runVisitorOnWorldElements | ( | const world_element_visitor_t & | v | ) |
|
inline |
|
inline |
|
private |
Changes the light source direction from azimuth and elevation angles (in radians)
Definition at line 1070 of file World_gui.cpp.
|
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 855 of file World_gui.cpp.
|
inline |
std::string World::xmlPathToActualPath | ( | const std::string & | modelURI | ) | const |
Parses URIs in all the forms explained in RemoteResourcesManager::resolve_path(), then passes it through local_to_abs_path().
|
friend |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
mrpt::opengl::CSetOfObjects::Ptr mvsim::World::guiUserObjectsPhysical_ |
mrpt::opengl::CSetOfObjects::Ptr mvsim::World::guiUserObjectsViz_ |
TGUIKeyEvent mvsim::World::lastKeyEvent_ |
|
private |
|
private |
|
mutableprivate |
|
private |
|
private |
|
private |
|
private |
std::atomic_bool mvsim::World::simulator_must_close_ = false |
|
private |
|
mutableprivate |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
3D scene with all visual objects (vehicles, obstacles, markers, etc.)
|
private |