Public Member Functions | List of all members
gazebo::physics::World Class Reference

The world provides access to all other object within a simulated environment. More...

#include <physics/physics.hh>

Inheritance diagram for gazebo::physics::World:
Inheritance graph
[legend]

Public Member Functions

 World (const std::string &_name="")
 Constructor. More...
 
 ~World ()
 Destructor. More...
 
void _AddDirty (Entity *_entity)
 
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...
 
void EnablePhysicsEngine (bool _enable)
 enable/disable physics engine during World::Update. More...
 
void Fini ()
 Finalize the world. More...
 
BasePtr GetByName (const std::string &_name)
 Get an element by name. More...
 
bool GetEnablePhysicsEngine ()
 check if physics engine is enabled/disabled. More...
 
EntityPtr GetEntity (const std::string &_name)
 Get a pointer to an Entity based on a name. More...
 
EntityPtr GetEntityBelowPoint (const math::Vector3 &_pt)
 Get the nearest entity below a point. More...
 
uint32_t GetIterations () const
 Get the total number of iterations. More...
 
ModelPtr GetModel (unsigned int _index) const
 Get a model based on an index. More...
 
ModelPtr GetModel (const std::string &_name)
 Get a model by name. More...
 
ModelPtr GetModelBelowPoint (const math::Vector3 &_pt)
 Get the nearest model below and not encapsulating a point. More...
 
unsigned int GetModelCount () const
 Get the number of models. More...
 
Model_V GetModels () const
 Get a list of all the models. More...
 
std::string GetName () const
 Get the name of the world. More...
 
common::Time GetPauseTime () const
 Get the amount of time simulation has been paused. More...
 
PhysicsEnginePtr GetPhysicsEngine () const
 Return the physics engine. More...
 
PresetManagerPtr GetPresetManager () const
 Return the preset manager. More...
 
common::Time GetRealTime () const
 Get the real time (elapsed time). More...
 
bool GetRunning () const
 Return the running state of the world. More...
 
msgs::Scene GetSceneMsg () const
 Get the current scene in message form. More...
 
boost::mutex * GetSetWorldPoseMutex () const
 Get the set world pose mutex. More...
 
common::Time GetSimTime () const
 Get the world simulation time, note if you want the PC wall clock call common::Time::GetWallTime. More...
 
common::SphericalCoordinatesPtr GetSphericalCoordinates () const
 Return the spherical coordinates converter. More...
 
common::Time GetStartTime () const
 Get the wall time simulation was started. 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...
 
void Load (sdf::ElementPtr _sdf)
 Load the world using SDF parameters. More...
 
void LoadPlugin (const std::string &_filename, const std::string &_name, sdf::ElementPtr _sdf)
 Load a plugin. More...
 
void PrintEntityTree ()
 Print Entity tree. More...
 
void PublishModelPose (physics::ModelPtr _model)
 Publish pose updates for a model. 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 ResetTime ()
 Reset simulation time back to zero. More...
 
void Run (unsigned int _iterations=0)
 Run the world in a thread. More...
 
void RunBlocking (unsigned int _iterations=0)
 Run the world. More...
 
void Save (const std::string &_filename)
 Save a world to a file. More...
 
void SetPaused (bool _p)
 Set whether the simulation is paused. More...
 
void SetSimTime (const common::Time &_t)
 Set the sim time. More...
 
void SetState (const WorldState &_state)
 Set the current world state. More...
 
void Step (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...
 
void UpdateStateSDF ()
 Update the state SDF value from the current state. More...
 

Detailed Description

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.

Constructor & Destructor Documentation

gazebo::physics::World::World ( const std::string &  _name = "")
explicit

Constructor.

Constructor for the World. Must specify a unique name.

Parameters
[in]_nameName of the world.
gazebo::physics::World::~World ( )

Destructor.

Member Function Documentation

void gazebo::physics::World::_AddDirty ( Entity _entity)
void gazebo::physics::World::Clear ( )

Remove all entities from the world.

This function has delayed effect. Models are cleared at the end of the current update iteration.

void gazebo::physics::World::ClearModels ( )

Remove all entities from the world.

Implementation of World::Clear

void gazebo::physics::World::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 gazebo::physics::World::EnableAllModels ( )

Enable all links in all the models.

Enable is a physics concept. Enabling means that the physics engine should update an entity.

void gazebo::physics::World::EnablePhysicsEngine ( bool  _enable)

enable/disable physics engine during World::Update.

Parameters
[in]_enableTrue to enable the physics engine.
void gazebo::physics::World::Fini ( )

Finalize the world.

Call this function to tear-down the world.

BasePtr gazebo::physics::World::GetByName ( const std::string &  _name)

Get an element by name.

Searches the list of entities, and return a pointer to the model with a matching _name.

Parameters
[in]_nameThe name of the Model to find.
Returns
A pointer to the entity, or NULL if no entity was found.
bool gazebo::physics::World::GetEnablePhysicsEngine ( )

check if physics engine is enabled/disabled.

Parameters
Trueif the physics engine is enabled.
EntityPtr gazebo::physics::World::GetEntity ( const std::string &  _name)

Get a pointer to an Entity based on a name.

This function is the same as GetByName, but limits the search to only Entities.

Parameters
[in]_nameThe name of the Entity to find.
Returns
A pointer to the Entity, or NULL if no Entity was found.
EntityPtr gazebo::physics::World::GetEntityBelowPoint ( const math::Vector3 _pt)

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.

Parameters
[in]_ptThe 3D point to search below
Returns
A pointer to nearest Entity, NULL if none is found.
uint32_t gazebo::physics::World::GetIterations ( ) const

Get the total number of iterations.

Returns
Number of iterations that simulation has taken.
ModelPtr gazebo::physics::World::GetModel ( 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::GetModelCount()

Parameters
[in]_indexThe index of the model [0..GetModelCount)
Returns
A pointer to the Model. NULL if _index is invalid.
ModelPtr gazebo::physics::World::GetModel ( const std::string &  _name)

Get a model by name.

This function is the same as GetByName, but limits the search to only models.

Parameters
[in]_nameThe name of the Model to find.
Returns
A pointer to the Model, or NULL if no model was found.
ModelPtr gazebo::physics::World::GetModelBelowPoint ( const math::Vector3 _pt)

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.

Parameters
[in]_ptThe 3D point to search below.
Returns
A pointer to nearest Model, NULL if none is found.
unsigned int gazebo::physics::World::GetModelCount ( ) const

Get the number of models.

Returns
The number of models in the World.
Model_V gazebo::physics::World::GetModels ( ) const

Get a list of all the models.

Returns
A list of all the Models in the world.
std::string gazebo::physics::World::GetName ( ) const

Get the name of the world.

Returns
The name of the world.
common::Time gazebo::physics::World::GetPauseTime ( ) const

Get the amount of time simulation has been paused.

Returns
The pause time.
PhysicsEnginePtr gazebo::physics::World::GetPhysicsEngine ( ) const

Return the physics engine.

Get a pointer to the physics engine used by the world.

Returns
Pointer to the physics engine.
PresetManagerPtr gazebo::physics::World::GetPresetManager ( ) const

Return the preset manager.

Returns
Pointer to the preset manager.
common::Time gazebo::physics::World::GetRealTime ( ) const

Get the real time (elapsed time).

Returns
The real time.
bool gazebo::physics::World::GetRunning ( ) const

Return the running state of the world.

Returns
True if the world is running.
msgs::Scene gazebo::physics::World::GetSceneMsg ( ) const

Get the current scene in message form.

Returns
The scene state as a protobuf message.
boost::mutex* gazebo::physics::World::GetSetWorldPoseMutex ( ) const

Get the set world pose mutex.

Returns
Pointer to the mutex.
common::Time gazebo::physics::World::GetSimTime ( ) const

Get the world simulation time, note if you want the PC wall clock call common::Time::GetWallTime.

Returns
The current simulation time
common::SphericalCoordinatesPtr gazebo::physics::World::GetSphericalCoordinates ( ) const

Return the spherical coordinates converter.

Returns
Pointer to the spherical coordinates converter.
common::Time gazebo::physics::World::GetStartTime ( ) const

Get the wall time simulation was started.

Returns
The start time.
void gazebo::physics::World::Init ( )

Initialize the world.

This is called after Load.

void gazebo::physics::World::InsertModelFile ( const std::string &  _sdfFilename)

Insert a model from an SDF file.

Spawns a model into the world base on and SDF file.

Parameters
[in]_sdfFilenameThe name of the SDF file (including path).
void gazebo::physics::World::InsertModelSDF ( const sdf::SDF &  _sdf)

Insert a model using SDF.

Spawns a model into the world base on and SDF object.

Parameters
[in]_sdfA reference to an SDF object.
void gazebo::physics::World::InsertModelString ( const std::string &  _sdfString)

Insert a model from an SDF string.

Spawns a model into the world base on and SDF string.

Parameters
[in]_sdfStringA string containing valid SDF markup.
bool gazebo::physics::World::IsLoaded ( ) const

Return true if the world has been loaded.

Returns
True if World::Load has completed.
bool gazebo::physics::World::IsPaused ( ) const

Returns the state of the simulation true if paused.

Returns
True if paused.
void gazebo::physics::World::Load ( sdf::ElementPtr  _sdf)

Load the world using SDF parameters.

Load a world from and SDF pointer.

Parameters
[in]_sdfSDF parameters.
void gazebo::physics::World::LoadPlugin ( const std::string &  _filename,
const std::string &  _name,
sdf::ElementPtr  _sdf 
)

Load a plugin.

Parameters
[in]_filenameThe filename of the plugin.
[in]_nameA unique name for the plugin.
[in]_sdfThe SDF to pass into the plugin.
void gazebo::physics::World::PrintEntityTree ( )

Print Entity tree.

Prints alls the entities to stdout.

void gazebo::physics::World::PublishModelPose ( physics::ModelPtr  _model)

Publish pose updates for a model.

This list of models to publish is processed and cleared once every iteration.

Parameters
[in]_modelPointer to the model to publish.
void gazebo::physics::World::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.

Parameters
[in]_modelPointer to a model to remove.
void gazebo::physics::World::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.

Parameters
[in]_nameName of the model to remove.
void gazebo::physics::World::RemovePlugin ( const std::string &  _name)

Remove a running plugin.

Parameters
[in]_nameThe unique name of the plugin to remove.
void gazebo::physics::World::Reset ( )

Reset time and model poses, configurations in simulation.

void gazebo::physics::World::ResetEntities ( Base::EntityType  _type = Base::BASE)

Reset with options.

The _type parameter specifies which type of eneities to reset. See Base::EntityType.

Parameters
[in]_typeThe type of reset.
void gazebo::physics::World::ResetTime ( )

Reset simulation time back to zero.

void gazebo::physics::World::Run ( unsigned int  _iterations = 0)

Run the world in a thread.

Run the update loop.

Parameters
[in]_iterationsRun for this many iterations, then stop. A value of zero disables run stop.
void gazebo::physics::World::RunBlocking ( unsigned int  _iterations = 0)

Run the world.

This call blocks. Run the update loop.

Parameters
[in]_iterationsRun for this many iterations, then stop. A value of zero disables run stop.
void gazebo::physics::World::Save ( const std::string &  _filename)

Save a world to a file.

Save the current world and its state to a file.

Parameters
[in]_filenameName of the file to save into.
void gazebo::physics::World::SetPaused ( bool  _p)

Set whether the simulation is paused.

Parameters
[in]_pTrue pauses the simulation. False runs the simulation.
void gazebo::physics::World::SetSimTime ( const common::Time _t)

Set the sim time.

Parameters
[in]_tThe new simulation time
void gazebo::physics::World::SetState ( const WorldState _state)

Set the current world state.

Parameters
_stateThe state to set the World to.
void gazebo::physics::World::Step ( unsigned int  _steps)

Step the world forward in time.

Parameters
[in]_stepsThe number of steps the World should take.
void gazebo::physics::World::Stop ( )

Stop the world.

Stop the update loop.

std::string gazebo::physics::World::StripWorldName ( const std::string &  _name) const

Return a version of the name with "<world_name>::" removed.

Parameters
[in]_nameUsually the name of an entity.
Returns
The stripped world name.
void gazebo::physics::World::UpdateStateSDF ( )

Update the state SDF value from the current state.


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