-
Notifications
You must be signed in to change notification settings - Fork 304
/
Copy pathgz.cc
396 lines (348 loc) · 11.9 KB
/
gz.cc
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
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
/*
* Copyright (C) 2019 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.
*
*/
#include "gz.hh"
#include <cstring>
#include <string>
#include <vector>
#include <gz/common/Console.hh>
#include <gz/common/Filesystem.hh>
#include <gz/fuel_tools/FuelClient.hh>
#include <gz/fuel_tools/ClientConfig.hh>
#include <gz/fuel_tools/Result.hh>
#include <gz/fuel_tools/WorldIdentifier.hh>
#include "gz/sim/config.hh"
#include "gz/sim/Server.hh"
#include "gz/sim/ServerConfig.hh"
#include "gz/sim/gui/Gui.hh"
//////////////////////////////////////////////////
extern "C" char *gzSimVersion()
{
return strdup(GZ_SIM_VERSION_FULL);
}
//////////////////////////////////////////////////
extern "C" char *simVersionHeader()
{
return strdup(GZ_SIM_VERSION_HEADER);
}
//////////////////////////////////////////////////
extern "C" void cmdVerbosity(
const char *_verbosity)
{
gz::common::Console::SetVerbosity(std::atoi(_verbosity));
}
//////////////////////////////////////////////////
extern "C" const char *worldInstallDir()
{
return GZ_SIM_WORLD_INSTALL_DIR;
}
//////////////////////////////////////////////////
extern "C" const char *findFuelResource(
char *_pathToResource)
{
std::string path;
std::string worldPath;
gz::fuel_tools::FuelClient fuelClient;
// Attempt to find cached copy, and then attempt download
if (fuelClient.CachedWorld(gz::common::URI(_pathToResource), path))
{
gzmsg << "Cached world found." << std::endl;
worldPath = path;
}
// cppcheck-suppress syntaxError
else if (gz::fuel_tools::Result result =
fuelClient.DownloadWorld(gz::common::URI(_pathToResource), path);
result)
{
gzmsg << "Successfully downloaded world from fuel." << std::endl;
worldPath = path;
}
else
{
gzwarn << "Fuel world download failed because " << result.ReadableResult()
<< std::endl;
return "";
}
if (!gz::common::exists(worldPath))
return "";
// Find the first sdf file in the world path for now, the later intention is
// to load an optional world config file first and if that does not exist,
// continue to load the first sdf file found as done below
for (gz::common::DirIter file(worldPath);
file != gz::common::DirIter(); ++file)
{
std::string current(*file);
if (gz::common::isFile(current))
{
std::string fileName = gz::common::basename(current);
std::string::size_type fileExtensionIndex = fileName.rfind(".");
std::string fileExtension = fileName.substr(fileExtensionIndex + 1);
if (fileExtension == "sdf")
{
return strdup(current.c_str());
}
}
}
return "";
}
//////////////////////////////////////////////////
extern "C" int runServer(const char *_sdfString,
int _iterations, int _run, float _hz, int _levels, const char *_networkRole,
int _networkSecondaries, int _record, const char *_recordPath,
int _recordResources, int _logOverwrite, int _logCompress,
const char *_playback, const char *_physicsEngine,
const char *_renderEngineServer, const char *_renderEngineGui,
const char *_file, const char *_recordTopics,
int _headless, int _seed)
{
gz::sim::ServerConfig serverConfig;
// Path for logs
std::string recordPathMod = serverConfig.LogRecordPath();
// Path for compressed log, used to check for duplicates
std::string cmpPath = std::string(recordPathMod);
if (!std::string(1, cmpPath.back()).compare(gz::common::separator("")))
{
// Remove the separator at end of path
cmpPath = cmpPath.substr(0, cmpPath.length() - 1);
}
cmpPath += ".zip";
// Initialize console log
if ((_recordPath != nullptr && std::strlen(_recordPath) > 0) ||
_record > 0 || _recordResources > 0 ||
(_recordTopics != nullptr && std::strlen(_recordTopics) > 0))
{
if (_playback != nullptr && std::strlen(_playback) > 0)
{
gzerr << "Both record and playback are specified. Only specify one.\n";
return -1;
}
serverConfig.SetUseLogRecord(true);
serverConfig.SetLogRecordResources(_recordResources);
// If a record path is specified
if (_recordPath != nullptr && std::strlen(_recordPath) > 0)
{
recordPathMod = std::string(_recordPath);
// Update compressed file path to name of recording directory path
cmpPath = std::string(recordPathMod);
if (!std::string(1, cmpPath.back()).compare(gz::common::separator(
"")))
{
// Remove the separator at end of path
cmpPath = cmpPath.substr(0, cmpPath.length() - 1);
}
cmpPath += ".zip";
// Check if path or compressed file with same prefix exists
if (gz::common::exists(recordPathMod) ||
gz::common::exists(cmpPath))
{
// Overwrite if flag specified
if (_logOverwrite > 0)
{
bool recordMsg = false;
bool cmpMsg = false;
// Remove files before initializing console log files on top of them
if (gz::common::exists(recordPathMod))
{
recordMsg = true;
gz::common::removeAll(recordPathMod);
}
if (gz::common::exists(cmpPath))
{
cmpMsg = true;
gz::common::removeFile(cmpPath);
}
// Create log file before printing any messages so they can be logged
gzLogInit(recordPathMod, "server_console.log");
if (recordMsg)
{
gzmsg << "Log path already exists on disk! Existing files will "
<< "be overwritten." << std::endl;
gzmsg << "Removing existing path [" << recordPathMod << "]\n";
}
if (cmpMsg)
{
if (_logCompress > 0)
{
gzwarn << "Compressed log path already exists on disk! Existing "
<< "files will be overwritten." << std::endl;
}
gzmsg << "Removing existing compressed file [" << cmpPath << "]\n";
}
}
// Otherwise rename to unique path
else
{
// Remove the separator at end of path
if (!std::string(1, recordPathMod.back()).compare(
gz::common::separator("")))
{
recordPathMod = recordPathMod.substr(0, recordPathMod.length()
- 1);
}
std::string recordOrigPrefix = std::string(recordPathMod);
int count = 1;
// Keep renaming until path does not exist for both directory and
// compressed file
while (gz::common::exists(recordPathMod) ||
gz::common::exists(cmpPath))
{
recordPathMod = recordOrigPrefix + "(" + std::to_string(count++) +
")";
cmpPath = std::string(recordPathMod);
// Remove the separator at end of path
if (!std::string(1, cmpPath.back()).compare(
gz::common::separator("")))
{
cmpPath = cmpPath.substr(0, cmpPath.length() - 1);
}
cmpPath += ".zip";
}
gzLogInit(recordPathMod, "server_console.log");
gzwarn << "Log path already exists on disk! "
<< "Recording instead to [" << recordPathMod << "]" << std::endl;
if (_logCompress > 0)
{
gzwarn << "Compressed log path already exists on disk! "
<< "Recording instead to [" << cmpPath << "]" << std::endl;
}
}
}
else
{
gzLogInit(recordPathMod, "server_console.log");
}
}
// Empty record path specified. Use default.
else
{
// Create log file before printing any messages so they can be logged
gzLogInit(recordPathMod, "server_console.log");
gzmsg << "Recording states to default path [" << recordPathMod << "]"
<< std::endl;
}
serverConfig.SetLogRecordPath(recordPathMod);
std::vector<std::string> topics = gz::common::split(
_recordTopics, ":");
for (const std::string &topic : topics)
{
serverConfig.AddLogRecordTopic(topic);
}
}
else
{
gzLogInit(serverConfig.LogRecordPath(), "server_console.log");
}
if (_logCompress > 0)
{
serverConfig.SetLogRecordCompressPath(cmpPath);
}
gzmsg << "Gazebo Sim Server v" << GZ_SIM_VERSION_FULL
<< std::endl;
// Set the SDF string to user
if (_sdfString != nullptr && std::strlen(_sdfString) > 0)
{
if (!serverConfig.SetSdfString(_sdfString))
{
gzerr << "Failed to set SDF string [" << _sdfString << "]" << std::endl;
return -1;
}
}
serverConfig.SetSdfFile(_file);
// Set the update rate.
if (_hz > 0.0)
serverConfig.SetUpdateRate(_hz);
// Set whether levels should be used.
if (_levels > 0)
{
gzmsg << "Using the level system\n";
serverConfig.SetUseLevels(true);
}
if (_networkRole && std::strlen(_networkRole) > 0)
{
gzmsg << "Using the distributed simulation and levels systems\n";
serverConfig.SetNetworkRole(_networkRole);
serverConfig.SetNetworkSecondaries(_networkSecondaries);
serverConfig.SetUseLevels(true);
}
if (_playback != nullptr && std::strlen(_playback) > 0)
{
if (_sdfString != nullptr && std::strlen(_sdfString) > 0)
{
gzerr << "Both an SDF file and playback flag are specified. "
<< "Only specify one.\n";
return -1;
}
else
{
gzmsg << "Playing back states" << _playback << std::endl;
serverConfig.SetLogPlaybackPath(gz::common::absPath(
std::string(_playback)));
}
}
if (_physicsEngine != nullptr && std::strlen(_physicsEngine) > 0)
{
serverConfig.SetPhysicsEngine(_physicsEngine);
}
serverConfig.SetHeadlessRendering(_headless);
if (_renderEngineServer != nullptr && std::strlen(_renderEngineServer) > 0)
{
serverConfig.SetRenderEngineServer(_renderEngineServer);
}
if (_renderEngineGui != nullptr && std::strlen(_renderEngineGui) > 0)
{
serverConfig.SetRenderEngineGui(_renderEngineGui);
}
if (_seed != 0)
{
serverConfig.SetSeed(_seed);
}
// Create the Gazebo server
gz::sim::Server server(serverConfig);
// Run the server
server.Run(true, _iterations, _run == 0);
gzdbg << "Shutting down gz-sim-server" << std::endl;
return 0;
}
//////////////////////////////////////////////////
extern "C" int runGui(const char *_guiConfig, const char *_renderEngine)
{
// argc and argv are going to be passed to a QApplication. The Qt
// documentation has a warning about these:
// "Warning: The data referred to by argc and argv must stay valid for the
// entire lifetime of the QApplication object. In addition, argc must be
// greater than zero and argv must contain at least one valid character
// string."
// Converting a string literal to char * is forbidden as of C++11. It can only
// be converted to a const char *. The const cast is here to prevent a warning
// since we do need to pass a char* to runGui
static char *argv[] = {
const_cast<char *>("gz-sim-gui"),
#ifdef QT_QML_DEBUG
// To debug with QML, you must add
//
// CMAKE_CXX_FLAGS += -DQT_QML_DEBUG
// Or at least (if CMAKE_BUILD_TYPE = Debug)
// CMAKE_CXX_FLAGS_DEBUG += -DQT_QML_DEBUG
//
// The port you must attach to is 40000
const_cast<char *>(
"-qmljsdebugger=port:40000,block,services:DebugMessages,QmlDebugger,"
"V8Debugger,QmlInspector,DebugTranslation")
#endif
};
int argc = sizeof(argv) / sizeof(argv[0]);
return gz::sim::gui::runGui(argc, argv, _guiConfig, _renderEngine);
}