Gazebo Gazebo

API Reference

6.17.1
gz/sim/Server.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef GZ_GAZEBO_SERVER_HH_
18 #define GZ_GAZEBO_SERVER_HH_
19 
20 #include <cstdint>
21 #include <memory>
22 #include <optional>
23 #include <string>
24 #include <gz/sim/config.hh>
26 #include <gz/sim/Export.hh>
27 #include <gz/sim/ServerConfig.hh>
29 
30 namespace ignition
31 {
32  namespace gazebo
33  {
34  // Inline bracket to help doxygen filtering.
35  inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
36  // Forware declarations
37  class ServerPrivate;
38 
114  class IGNITION_GAZEBO_VISIBLE Server
115  {
120  public: explicit Server(const ServerConfig &_config = ServerConfig());
121 
123  public: ~Server();
124 
131  public: void SetUpdatePeriod(
132  const std::chrono::steady_clock::duration &_updatePeriod,
133  const unsigned int _worldIndex = 0);
134 
150  public: bool Run(const bool _blocking = false,
151  const uint64_t _iterations = 0,
152  const bool _paused = true);
153 
161  public: bool RunOnce(const bool _paused = true);
162 
168  public: bool Running() const;
169 
178  public: std::optional<bool> Running(const unsigned int _worldIndex) const;
179 
187  public: bool SetPaused(const bool _paused,
188  const unsigned int _worldIndex = 0) const;
189 
196  public: std::optional<bool> Paused(
197  const unsigned int _worldIndex = 0) const;
198 
203  public: std::optional<uint64_t> IterationCount(
204  const unsigned int _worldIndex = 0) const;
205 
209  public: std::optional<size_t> EntityCount(
210  const unsigned int _worldIndex = 0) const;
211 
215  public: std::optional<size_t> SystemCount(
216  const unsigned int _worldIndex = 0) const;
217 
224  public: std::optional<bool> AddSystem(
225  const SystemPluginPtr &_system,
226  const unsigned int _worldIndex = 0);
227 
234  public: std::optional<bool> AddSystem(
235  const std::shared_ptr<System> &_system,
236  const unsigned int _worldIndex = 0);
237 
246  public: std::optional<Entity> EntityByName(const std::string &_name,
247  const unsigned int _worldIndex = 0) const;
248 
255  public: bool HasEntity(const std::string &_name,
256  const unsigned int _worldIndex = 0) const;
257 
271  public: bool RequestRemoveEntity(const std::string &_name,
272  bool _recursive = true,
273  const unsigned int _worldIndex = 0);
274 
286  public: bool RequestRemoveEntity(const Entity _entity,
287  bool _recursive = true,
288  const unsigned int _worldIndex = 0);
289 
291  public: void Stop();
292 
294  private: std::unique_ptr<ServerPrivate> dataPtr;
295  };
296  }
297  }
298 }
299 
300 #endif
Configuration parameters for a Server. An instance of this object can be used to construct a Server w...
Definition: gz/sim/ServerConfig.hh:45
std::optional< Entity > EntityByName(const std::string &_name, const unsigned int _worldIndex=0) const
Get an Entity based on a name.
uint64_t Entity
An Entity identifies a single object in simulation such as a model, link, or light....
Definition: gz/sim/Entity.hh:58
This library is part of the Gazebo project.
Definition: gz/sim/Actor.hh:33
STL class.
STL class.
bool Running() const
Get whether the server is running. The server can have zero or more simulation worlds,...
gz::plugin::SpecializedPluginPtr< System, ISystemConfigure, ISystemPreUpdate, ISystemUpdate, ISystemPostUpdate > SystemPluginPtr
Definition: gz/sim/SystemPluginPtr.hh:33
std::optional< size_t > EntityCount(const unsigned int _worldIndex=0) const
Get the number of entities on the server.
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.
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.
void Stop()
Stop the server. This will stop all running simulations.
std::optional< size_t > SystemCount(const unsigned int _worldIndex=0) const
Get the number of systems on the server.
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....
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...
Server(const ServerConfig &_config=ServerConfig())
Construct the server using the parameters specified in a ServerConfig.
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.
The server instantiates and controls simulation.
Definition: gz/sim/Server.hh:114
std::optional< uint64_t > IterationCount(const unsigned int _worldIndex=0) const
Get the number of iterations the server has executed.
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...
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...
gz::common::EventT< void(void), struct StopTag > Stop
The stop event can be used to terminate simulation. Emit this signal to terminate an active simulatio...
Definition: gz/sim/Events.hh:55
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...