-
Notifications
You must be signed in to change notification settings - Fork 277
/
Copy pathServerConfig.hh
369 lines (306 loc) · 15.4 KB
/
ServerConfig.hh
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
/*
* Copyright (C) 2018 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_GAZEBO_SERVERCONFIG_HH_
#define IGNITION_GAZEBO_SERVERCONFIG_HH_
#include <chrono>
#include <list>
#include <memory>
#include <optional> // NOLINT(*)
#include <string>
#include <vector>
#include <sdf/Element.hh>
#include <ignition/gazebo/config.hh>
#include <ignition/gazebo/Export.hh>
namespace ignition
{
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
// Forward declarations.
class ServerConfigPrivate;
/// \class ServerConfig ServerConfig.hh ignition/gazebo/ServerConfig.hh
/// \brief Configuration parameters for a Server. An instance of this
/// object can be used to construct a Server with a particular
/// configuration.
class IGNITION_GAZEBO_VISIBLE ServerConfig
{
class PluginInfoPrivate;
/// \brief Information about a plugin that should be loaded by the
/// server.
/// \detail Currently supports attaching a plugin to an entity given its
/// type and name, but it can't tell apart multiple entities with the same
/// name in different parts of the entity tree.
/// \sa const std::list<PluginInfo> &Plugins() const
public: class PluginInfo
{
/// \brief Default constructor.
public: PluginInfo();
/// \brief Destructor.
public: ~PluginInfo();
/// \brief Constructor with plugin information specified.
/// \param[in] _entityName Name of the entity which should receive
/// this plugin. The name is used in conjuction with _entityType to
/// uniquely identify an entity.
/// \param[in] _entityType Entity type which should receive this
/// plugin. The type is used in conjuction with _entityName to
/// uniquely identify an entity.
/// \param[in] _filename Plugin library filename.
/// \param[in] _name Name of the interface within the plugin library
/// to load.
/// \param[in] _sdf Plugin XML elements associated with this plugin.
public: PluginInfo(const std::string &_entityName,
const std::string &_entityType,
const std::string &_filename,
const std::string &_name,
const sdf::ElementPtr &_sdf);
/// \brief Copy constructor.
/// \param[in] _info Plugin to copy.
public: PluginInfo(const PluginInfo &_info);
/// \brief Equal operator.
/// \param[in] _info PluginInfo to copy.
/// \return Reference to this class.
public: PluginInfo &operator=(const PluginInfo &_info);
/// \brief Get the name of the entity which should receive
/// this plugin. The name is used in conjuction with _entityType to
/// uniquely identify an entity.
/// \return Entity name.
public: const std::string &EntityName() const;
/// \brief Set the name of the entity which should receive
/// this plugin. The name is used in conjuction with _entityType to
/// uniquely identify an entity.
/// \param[in] _entityName Entity name.
public: void SetEntityName(const std::string &_entityName);
/// \brief Get the entity type which should receive this
/// plugin. The type is used in conjuction with EntityName to
/// uniquely identify an entity.
/// \return Entity type string.
public: const std::string &EntityType() const;
/// \brief Set the type of the entity which should receive this
/// plugin. The type is used in conjuction with EntityName to
/// uniquely identify an entity.
/// \param[in] _entityType Entity type string.
public: void SetEntityType(const std::string &_entityType);
/// \brief Get the plugin library filename.
/// \return Plugin library filename.
public: const std::string &Filename() const;
/// \brief Set the type of the entity which should receive this
/// plugin. The type is used in conjuction with EntityName to
/// uniquely identify an entity.
/// \param[in] _entityType Entity type string.
public: void SetFilename(const std::string &_filename);
/// \brief Name of the interface within the plugin library
/// to load.
/// \return Interface name.
public: const std::string &Name() const;
/// \brief Set the name of the interface within the plugin library
/// to load.
/// \param[in] _name Interface name.
public: void SetName(const std::string &_name);
/// \brief Plugin XML elements associated with this plugin.
/// \return SDF pointer.
public: const sdf::ElementPtr &Sdf() const;
/// \brief Set the plugin XML elements associated with this plugin.
/// \param[in] _sdf SDF pointer, it will be cloned.
public: void SetSdf(const sdf::ElementPtr &_sdf);
/// \brief Private data pointer
private: std::unique_ptr<ServerConfig::PluginInfoPrivate> dataPtr;
};
/// \brief Constructor
public: ServerConfig();
/// \brief Copy constructor.
/// \param[in] _config ServerConfig to copy.
public: ServerConfig(const ServerConfig &_config);
/// \brief Destructor
public: ~ServerConfig();
/// \brief Set an SDF file to be used with the server.
///
/// Setting the SDF file will override any value set by `SetSdfString`.
///
/// \param[in] _file Full path to an SDF file.
/// \return (reserved for future use)
public: bool SetSdfFile(const std::string &_file);
/// \brief Get the SDF file that has been set. An empty string will be
/// returned if an SDF file has not been set.
/// \return The full path to the SDF file, or empty string.
public: std::string SdfFile() const;
/// \brief Set an SDF string to be used by the server.
///
/// Setting the SDF string will override any value set by `SetSdfFile`.
///
/// \param[in] _file Full path to an SDF file.
/// \return (reserved for future use)
public: bool SetSdfString(const std::string &_sdfString);
/// \brief Get the SDF String that has been set. An empty string will
/// be returned if an SDF string has not been set.
/// \return The full contents of the SDF string, or empty string.
public: std::string SdfString() const;
/// \brief Set the update rate in Hertz. Value <=0 are ignored.
/// \param[in] _hz The desired update rate of the server in Hertz.
public: void SetUpdateRate(const double &_hz);
/// \brief Get the update rate in Hertz.
/// \return The desired update rate of the server in Hertz, or nullopt if
/// an UpdateRate has not been set.
public: std::optional<double> UpdateRate() const;
/// \brief Get whether the server is using the level system
/// \return True if the server is set to use the level system
public: bool UseLevels() const;
/// \brief Get whether the server is using the level system.
/// \param[in] _levels Value to set.
public: void SetUseLevels(const bool _levels);
/// \brief Get whether the server is using the distributed sim system
/// \return True if the server is set to use the distributed simulation
/// system
/// \sa SetNetworkRole(const std::string &_role)
public: bool UseDistributedSimulation() const;
/// \brief Set whether the server is using the distributed sim system.
/// \param[in] _distributeSimulation Value to set.
/// \deprecated SetNetworkRole(const std::string &_role) is used
/// to indicate if distributed simulation is enabled.
public: void IGN_DEPRECATED(2) SetUseDistributedSimulation(
const bool _distributed);
/// \brief Set the number of network secondary servers that the
/// primary server should expect. This value is valid only when
/// SetNetworkRole("primary") is also used.
/// \param[in] _secondaries Number of secondary servers.
/// \sa SetNetworkRole(const std::string &_role)
/// \sa NetworkRole() const
public: void SetNetworkSecondaries(unsigned int _secondaries);
/// \brief Get the number of secondary servers that a primary server
/// should expect.
/// \return Number of secondary servers.
/// \sa SetNetworkSecondaries(unsigned int _secondaries)
public: unsigned int NetworkSecondaries() const;
/// \brief Set the network role, which is one of [primary, secondary].
/// If primary is used, then make sure to also set the numer of
/// network secondaries via
/// SetNetworkSecondaries(unsigned int _secondaries).
/// \param[in] _role Network role, one of [primary, secondary].
/// \note Setting a network role enables distributed simulation.
/// \sa SetNetworkSecondaries(unsigned int _secondaries)
public: void SetNetworkRole(const std::string &_role);
/// \brief Get the network role. See
/// SetNetworkRole(const std::string &_role) for more information
/// about distributed simulation and network roles.
/// \return The network role.
/// \sa SetNetworkRole(const std::string &_role)
public: std::string NetworkRole() const;
/// \brief Get whether the server is recording states
/// \return True if the server is set to record states
public: bool UseLogRecord() const;
/// \brief Set whether the server is recording states
/// \param[in] _record Value to set
public: void SetUseLogRecord(const bool _record);
/// \brief Get path to place recorded states
/// \return Path to place recorded states
public: const std::string LogRecordPath() const;
/// \brief Set path to place recorded states
/// \param[in] _recordPath Path to place recorded states
public: void SetLogRecordPath(const std::string &_recordPath);
/// \brief Get whether to ignore the path specified in SDF.
/// \return Whether to ignore the path specified in SDF
/// \TODO(anyone) Deprecate on Dome, SDF path will always be ignored.
public: bool LogIgnoreSdfPath() const;
/// \brief Set whether to ignore the path specified in SDF. Path in SDF
/// should be ignored if a record path is specified on the command line,
/// for example.
/// \param[in] _ignore Whether to ignore the path specified in SDF
/// \TODO(anyone) Deprecate on Dome, SDF path will always be ignored.
public: void SetLogIgnoreSdfPath(bool _ignore);
/// \brief Add a topic to record.
/// \param[in] _topic Topic name, which can include wildcards.
public: void AddLogRecordTopic(const std::string &_topic);
/// \brief Clear topics to record. This will remove all topics set
/// using AddLogRecordTopic.
public: void ClearLogRecordTopics();
/// \brief Get the topics to record that were added using
/// AddLogRecordTopic.
/// \return The topics to record.
public: const std::vector<std::string> &LogRecordTopics() const;
/// \brief Get path to recorded states to play back
/// \return Path to recorded states
public: const std::string LogPlaybackPath() const;
/// \brief Set path to recorded states to play back
/// \param[in] _playbackPath Path to recorded states
public: void SetLogPlaybackPath(const std::string &_playbackPath);
/// \brief Get whether meshes and material files are recorded
/// \return True if resources should be recorded.
public: bool LogRecordResources() const;
/// \brief Set whether meshes and material files are recorded
/// \param[in] _recordResources Value to set
public: void SetLogRecordResources(bool _recordResources);
/// \brief Get file path to compress log files to
/// \return File path to compress log files to
public: std::string LogRecordCompressPath() const;
/// \brief Set file path to compress log files to
/// \param[in] _path File path to compress log files to
public: void SetLogRecordCompressPath(const std::string &_path);
/// \brief The given random seed.
/// \return The random seed or 0 if not specified.
public: unsigned int Seed() const;
/// \brief Set the random seed.
/// \param[in] _seed The seed.
public: void SetSeed(unsigned int _seed);
/// \brief Get the update period duration.
/// \return The desired update period, or nullopt if
/// an UpdateRate has not been set.
public: std::optional<std::chrono::steady_clock::duration>
UpdatePeriod() const;
/// \brief Path to where simulation resources, such as models downloaded
/// from fuel.ignitionrobotics.org, should be stored.
/// \return Path to a location on disk. An empty string indicates that
/// the default value will be used, which is currently
/// ~/.ignition/fuel.
public: const std::string &ResourceCache() const;
/// \brief Set the path to where simulation resources, such as models
/// downloaded from fuel.ignitionrobotics.org, should be stored.
/// \param[in] _path Path to a location on disk. An empty string
/// indicates that the default value will be used, which is currently
/// ~/.ignition/fuel.
public: void SetResourceCache(const std::string &_path);
/// \brief Physics engine plugin library to load.
/// \return File containing physics engine library.
public: const std::string &PhysicsEngine() const;
/// \brief Set the physics engine plugin library.
/// \param[in] _physicsEngine File containing physics engine library.
public: void SetPhysicsEngine(const std::string &_physicsEngine);
/// \brief Instruct simulation to attach a plugin to a specific
/// entity when simulation starts.
/// \param[in] _info Information about the plugin to load.
public: void AddPlugin(const PluginInfo &_info);
/// \brief Get all the plugins that should be loaded.
/// \return A list of all the plugins specified via
/// AddPlugin(const PluginInfo &).
public: const std::list<PluginInfo> &Plugins() const;
/// \brief Equal operator.
/// \param[in] _cfg ServerConfig to copy.
/// \return Reference to this class.
public: ServerConfig &operator=(const ServerConfig &_cfg);
/// \brief Get the timestamp of this ServerConfig. This is the system
/// time when this ServerConfig was created. The timestamp is used
/// internally to create log file paths so that both state and console
/// logs are co-located.
/// \return Time when this ServerConfig was created.
public: const std::chrono::time_point<std::chrono::system_clock> &
Timestamp() const;
/// \brief Private data pointer
private: std::unique_ptr<ServerConfigPrivate> dataPtr;
};
}
}
}
#endif