The world provides access to all other object within a simulated environment. More...
#include <physics/physics.hh>
Inherits enable_shared_from_this< World >.
Public Member Functions | |
World (const std::string &_name="") | |
Constructor. More... | |
~World () | |
Destructor. More... | |
void | _AddDirty (Entity *_entity) |
void | _SetSensorsInitialized (const bool _init) |
physics::Atmosphere & | Atmosphere () const |
Get a reference to the atmosphere model used by the world. More... | |
bool | AtmosphereEnabled () const |
check if atmosphere model is enabled/disabled. More... | |
BasePtr | BaseByName (const std::string &_name) const |
Get an element by name. More... | |
void | Clear () |
Remove all entities from the world. More... | |
void | ClearModels () |
Remove all entities from the world. More... | |
void | DisableAllModels () |
Disable all links in all the models. More... | |
void | EnableAllModels () |
Enable all links in all the models. More... | |
EntityPtr | EntityBelowPoint (const ignition::math::Vector3d &_pt) const |
Get the nearest entity below a point. More... | |
EntityPtr | EntityByName (const std::string &_name) const |
Get a pointer to an Entity based on a name. More... | |
void | Fini () |
Finalize the world. More... | |
ignition::math::Vector3d | Gravity () const |
Return the gravity vector. More... | |
void | Init () |
Initialize the world. More... | |
void | InsertModelFile (const std::string &_sdfFilename) |
Insert a model from an SDF file. More... | |
void | InsertModelSDF (const sdf::SDF &_sdf) |
Insert a model using SDF. More... | |
void | InsertModelString (const std::string &_sdfString) |
Insert a model from an SDF string. More... | |
bool | IsLoaded () const |
Return true if the world has been loaded. More... | |
bool | IsPaused () const |
Returns the state of the simulation true if paused. More... | |
uint32_t | Iterations () const |
Get the total number of iterations. More... | |
LightPtr | LightByName (const std::string &_name) const |
Get a light by name. More... | |
unsigned int | LightCount () const |
Get the number of lights. More... | |
Light_V | Lights () const |
Get a list of all the lights. More... | |
void | Load (sdf::ElementPtr _sdf) |
Load the world using SDF parameters. More... | |
LightPtr | LoadLight (const sdf::ElementPtr &_sdf, const BasePtr &_parent) |
Load a light. More... | |
void | LoadPlugin (const std::string &_filename, const std::string &_name, sdf::ElementPtr _sdf) |
Load a plugin. More... | |
virtual ignition::math::Vector3d | MagneticField () const |
Return the magnetic field vector. More... | |
ModelPtr | ModelBelowPoint (const ignition::math::Vector3d &_pt) const |
Get the nearest model below and not encapsulating a point. More... | |
ModelPtr | ModelByIndex (const unsigned int _index) const |
Get a model based on an index. More... | |
ModelPtr | ModelByName (const std::string &_name) const |
Get a model by name. More... | |
unsigned int | ModelCount () const |
Get the number of models. More... | |
Model_V | Models () const |
Get a list of all the models. More... | |
std::string | Name () const |
Get the name of the world. More... | |
common::Time | PauseTime () const |
Get the amount of time simulation has been paused. More... | |
PhysicsEnginePtr | Physics () const |
Return the physics engine. More... | |
bool | PhysicsEnabled () const |
check if physics engine is enabled/disabled. More... | |
PresetManagerPtr | PresetMgr () const |
Return the preset manager. More... | |
void | PrintEntityTree () |
Print Entity tree. More... | |
void | PublishLightPose (const physics::LightPtr _light) |
Publish pose updates for a light. More... | |
void | PublishModelPose (physics::ModelPtr _model) |
Publish pose updates for a model. More... | |
void | PublishModelScale (physics::ModelPtr _model) |
Publish scale updates for a model. More... | |
common::Time | RealTime () const |
Get the real time (elapsed time). More... | |
void | RemoveModel (ModelPtr _model) |
Remove a model. More... | |
void | RemoveModel (const std::string &_name) |
Remove a model by name. More... | |
void | RemovePlugin (const std::string &_name) |
Remove a running plugin. More... | |
void | Reset () |
Reset time and model poses, configurations in simulation. More... | |
void | ResetEntities (Base::EntityType _type=Base::BASE) |
Reset with options. More... | |
void | ResetPhysicsStates () |
Reset the velocity, acceleration, force and torque of all child models. More... | |
void | ResetTime () |
Reset simulation time back to zero. More... | |
void | Run (const unsigned int _iterations=0) |
Run the world in a thread. More... | |
void | RunBlocking (const unsigned int _iterations=0) |
Run the world. More... | |
bool | Running () const |
Return the running state of the world. More... | |
void | Save (const std::string &_filename) |
Save a world to a file. More... | |
msgs::Scene | SceneMsg () const |
Get the current scene in message form. More... | |
const sdf::ElementPtr | SDF () |
Get the SDF of the world in the current state. More... | |
bool | SensorsInitialized () const |
Get whether sensors have been initialized. More... | |
void | SetAtmosphereEnabled (const bool _enable) |
enable/disable atmosphere model. More... | |
void | SetGravity (const ignition::math::Vector3d &_gravity) |
Set the gravity vector. More... | |
void | SetGravitySDF (const ignition::math::Vector3d &_gravity) |
Set the gravity sdf value. More... | |
void | SetMagneticField (const ignition::math::Vector3d &_mag) |
Set the magnetic field vector. More... | |
void | SetPaused (const bool _p) |
Set whether the simulation is paused. More... | |
void | SetPhysicsEnabled (const bool _enable) |
enable/disable physics engine during World::Update. More... | |
void | SetSimTime (const common::Time &_t) |
Set the sim time. More... | |
void | SetState (const WorldState &_state) |
Set the current world state. More... | |
void | SetWindEnabled (const bool _enable) |
enable/disable wind. More... | |
common::Time | SimTime () const |
Get the world simulation time, note if you want the PC wall clock call common::Time::GetWallTime. More... | |
common::SphericalCoordinatesPtr | SphericalCoords () const |
Return the spherical coordinates converter. More... | |
common::Time | StartTime () const |
Get the wall time simulation was started. More... | |
void | Step (const unsigned int _steps) |
Step the world forward in time. More... | |
void | Stop () |
Stop the world. More... | |
std::string | StripWorldName (const std::string &_name) const |
Return a version of the name with "<world_name>::" removed. More... | |
std::string | UniqueModelName (const std::string &_name) |
Get a model name which doesn't equal any existing model's name, by appending numbers to the given name. More... | |
void | UpdateStateSDF () |
Update the state SDF value from the current state. More... | |
common::URI | URI () const |
Return the URI of the world. More... | |
physics::Wind & | Wind () const |
Get a reference to the wind used by the world. More... | |
bool | WindEnabled () const |
check if wind is enabled/disabled. More... | |
std::mutex & | WorldPoseMutex () const |
Get the set world pose mutex. More... | |
The world provides access to all other object within a simulated environment.
The World is the container for all models and their components (links, joints, sensors, plugins, etc), and WorldPlugin instances. Many core function are also handled in the World, including physics update, model updates, and message processing.
|
explicit |
Constructor.
Constructor for the World. Must specify a unique name.
[in] | _name | Name of the world. |
~World | ( | ) |
Destructor.
void _AddDirty | ( | Entity * | _entity | ) |
void _SetSensorsInitialized | ( | const bool | _init | ) |
physics::Atmosphere& Atmosphere | ( | ) | const |
Get a reference to the atmosphere model used by the world.
bool AtmosphereEnabled | ( | ) | const |
check if atmosphere model is enabled/disabled.
True | if the atmosphere model is enabled. |
BasePtr BaseByName | ( | const std::string & | _name | ) | const |
Get an element by name.
Searches the list of entities, and return a pointer to the model with a matching _name.
[in] | _name | The name of the Model to find. |
void Clear | ( | ) |
Remove all entities from the world.
This function has delayed effect. Models are cleared at the end of the current update iteration.
void ClearModels | ( | ) |
Remove all entities from the world.
Implementation of World::Clear
void DisableAllModels | ( | ) |
Disable all links in all the models.
Disable is a physics concept. Disabling means that the physics engine should not update an entity.
void EnableAllModels | ( | ) |
Enable all links in all the models.
Enable is a physics concept. Enabling means that the physics engine should update an entity.
EntityPtr EntityBelowPoint | ( | const ignition::math::Vector3d & | _pt | ) | const |
Get the nearest entity below a point.
Projects a Ray down (-Z axis) starting at the given point. The first entity hit by the Ray is returned.
[in] | _pt | The 3D point to search below |
EntityPtr EntityByName | ( | const std::string & | _name | ) | const |
void Fini | ( | ) |
Finalize the world.
Call this function to tear-down the world.
ignition::math::Vector3d Gravity | ( | ) | const |
Return the gravity vector.
void Init | ( | ) |
Initialize the world.
This is called after Load.
void InsertModelFile | ( | const std::string & | _sdfFilename | ) |
Insert a model from an SDF file.
Spawns a model into the world base on and SDF file.
[in] | _sdfFilename | The name of the SDF file (including path). |
void InsertModelSDF | ( | const sdf::SDF & | _sdf | ) |
Insert a model using SDF.
Spawns a model into the world base on and SDF object.
[in] | _sdf | A reference to an SDF object. |
void InsertModelString | ( | const std::string & | _sdfString | ) |
Insert a model from an SDF string.
Spawns a model into the world base on and SDF string.
[in] | _sdfString | A string containing valid SDF markup. |
bool IsLoaded | ( | ) | const |
Return true if the world has been loaded.
bool IsPaused | ( | ) | const |
Returns the state of the simulation true if paused.
uint32_t Iterations | ( | ) | const |
Get the total number of iterations.
LightPtr LightByName | ( | const std::string & | _name | ) | const |
Get a light by name.
This function is the same as BaseByName(), but limits the search to only lights.
[in] | _name | The name of the Light to find. |
unsigned int LightCount | ( | ) | const |
Get the number of lights.
Light_V Lights | ( | ) | const |
Get a list of all the lights.
void Load | ( | sdf::ElementPtr | _sdf | ) |
Load the world using SDF parameters.
Load a world from and SDF pointer.
[in] | _sdf | SDF parameters. |
void LoadPlugin | ( | const std::string & | _filename, |
const std::string & | _name, | ||
sdf::ElementPtr | _sdf | ||
) |
Load a plugin.
[in] | _filename | The filename of the plugin. |
[in] | _name | A unique name for the plugin. |
[in] | _sdf | The SDF to pass into the plugin. |
|
virtual |
Return the magnetic field vector.
ModelPtr ModelBelowPoint | ( | const ignition::math::Vector3d & | _pt | ) | const |
Get the nearest model below and not encapsulating a point.
Only objects below the start point can be returned. Any object that encapsulates the start point can not be returned from this function. This function makes use of World::GetEntityBelowPoint.
[in] | _pt | The 3D point to search below. |
ModelPtr ModelByIndex | ( | const unsigned int | _index | ) | const |
Get a model based on an index.
Get a Model using an index, where index must be greater than zero and less than World::ModelCount()
[in] | _index | The index of the model [0..GetModelCount) |
ModelPtr ModelByName | ( | const std::string & | _name | ) | const |
unsigned int ModelCount | ( | ) | const |
Get the number of models.
Model_V Models | ( | ) | const |
Get a list of all the models.
std::string Name | ( | ) | const |
Get the name of the world.
common::Time PauseTime | ( | ) | const |
Get the amount of time simulation has been paused.
PhysicsEnginePtr Physics | ( | ) | const |
Return the physics engine.
Get a pointer to the physics engine used by the world.
bool PhysicsEnabled | ( | ) | const |
check if physics engine is enabled/disabled.
True | if the physics engine is enabled. |
PresetManagerPtr PresetMgr | ( | ) | const |
Return the preset manager.
void PrintEntityTree | ( | ) |
Print Entity tree.
Prints alls the entities to stdout.
void PublishLightPose | ( | const physics::LightPtr | _light | ) |
Publish pose updates for a light.
Adds light to a list of lights to publish, which is processed and cleared once every iteration.
[in] | _light | Pointer to the light to publish. |
void PublishModelPose | ( | physics::ModelPtr | _model | ) |
Publish pose updates for a model.
This list of models to publish is processed and cleared once every iteration.
[in] | _model | Pointer to the model to publish. |
void PublishModelScale | ( | physics::ModelPtr | _model | ) |
Publish scale updates for a model.
This list of models to publish is processed and cleared once every iteration.
[in] | _model | Pointer to the model to publish. |
common::Time RealTime | ( | ) | const |
Get the real time (elapsed time).
void RemoveModel | ( | ModelPtr | _model | ) |
Remove a model.
This function will block until the physics engine is not locked. The duration of the block is less than the time to complete a simulation iteration.
[in] | _model | Pointer to a model to remove. |
void RemoveModel | ( | const std::string & | _name | ) |
Remove a model by name.
This function will block until the physics engine is not locked. The duration of the block is less than the time to complete a simulation iteration.
[in] | _name | Name of the model to remove. |
void RemovePlugin | ( | const std::string & | _name | ) |
Remove a running plugin.
[in] | _name | The unique name of the plugin to remove. |
void Reset | ( | ) |
Reset time and model poses, configurations in simulation.
void ResetEntities | ( | Base::EntityType | _type = Base::BASE | ) |
Reset with options.
The _type parameter specifies which type of eneities to reset. See Base::EntityType.
[in] | _type | The type of reset. |
void ResetPhysicsStates | ( | ) |
Reset the velocity, acceleration, force and torque of all child models.
void ResetTime | ( | ) |
Reset simulation time back to zero.
void Run | ( | const unsigned int | _iterations = 0 | ) |
Run the world in a thread.
Run the update loop.
[in] | _iterations | Run for this many iterations, then stop. A value of zero disables run stop. |
void RunBlocking | ( | const unsigned int | _iterations = 0 | ) |
Run the world.
This call blocks. Run the update loop.
[in] | _iterations | Run for this many iterations, then stop. A value of zero disables run stop. |
bool Running | ( | ) | const |
Return the running state of the world.
void Save | ( | const std::string & | _filename | ) |
Save a world to a file.
Save the current world and its state to a file.
[in] | _filename | Name of the file to save into. |
msgs::Scene SceneMsg | ( | ) | const |
Get the current scene in message form.
const sdf::ElementPtr SDF | ( | ) |
Get the SDF of the world in the current state.
bool SensorsInitialized | ( | ) | const |
Get whether sensors have been initialized.
void SetAtmosphereEnabled | ( | const bool | _enable | ) |
enable/disable atmosphere model.
[in] | _enable | True to enable the atmosphere model. |
void SetGravity | ( | const ignition::math::Vector3d & | _gravity | ) |
Set the gravity vector.
[in] | _gravity | New gravity vector. |
void SetGravitySDF | ( | const ignition::math::Vector3d & | _gravity | ) |
Set the gravity sdf value.
[in] | _gravity | New gravity vector. |
void SetMagneticField | ( | const ignition::math::Vector3d & | _mag | ) |
Set the magnetic field vector.
[in] | _mag | New magnetic field vector. |
void SetPaused | ( | const bool | _p | ) |
Set whether the simulation is paused.
[in] | _p | True pauses the simulation. False runs the simulation. |
void SetPhysicsEnabled | ( | const bool | _enable | ) |
enable/disable physics engine during World::Update.
[in] | _enable | True to enable the physics engine. |
void SetSimTime | ( | const common::Time & | _t | ) |
Set the sim time.
[in] | _t | The new simulation time |
void SetState | ( | const WorldState & | _state | ) |
Set the current world state.
_state | The state to set the World to. |
void SetWindEnabled | ( | const bool | _enable | ) |
enable/disable wind.
[in] | _enable | True to enable the wind. |
common::Time SimTime | ( | ) | const |
Get the world simulation time, note if you want the PC wall clock call common::Time::GetWallTime.
common::SphericalCoordinatesPtr SphericalCoords | ( | ) | const |
Return the spherical coordinates converter.
common::Time StartTime | ( | ) | const |
Get the wall time simulation was started.
void Step | ( | const unsigned int | _steps | ) |
Step the world forward in time.
[in] | _steps | The number of steps the World should take. |
void Stop | ( | ) |
Stop the world.
Stop the update loop.
std::string StripWorldName | ( | const std::string & | _name | ) | const |
Return a version of the name with "<world_name>::" removed.
[in] | _name | Usually the name of an entity. |
std::string UniqueModelName | ( | const std::string & | _name | ) |
Get a model name which doesn't equal any existing model's name, by appending numbers to the given name.
If _name is already unique, the returned value is the same.
[in] | _name | Desired model name. |
void UpdateStateSDF | ( | ) |
Update the state SDF value from the current state.
common::URI URI | ( | ) | const |
Return the URI of the world.
physics::Wind& Wind | ( | ) | const |
Get a reference to the wind used by the world.
bool WindEnabled | ( | ) | const |
check if wind is enabled/disabled.
True | if the wind is enabled. |
std::mutex& WorldPoseMutex | ( | ) | const |
Get the set world pose mutex.