Gazebo Gazebo

API Reference

3.15.1
Server Class Reference

The server instantiates and controls simulation. More...

#include <ignition/gazebo/Server.hh>

Public Member Functions

 Server (const ServerConfig &_config=ServerConfig())
 Construct the server using the parameters specified in a ServerConfig. More...
 
 ~Server ()
 Destructor. More...
 
std::optional< bool > AddSystem (const std::shared_ptr< System > &_system, const unsigned int _worldIndex=0)
 Add a System to the server. The server must not be running when calling this. More...
 
std::optional< bool > AddSystem (const SystemPluginPtr &_system, const unsigned int _worldIndex=0)
 Add a System to the server. The server must not be running when calling this. More...
 
std::optional< EntityEntityByName (const std::string &_name, const unsigned int _worldIndex=0) const
 Get an Entity based on a name. More...
 
std::optional< size_t > EntityCount (const unsigned int _worldIndex=0) const
 Get the number of entities on the server. More...
 
bool HasEntity (const std::string &_name, const unsigned int _worldIndex=0) const
 Return true if the specified world has an entity with the provided name. More...
 
std::optional< uint64_t > IterationCount (const unsigned int _worldIndex=0) const
 Get the number of iterations the server has executed. More...
 
std::optional< bool > Paused (const unsigned int _worldIndex=0) const
 Get whether a world simulation instance is paused. When paused is true, then simulation for the world is not stepping forward. More...
 
bool RequestRemoveEntity (const Entity _entity, bool _recursive=true, const unsigned int _worldIndex=0)
 Return true if the specified world has an entity with the provided id and the entity was queued for deletion. Note that the entity is not removed immediately. Entity deletion happens at the end of the next (or current depending on when this function is called) simulation step. More...
 
bool RequestRemoveEntity (const std::string &_name, bool _recursive=true, const unsigned int _worldIndex=0)
 Return true if the specified world has an entity with the provided name and the entity was queued for deletion. Note that the entity is not removed immediately. Entity deletion happens at the end of the next (or current depending on when this function is called) simulation step. More...
 
bool Run (const bool _blocking=false, const uint64_t _iterations=0, const bool _paused=true)
 Run the server. By default this is a non-blocking call, which means the server runs simulation in a separate thread. Pass in true to the _blocking argument to run the server in the current thread. More...
 
bool Running () const
 Get whether the server is running. The server can have zero or more simulation worlds, each of which may or may not be running. See Running(const unsigned int) to get the running status of a world. More...
 
std::optional< bool > Running (const unsigned int _worldIndex) const
 Get whether a world simulation instance is running. When running is true, then systems are being updated but simulation may or may not be stepping forward. Check the value of Paused() to determine if a world simulation instance is stepping forward. If Paused() returns true, then simulation is not stepping foward. More...
 
bool RunOnce (const bool _paused=true)
 Run the server once, all systems will be updated once and then this returns. This is a blocking call. More...
 
bool SetPaused (const bool _paused, const unsigned int _worldIndex=0) const
 Set whether a world simulation instance is paused. When paused is true, then simulation for the world is not stepping forward. More...
 
void SetUpdatePeriod (const std::chrono::steady_clock::duration &_updatePeriod, const unsigned int _worldIndex=0)
 Set the update period. The update period is the wall-clock time between ECS updates. Note that this is different from the simulation update rate. ECS systems will be updated even while sim time is paused. More...
 
std::optional< size_t > SystemCount (const unsigned int _worldIndex=0) const
 Get the number of systems on the server. More...
 

Detailed Description

The server instantiates and controls simulation.

Example Usage

A basic simulation server can be instantiated and run using

server.Run();

An SDF File can be passed into the server via a ServerConfig object. The server will parse the SDF file and create entities for the elements contained in the file.

config.SetSdfFile("path_to_file.sdf");
gz::sim::Server server(config);
server.Run();

The Run() function accepts a few arguments, one of which is whether simulation should start in a paused state. The default value of this argument is true, which starts simulation paused. This means that by default, running the server will cause systems to update but some systems may not update because paused == true. For example, a physics system will not update its state when paused is true. So, while a Server can be Running, simulation itself can be paused.

Simulation is paused by default because a common use case is to load a world from the command line. If simulation starts running, the GUI client may miss the first few simulation iterations.

Services

The following are services provided by the Server. The <world_name> in the service list is the name of the simulated world.

List syntax: service_name(request_msg_type) : response_msg_type

  1. /world/<world_name>/scene/info(none) : gz::msgs::Scene
    • Returns the current scene information.
  2. /gazebo/resource_paths/get(gz::msgs::Empty) : gz::msgs::StringMsg_V
    • Get list of resource paths.
  3. /gazebo/resource_paths/add(gz::msgs::StringMsg_V) : gz::msgs::Empty
    • Add new resource paths.
  4. /server_control(gz::msgs::ServerControl) : gz::msgs::Boolean
    • Control the simulation server.

Topics

The following are topics provided by the Server. The <world_name> in the service list is the name of the simulated world.

List syntax: topic_name : published_msg_type

  1. /world/<world_name>/clock : gz::msgs::Clock
  2. /world/<world_name>/stats : gz::msgs::WorldStatistics
    • This topic is throttled to 5Hz.
  3. /gazebo/resource_paths : gz::msgs::StringMsg_V
    • Updated list of resource paths.

Constructor & Destructor Documentation

◆ Server()

Server ( const ServerConfig _config = ServerConfig())
explicit

Construct the server using the parameters specified in a ServerConfig.

Parameters
[in]_configServer configuration parameters. If this parameter is omitted, then an empty world is loaded.

◆ ~Server()

~Server ( )

Destructor.

Member Function Documentation

◆ AddSystem() [1/2]

std::optional<bool> AddSystem ( const std::shared_ptr< System > &  _system,
const unsigned int  _worldIndex = 0 
)

Add a System to the server. The server must not be running when calling this.

Parameters
[in]_systemSystem to be added
[in]_worldIndexIndex of the world to add to.
Returns
Whether the system was added successfully, or std::nullopt if _worldIndex is invalid.

◆ AddSystem() [2/2]

std::optional<bool> AddSystem ( const SystemPluginPtr _system,
const unsigned int  _worldIndex = 0 
)

Add a System to the server. The server must not be running when calling this.

Parameters
[in]_systemsystem to be added
[in]_worldIndexIndex of the world to query.
Returns
Whether the system was added successfully, or std::nullopt if _worldIndex is invalid.

◆ EntityByName()

std::optional<Entity> EntityByName ( const std::string _name,
const unsigned int  _worldIndex = 0 
) const

Get an Entity based on a name.

If multiple entities with the same name exist, the first entity found will be returned.

Parameters
[in]_nameName of the entity to get from the specified world.
[in]_worldIndexIndex of the world to query.
Returns
The entity, or std::nullopt if the entity or world doesn't exist.

◆ EntityCount()

std::optional<size_t> EntityCount ( const unsigned int  _worldIndex = 0) const

Get the number of entities on the server.

Parameters
[in]_worldIndexIndex of the world to query.
Returns
Entity count, or std::nullopt if _worldIndex is invalid.

◆ HasEntity()

bool HasEntity ( const std::string _name,
const unsigned int  _worldIndex = 0 
) const

Return true if the specified world has an entity with the provided name.

Parameters
[in]_nameName of the entity.
[in]_worldIndexIndex of the world.
Returns
True if the _worldIndex is valid and the entity exists in the world.

◆ IterationCount()

std::optional<uint64_t> IterationCount ( const unsigned int  _worldIndex = 0) const

Get the number of iterations the server has executed.

Parameters
[in]_worldIndexIndex of the world to query.
Returns
The current iteration count, or std::nullopt if _worldIndex is invalid.

◆ Paused()

std::optional<bool> Paused ( const unsigned int  _worldIndex = 0) const

Get whether a world simulation instance is paused. When paused is true, then simulation for the world is not stepping forward.

Parameters
[in]_worldIndexIndex of the world to query.
Returns
True if the world simulation instance is paused, false if stepping forward, or std::nullopt if _worldIndex is invalid.

◆ RequestRemoveEntity() [1/2]

bool RequestRemoveEntity ( const Entity  _entity,
bool  _recursive = true,
const unsigned int  _worldIndex = 0 
)

Return true if the specified world has an entity with the provided id and the entity was queued for deletion. Note that the entity is not removed immediately. Entity deletion happens at the end of the next (or current depending on when this function is called) simulation step.

Parameters
[in]_entityThe entity to delete.
[in]_recursiveWhether to recursively delete all child entities. True by default.
[in]_worldIndexIndex of the world.
Returns
True if the entity exists in the world and it was queued for deletion.

◆ RequestRemoveEntity() [2/2]

bool RequestRemoveEntity ( const std::string _name,
bool  _recursive = true,
const unsigned int  _worldIndex = 0 
)

Return true if the specified world has an entity with the provided name and the entity was queued for deletion. Note that the entity is not removed immediately. Entity deletion happens at the end of the next (or current depending on when this function is called) simulation step.

If multiple entities with the same name exist, only the first entity found will be deleted.

Parameters
[in]_nameName of the entity to delete.
[in]_recursiveWhether to recursively delete all child entities. True by default.
[in]_worldIndexIndex of the world.
Returns
True if the entity exists in the world and it was queued for deletion.

◆ Run()

bool Run ( const bool  _blocking = false,
const uint64_t  _iterations = 0,
const bool  _paused = true 
)

Run the server. By default this is a non-blocking call, which means the server runs simulation in a separate thread. Pass in true to the _blocking argument to run the server in the current thread.

Parameters
[in]_blockingFalse to run the server in a new thread. True to run the server in the current thread.
[in]_iterationsNumber of steps to perform. A value of zero will run indefinitely.
[in]_pausedTrue to start simulation in a paused state, false, to start simulation unpaused.
Returns
In non-blocking mode, the return value is true if a thread was successfully created. In blocking mode, true will be returned if the Server ran for the specified number of iterations or was terminated. False will always be returned if signal handlers could not be initialized, and if the server is already running.

◆ Running() [1/2]

bool Running ( ) const

Get whether the server is running. The server can have zero or more simulation worlds, each of which may or may not be running. See Running(const unsigned int) to get the running status of a world.

Returns
True if the server is running.

◆ Running() [2/2]

std::optional<bool> Running ( const unsigned int  _worldIndex) const

Get whether a world simulation instance is running. When running is true, then systems are being updated but simulation may or may not be stepping forward. Check the value of Paused() to determine if a world simulation instance is stepping forward. If Paused() returns true, then simulation is not stepping foward.

Parameters
[in]_worldIndexIndex of the world to query.
Returns
True if the server is running, or std::nullopt if _worldIndex is invalid.

◆ RunOnce()

bool RunOnce ( const bool  _paused = true)

Run the server once, all systems will be updated once and then this returns. This is a blocking call.

Parameters
[in]_pausedTrue to run the simulation in a paused state, false to run simulation unpaused. The simulation iterations will be increased by 1.
Returns
False if the server was terminated before completing, not being initialized, or if the server is already running.

◆ SetPaused()

bool SetPaused ( const bool  _paused,
const unsigned int  _worldIndex = 0 
) const

Set whether a world simulation instance is paused. When paused is true, then simulation for the world is not stepping forward.

Parameters
[in]_pausedTrue to pause the world, false to unpause.
[in]_worldIndexIndex of the world to query.
Returns
True if the world referenced by _worldIndex exists, false otherwise.

◆ SetUpdatePeriod()

void SetUpdatePeriod ( const std::chrono::steady_clock::duration &  _updatePeriod,
const unsigned int  _worldIndex = 0 
)

Set the update period. The update period is the wall-clock time between ECS updates. Note that this is different from the simulation update rate. ECS systems will be updated even while sim time is paused.

Parameters
[in]_updatePeriodDuration between updates.
[in]_worldIndexIndex of the world to query.

◆ SystemCount()

std::optional<size_t> SystemCount ( const unsigned int  _worldIndex = 0) const

Get the number of systems on the server.

Parameters
[in]_worldIndexIndex of the world to query.
Returns
System count, or std::nullopt if _worldIndex is invalid.

The documentation for this class was generated from the following file:
Configuration parameters for a Server. An instance of this object can be used to construct a Server w...
Definition: gz/sim/ServerConfig.hh:43
bool SetSdfFile(const std::string &_file)
Set an SDF file to be used with the server.
The server instantiates and controls simulation.
Definition: gz/sim/Server.hh:114
bool Run(const bool _blocking=false, const uint64_t _iterations=0, const bool _paused=true)
Run the server. By default this is a non-blocking call, which means the server runs simulation in a s...