-
Notifications
You must be signed in to change notification settings - Fork 276
/
SimulationRunner.cc
1555 lines (1326 loc) · 45.3 KB
/
SimulationRunner.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
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* 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.
*
*/
#include "SimulationRunner.hh"
#include <algorithm>
#ifdef HAVE_PYBIND11
#include <pybind11/pybind11.h>
#endif
#include <gz/msgs/boolean.pb.h>
#include <gz/msgs/clock.pb.h>
#include <gz/msgs/gui.pb.h>
#include <gz/msgs/log_playback_control.pb.h>
#include <gz/msgs/sdf_generator_config.pb.h>
#include <gz/msgs/stringmsg.pb.h>
#include <gz/msgs/world_control.pb.h>
#include <gz/msgs/world_control_state.pb.h>
#include <gz/msgs/world_stats.pb.h>
#include <sdf/Root.hh>
#include <vector>
#include "gz/common/Profiler.hh"
#include "gz/sim/components/Model.hh"
#include "gz/sim/components/Name.hh"
#include "gz/sim/components/Sensor.hh"
#include "gz/sim/components/Visual.hh"
#include "gz/sim/components/World.hh"
#include "gz/sim/components/ParentEntity.hh"
#include "gz/sim/components/Physics.hh"
#include "gz/sim/components/PhysicsCmd.hh"
#include "gz/sim/components/Recreate.hh"
#include "gz/sim/Events.hh"
#include "gz/sim/SdfEntityCreator.hh"
#include "gz/sim/Util.hh"
#include "gz/transport/TopicUtils.hh"
#include "network/NetworkManagerPrimary.hh"
#include "SdfGenerator.hh"
using namespace gz;
using namespace sim;
using StringSet = std::unordered_set<std::string>;
namespace {
#ifdef HAVE_PYBIND11
// Helper struct to maybe do a scoped release of the Python GIL. There are a
// number of ways where releasing and acquiring the GIL is not necessary:
// 1. Gazebo is built without Pybind11
// 2. The python interpreter is not initialized. This could happen in tests that
// create a SimulationRunner without sim::Server where the interpreter is
// intialized.
// 3. sim::Server was instantiated by a Python module. In this case, there's a
// chance that this would be called with the GIL already released.
struct MaybeGilScopedRelease
{
MaybeGilScopedRelease()
{
if (Py_IsInitialized() != 0 && PyGILState_Check() == 1)
{
this->release.emplace();
}
}
std::optional<pybind11::gil_scoped_release> release;
};
#else
struct MaybeGilScopedRelease
{
// The empty constructor is needed to avoid an "unused variable" warning
// when an instance of this class is used.
MaybeGilScopedRelease(){}
};
#endif
}
//////////////////////////////////////////////////
SimulationRunner::SimulationRunner(const sdf::World *_world,
const SystemLoaderPtr &_systemLoader,
const ServerConfig &_config)
// \todo(nkoenig) Either copy the world, or add copy constructor to the
// World and other elements.
: sdfWorld(_world), serverConfig(_config)
{
if (nullptr == _world)
{
gzerr << "Can't start simulation runner with null world." << std::endl;
return;
}
// Keep world name
this->worldName = transport::TopicUtils::AsValidTopic(_world->Name());
auto validWorldName = transport::TopicUtils::AsValidTopic(worldName);
if (this->worldName.empty())
{
gzerr << "Can't start simulation runner with this world name ["
<< worldName << "]." << std::endl;
return;
}
this->parametersRegistry = std::make_unique<
gz::transport::parameters::ParametersRegistry>(
std::string{"world/"} + this->worldName);
// Get the physics profile
// TODO(luca): remove duplicated logic in SdfEntityCreator and LevelManager
auto physics = _world->PhysicsByIndex(0);
if (!physics)
{
physics = _world->PhysicsDefault();
}
// Step size
auto dur = std::chrono::duration<double>(physics->MaxStepSize());
this->stepSize =
std::chrono::duration_cast<std::chrono::steady_clock::duration>(
dur);
// Desired real time factor
this->desiredRtf = physics->RealTimeFactor();
// The instantaneous real time factor is given as:
//
// RTF = sim_time / real_time
//
// Where the sim time is the step size times the number of sim iterations:
//
// sim_time = sim_it * step_size
//
// And the real time is the period times the number of iterations:
//
// real_time = it * period
//
// So we have:
//
// RTF = sim_it * step_size / it * period
//
// Considering no pause, sim_it equals it, so:
//
// RTF = step_size / period
//
// So to get a given RTF, our desired period is:
//
// period = step_size / RTF
if (this->desiredRtf < 1e-9)
{
this->updatePeriod = 0ms;
}
else
{
this->updatePeriod = std::chrono::nanoseconds(
static_cast<int>(this->stepSize.count() / this->desiredRtf));
}
// Epoch
this->simTimeEpoch = std::chrono::round<std::chrono::nanoseconds>(
std::chrono::duration<double>{_config.InitialSimTime()}
);
this->currentInfo.simTime = this->simTimeEpoch;
// World control
transport::NodeOptions opts;
std::string ns{"/world/" + this->worldName};
if (this->networkMgr)
{
ns = this->networkMgr->Namespace() + ns;
}
auto validNs = transport::TopicUtils::AsValidTopic(ns);
if (validNs.empty())
{
gzerr << "Invalid namespace [" << ns
<< "], not initializing runner transport." << std::endl;
return;
}
opts.SetNameSpace(validNs);
this->node = std::make_unique<transport::Node>(opts);
// Create the system manager
this->systemMgr = std::make_unique<SystemManager>(
_systemLoader, &this->entityCompMgr, &this->eventMgr, validNs,
this->parametersRegistry.get());
this->pauseConn = this->eventMgr.Connect<events::Pause>(
std::bind(&SimulationRunner::SetPaused, this, std::placeholders::_1));
this->stopConn = this->eventMgr.Connect<events::Stop>(
std::bind(&SimulationRunner::OnStop, this));
this->loadPluginsConn = this->eventMgr.Connect<events::LoadSdfPlugins>(
std::bind(&SimulationRunner::LoadPlugins, this, std::placeholders::_1,
std::placeholders::_2));
// Create the level manager
this->levelMgr = std::make_unique<LevelManager>(this, _config.UseLevels());
// Check if this is going to be a distributed runner
// Attempt to create the manager based on environment variables.
// If the configuration is invalid, then networkMgr will be `nullptr`.
if (_config.UseDistributedSimulation())
{
if (_config.NetworkRole().empty())
{
/// \todo(nkoenig) Remove part of the 'if' statement in gz-sim3.
this->networkMgr = NetworkManager::Create(
std::bind(&SimulationRunner::Step, this, std::placeholders::_1),
this->entityCompMgr, &this->eventMgr);
}
else
{
this->networkMgr = NetworkManager::Create(
std::bind(&SimulationRunner::Step, this, std::placeholders::_1),
this->entityCompMgr, &this->eventMgr,
NetworkConfig::FromValues(
_config.NetworkRole(), _config.NetworkSecondaries()));
}
if (this->networkMgr)
{
if (this->networkMgr->IsPrimary())
{
gzmsg << "Network Primary, expects ["
<< this->networkMgr->Config().numSecondariesExpected
<< "] secondaries." << std::endl;
}
else if (this->networkMgr->IsSecondary())
{
gzmsg << "Network Secondary, with namespace ["
<< this->networkMgr->Namespace() << "]." << std::endl;
}
}
}
// Load the active levels
this->levelMgr->UpdateLevelsState();
// Store the initial state of the ECM;
this->initialEntityCompMgr.CopyFrom(this->entityCompMgr);
// Load any additional plugins from the Server Configuration
this->LoadServerPlugins(this->serverConfig.Plugins());
// If we have reached this point and no world systems have been loaded, then
// load a default set of systems.
if (this->systemMgr->TotalByEntity(
worldEntity(this->entityCompMgr)).empty())
{
gzmsg << "No systems loaded from SDF, loading defaults" << std::endl;
bool isPlayback = !this->serverConfig.LogPlaybackPath().empty();
auto plugins = sim::loadPluginInfo(isPlayback);
this->LoadServerPlugins(plugins);
}
this->LoadLoggingPlugins(this->serverConfig);
// TODO(louise) Combine both messages into one.
this->node->Advertise("control", &SimulationRunner::OnWorldControl, this);
this->node->Advertise("control/state", &SimulationRunner::OnWorldControlState,
this);
this->node->Advertise("playback/control",
&SimulationRunner::OnPlaybackControl, this);
gzmsg << "Serving world controls on [" << opts.NameSpace()
<< "/control], [" << opts.NameSpace() << "/control/state] and ["
<< opts.NameSpace() << "/playback/control]" << std::endl;
// Publish empty GUI messages for worlds that have no GUI in the beginning.
// In the future, support modifying GUI from the server at runtime.
if (_world->Gui())
{
this->guiMsg = convert<msgs::GUI>(*_world->Gui());
}
std::string infoService{"gui/info"};
this->node->Advertise(infoService, &SimulationRunner::GuiInfoService, this);
gzmsg << "Serving GUI information on [" << opts.NameSpace() << "/"
<< infoService << "]" << std::endl;
gzmsg << "World [" << _world->Name() << "] initialized with ["
<< physics->Name() << "] physics profile." << std::endl;
std::string genWorldSdfService{"generate_world_sdf"};
this->node->Advertise(
genWorldSdfService, &SimulationRunner::GenerateWorldSdf, this);
gzmsg << "Serving world SDF generation service on [" << opts.NameSpace()
<< "/" << genWorldSdfService << "]" << std::endl;
}
//////////////////////////////////////////////////
SimulationRunner::~SimulationRunner()
{
this->StopWorkerThreads();
}
/////////////////////////////////////////////////
void SimulationRunner::UpdateCurrentInfo()
{
GZ_PROFILE("SimulationRunner::UpdateCurrentInfo");
// Rewind
if (this->requestedRewind)
{
gzdbg << "Rewinding simulation back to initial time." << std::endl;
this->realTimeFactor = 0;
this->currentInfo.dt = this->simTimeEpoch - this->currentInfo.simTime;
this->currentInfo.simTime = this->simTimeEpoch;
this->currentInfo.realTime = std::chrono::steady_clock::duration::zero();
this->currentInfo.iterations = 0;
this->realTimeWatch.Reset();
if (!this->currentInfo.paused)
this->realTimeWatch.Start();
this->resetInitiated = true;
this->requestedRewind = false;
return;
}
// Seek
if (this->requestedSeek && this->requestedSeek.value() >= this->simTimeEpoch)
{
gzdbg << "Seeking to " << std::chrono::duration_cast<std::chrono::seconds>(
this->requestedSeek.value()).count() << "s." << std::endl;
this->realTimeFactor = 0;
this->currentInfo.dt = this->requestedSeek.value() -
this->currentInfo.simTime;
this->currentInfo.simTime = this->requestedSeek.value();
this->currentInfo.iterations = 0;
this->currentInfo.realTime = this->realTimeWatch.ElapsedRunTime();
this->requestedSeek = {};
return;
}
// Regular time flow
const double simTimeCount =
static_cast<double>(this->currentInfo.simTime.count());
const double realTimeCount =
static_cast<double>(this->currentInfo.realTime.count());
// Fill the current update info
this->currentInfo.realTime = this->realTimeWatch.ElapsedRunTime();
this->currentInfo.dt = std::chrono::steady_clock::duration::zero();
// In the case that networking is not running, or this is a primary.
// If this is a network secondary, this data is populated via the network.
if (!this->currentInfo.paused &&
(!this->networkMgr || this->networkMgr->IsPrimary()))
{
this->currentInfo.simTime += this->stepSize;
++this->currentInfo.iterations;
this->currentInfo.dt = this->stepSize;
}
const double simTimeDiff =
static_cast<double>(this->currentInfo.simTime.count()) - simTimeCount;
const double realTimeDiff =
static_cast<double>(this->currentInfo.realTime.count()) - realTimeCount;
if (realTimeDiff > 0)
{
this->realTimeFactor = simTimeDiff / realTimeDiff;
}
}
/////////////////////////////////////////////////
void SimulationRunner::UpdatePhysicsParams()
{
auto worldEntity =
this->entityCompMgr.EntityByComponents(components::World());
const auto physicsCmdComp =
this->entityCompMgr.Component<components::PhysicsCmd>(worldEntity);
if (!physicsCmdComp)
{
return;
}
auto physicsComp =
this->entityCompMgr.Component<components::Physics>(worldEntity);
const auto& physicsParams = physicsCmdComp->Data();
const auto newStepSize =
std::chrono::duration<double>(physicsParams.max_step_size());
const double newRTF = physicsParams.real_time_factor();
const double eps = 0.00001;
if (newStepSize != this->stepSize ||
std::abs(newRTF - this->desiredRtf) > eps)
{
bool updated = false;
// Make sure the values are valid before setting them
if (newStepSize.count() > 0.0)
{
this->SetStepSize(
std::chrono::duration_cast<std::chrono::steady_clock::duration>(
newStepSize));
physicsComp->Data().SetMaxStepSize(physicsParams.max_step_size());
updated = true;
}
if (newRTF > 0.0)
{
this->desiredRtf = newRTF;
this->updatePeriod = std::chrono::nanoseconds(
static_cast<int>(this->stepSize.count() / this->desiredRtf));
physicsComp->Data().SetRealTimeFactor(newRTF);
updated = true;
}
if (updated)
{
// Set as OneTimeChange to make sure the update is not missed
this->entityCompMgr.SetChanged(worldEntity, components::Physics::typeId,
ComponentState::OneTimeChange);
}
}
this->entityCompMgr.RemoveComponent<components::PhysicsCmd>(worldEntity);
}
/////////////////////////////////////////////////
void SimulationRunner::PublishStats()
{
GZ_PROFILE("SimulationRunner::PublishStats");
// Create the world statistics message.
msgs::WorldStatistics msg;
msg.set_real_time_factor(this->realTimeFactor);
auto realTimeSecNsec =
math::durationToSecNsec(this->currentInfo.realTime);
auto simTimeSecNsec =
math::durationToSecNsec(this->currentInfo.simTime);
msg.mutable_real_time()->set_sec(realTimeSecNsec.first);
msg.mutable_real_time()->set_nsec(realTimeSecNsec.second);
msg.mutable_sim_time()->set_sec(simTimeSecNsec.first);
msg.mutable_sim_time()->set_nsec(simTimeSecNsec.second);
msg.set_iterations(this->currentInfo.iterations);
msg.set_paused(this->currentInfo.paused);
msgs::Set(msg.mutable_step_size(), this->currentInfo.dt);
if (this->Stepping())
{
// (deprecated) Remove this header in Gazebo H
auto headerData = msg.mutable_header()->add_data();
headerData->set_key("step");
msg.set_stepping(true);
}
// Publish the stats message. The stats message is throttled.
this->statsPub.Publish(msg);
if (this->rootStatsPub.Valid())
this->rootStatsPub.Publish(msg);
// Create and publish the clock message. The clock message is not
// throttled.
msgs::Clock clockMsg;
clockMsg.mutable_real()->set_sec(realTimeSecNsec.first);
clockMsg.mutable_real()->set_nsec(realTimeSecNsec.second);
clockMsg.mutable_sim()->set_sec(simTimeSecNsec.first);
clockMsg.mutable_sim()->set_nsec(simTimeSecNsec.second);
clockMsg.mutable_system()->set_sec(GZ_SYSTEM_TIME_S());
clockMsg.mutable_system()->set_nsec(
GZ_SYSTEM_TIME_NS() - GZ_SYSTEM_TIME_S() * GZ_SEC_TO_NANO);
this->clockPub.Publish(clockMsg);
// Only publish to root topic if no others are.
if (this->rootClockPub.Valid())
this->rootClockPub.Publish(clockMsg);
}
namespace {
// Create an sdf::ElementPtr that corresponds to an empty `<plugin>` element.
sdf::ElementPtr createEmptyPluginElement()
{
auto plugin = std::make_shared<sdf::Element>();
sdf::initFile("plugin.sdf", plugin);
return plugin;
}
}
//////////////////////////////////////////////////
void SimulationRunner::AddSystem(const SystemPluginPtr &_system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf)
{
auto entity = _entity.value_or(worldEntity(this->entityCompMgr));
auto sdf = _sdf.value_or(createEmptyPluginElement());
this->systemMgr->AddSystem(_system, entity, sdf);
}
//////////////////////////////////////////////////
void SimulationRunner::AddSystem(
const std::shared_ptr<System> &_system,
std::optional<Entity> _entity,
std::optional<std::shared_ptr<const sdf::Element>> _sdf)
{
auto entity = _entity.value_or(worldEntity(this->entityCompMgr));
auto sdf = _sdf.value_or(createEmptyPluginElement());
this->systemMgr->AddSystem(_system, entity, sdf);
}
/////////////////////////////////////////////////
void SimulationRunner::ProcessSystemQueue()
{
auto pending = this->systemMgr->PendingCount();
if (0 == pending && !this->threadsNeedCleanUp)
return;
// If additional systems are to be added or have been removed,
// stop the existing threads.
this->StopWorkerThreads();
this->threadsNeedCleanUp = false;
this->systemMgr->ActivatePendingSystems();
unsigned int threadCount =
static_cast<unsigned int>(this->systemMgr->SystemsPostUpdate().size() + 1u);
gzdbg << "Creating PostUpdate worker threads: "
<< threadCount << std::endl;
this->postUpdateStartBarrier = std::make_unique<Barrier>(threadCount);
this->postUpdateStopBarrier = std::make_unique<Barrier>(threadCount);
this->postUpdateThreadsRunning = true;
int id = 0;
for (auto &system : this->systemMgr->SystemsPostUpdate())
{
gzdbg << "Creating postupdate worker thread (" << id << ")" << std::endl;
this->postUpdateThreads.push_back(std::thread([&, id]()
{
std::stringstream ss;
ss << "PostUpdateThread: " << id;
GZ_PROFILE_THREAD_NAME(ss.str().c_str());
while (this->postUpdateThreadsRunning)
{
this->postUpdateStartBarrier->Wait();
if (this->postUpdateThreadsRunning)
{
system->PostUpdate(this->currentInfo, this->entityCompMgr);
}
this->postUpdateStopBarrier->Wait();
}
gzdbg << "Exiting postupdate worker thread ("
<< id << ")" << std::endl;
}));
id++;
}
}
/////////////////////////////////////////////////
void SimulationRunner::UpdateSystems()
{
GZ_PROFILE("SimulationRunner::UpdateSystems");
// \todo(nkoenig) Systems used to be updated in parallel using
// a common::WorkerPool. There is overhead associated with
// this, most notably the creation and destruction of WorkOrders (see
// WorkerPool.cc). We could turn on parallel updates in the future, and/or
// turn it on if there are sufficient systems. More testing is required.
if (this->resetInitiated)
{
GZ_PROFILE("Reset");
this->systemMgr->Reset(this->currentInfo, this->entityCompMgr);
return;
}
{
GZ_PROFILE("PreUpdate");
for (auto& system : this->systemMgr->SystemsPreUpdate())
system->PreUpdate(this->currentInfo, this->entityCompMgr);
}
{
GZ_PROFILE("Update");
for (auto& system : this->systemMgr->SystemsUpdate())
system->Update(this->currentInfo, this->entityCompMgr);
}
{
GZ_PROFILE("PostUpdate");
this->entityCompMgr.LockAddingEntitiesToViews(true);
// If no systems implementing PostUpdate have been added, then
// the barriers will be uninitialized, so guard against that condition.
if (this->postUpdateStartBarrier && this->postUpdateStopBarrier)
{
// Release the GIL from the main thread to run PostUpdate threads which
// might be calling into python. The system that does call into python
// needs to lock the GIL from its thread.
MaybeGilScopedRelease release;
this->postUpdateStartBarrier->Wait();
this->postUpdateStopBarrier->Wait();
}
this->entityCompMgr.LockAddingEntitiesToViews(false);
}
}
/////////////////////////////////////////////////
void SimulationRunner::Stop()
{
this->eventMgr.Emit<events::Stop>();
}
/////////////////////////////////////////////////
void SimulationRunner::OnStop()
{
this->stopReceived = true;
this->running = false;
}
/////////////////////////////////////////////////
void SimulationRunner::StopWorkerThreads()
{
this->postUpdateThreadsRunning = false;
if (this->postUpdateStartBarrier)
{
this->postUpdateStartBarrier->Cancel();
}
if (this->postUpdateStopBarrier)
{
this->postUpdateStopBarrier->Cancel();
}
for (auto &thread : this->postUpdateThreads)
{
thread.join();
}
this->postUpdateThreads.clear();
}
/////////////////////////////////////////////////
bool SimulationRunner::Run(const uint64_t _iterations)
{
// \todo(nkoenig) Systems will need a an update structure, such as
// priorties, or a dependency chain.
//
// \todo(nkoenig) We should implement the two-phase update detailed
// in the design.
GZ_PROFILE_THREAD_NAME("SimulationRunner");
// Initialize network communications.
if (this->networkMgr)
{
gzdbg << "Initializing network configuration" << std::endl;
this->networkMgr->Handshake();
// Secondaries are stepped through the primary, just keep alive until
// simulation is over
if (this->networkMgr->IsSecondary())
{
gzdbg << "Secondary running." << std::endl;
while (!this->stopReceived)
{
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
gzdbg << "Secondary finished run." << std::endl;
return true;
}
}
// Keep track of wall clock time. Only start the realTimeWatch if this
// runner is not paused.
if (!this->currentInfo.paused)
this->realTimeWatch.Start();
// Variables for time keeping.
std::chrono::steady_clock::time_point startTime;
std::chrono::steady_clock::duration sleepTime;
std::chrono::steady_clock::duration actualSleep;
this->running = true;
// Create the world statistics publisher.
if (!this->statsPub.Valid())
{
transport::AdvertiseMessageOptions advertOpts;
// publish 10 world statistics msgs/second. A smaller number isn't used
// because the GUI listens to these msgs to receive confirmation that
// pause/play GUI requests have been processed by the server, so we want to
// make sure that GUI requests are acknowledged quickly (see
// https://github.com/gazebosim/gz-gui/pull/306 and
// https://github.com/gazebosim/gz-sim/pull/1163)
advertOpts.SetMsgsPerSec(10);
this->statsPub = this->node->Advertise<msgs::WorldStatistics>(
"stats", advertOpts);
}
if (!this->rootStatsPub.Valid())
{
// Check for the existence of other publishers on `/stats`
std::vector<transport::MessagePublisher> publishers;
std::vector<transport::MessagePublisher> subscribers;
this->node->TopicInfo("/stats", publishers, subscribers);
if (!publishers.empty())
{
gzwarn << "Found additional publishers on /stats," <<
" using namespaced stats topic only" << std::endl;
gzdbg << "Publishers [Address, Message Type]:\n";
/// List the publishers
for (auto & pub : publishers)
{
gzdbg << " " << pub.Addr() << ", "
<< pub.MsgTypeName() << std::endl;
}
}
else
{
gzmsg << "Found no publishers on /stats, adding root stats topic"
<< std::endl;
this->rootStatsPub = this->node->Advertise<msgs::WorldStatistics>(
"/stats");
}
}
// Create the clock publisher.
if (!this->clockPub.Valid())
this->clockPub = this->node->Advertise<msgs::Clock>("clock");
// Create the global clock publisher.
if (!this->rootClockPub.Valid())
{
// Check for the existence of other publishers on `/clock`
std::vector<transport::MessagePublisher> publishers;
std::vector<transport::MessagePublisher> subscribers;
this->node->TopicInfo("/clock", publishers, subscribers);
if (!publishers.empty())
{
gzwarn << "Found additional publishers on /clock," <<
" using namespaced clock topic only" << std::endl;
gzdbg << "Publishers [Address, Message Type]:\n";
/// List the publishers
for (auto & pub : publishers)
{
gzdbg << " " << pub.Addr() << ", "
<< pub.MsgTypeName() << std::endl;
}
}
else
{
gzmsg << "Found no publishers on /clock, adding root clock topic"
<< std::endl;
this->rootClockPub = this->node->Advertise<msgs::Clock>(
"/clock");
}
}
// Keep number of iterations requested by caller
uint64_t processedIterations{0};
// Execute all the systems until we are told to stop, or the number of
// iterations is reached.
while (this->running && (_iterations == 0 ||
processedIterations < _iterations))
{
GZ_PROFILE("SimulationRunner::Run - Iteration");
// Update the step size and desired rtf
this->UpdatePhysicsParams();
// Compute the time to sleep in order to match, as closely as possible,
// the update period.
sleepTime = 0ns;
actualSleep = 0ns;
sleepTime = std::max(0ns, this->prevUpdateRealTime +
this->updatePeriod - std::chrono::steady_clock::now() -
this->sleepOffset);
// Only sleep if needed.
if (sleepTime > 0ns)
{
GZ_PROFILE("Sleep");
// Get the current time, sleep for the duration needed to match the
// updatePeriod, and then record the actual time slept.
startTime = std::chrono::steady_clock::now();
std::this_thread::sleep_for(sleepTime);
actualSleep = std::chrono::steady_clock::now() - startTime;
}
// Exponentially average out the difference between expected sleep time
// and actual sleep time.
this->sleepOffset =
std::chrono::duration_cast<std::chrono::nanoseconds>(
(actualSleep - sleepTime) * 0.01 + this->sleepOffset * 0.99);
// Update time information. This will update the iteration count, RTF,
// and other values.
this->UpdateCurrentInfo();
if (this->resetInitiated)
{
this->entityCompMgr.ResetTo(this->initialEntityCompMgr);
}
if (!this->currentInfo.paused)
{
processedIterations++;
}
// If network, wait for network step, otherwise do our own step
if (this->networkMgr)
{
auto netPrimary =
dynamic_cast<NetworkManagerPrimary *>(this->networkMgr.get());
netPrimary->Step(this->currentInfo);
}
else
{
this->Step(this->currentInfo);
}
// Handle Server::RunOnce(false) in which a single paused run is executed
if (this->currentInfo.paused && this->blockingPausedStepPending)
{
processedIterations++;
this->currentInfo.iterations++;
this->blockingPausedStepPending = false;
}
this->resetInitiated = false;
}
this->running = false;
return true;
}
/////////////////////////////////////////////////
void SimulationRunner::Step(const UpdateInfo &_info)
{
GZ_PROFILE("SimulationRunner::Step");
this->currentInfo = _info;
// Process new ECM state information, typically sent from the GUI after
// a change was made to the GUI's ECM.
this->ProcessNewWorldControlState();
// Publish info
this->PublishStats();
// Record when the update step starts.
this->prevUpdateRealTime = std::chrono::steady_clock::now();
this->levelMgr->UpdateLevelsState();
// Handle pending systems
this->ProcessSystemQueue();
// Handle entities that need to be recreated.
// Put in a request to mark them as removed so that in the UpdateSystem call
// the systems can remove them first before new ones are created. This is
// so that we can recreate entities with the same name.
this->ProcessRecreateEntitiesRemove();
// handle systems that need to be added
this->systemMgr->ProcessPendingEntitySystems();
// Update all the systems.
this->UpdateSystems();
if (!this->Paused() && this->requestedRunToSimTime &&
this->requestedRunToSimTime.value() > this->simTimeEpoch &&
this->currentInfo.simTime >= this->requestedRunToSimTime.value())
{
this->SetPaused(true);
this->requestedRunToSimTime = {};
}
if (!this->Paused() && this->pendingSimIterations > 0)
{
// Decrement the pending sim iterations, if there are any.
--this->pendingSimIterations;
// If this is was the last sim iterations, then re-pause simulation.
if (this->pendingSimIterations <= 0)
{
this->SetPaused(true);
}
}
// Process world control messages.
this->ProcessMessages();
// Clear all new entities
this->entityCompMgr.ClearNewlyCreatedEntities();
// Recreate any entities that have the Recreate component
// The entities will have different Entity ids but keep the same name
// Make sure this happens after ClearNewlyCreatedEntities, otherwise the
// cloned entities will loose their "New" state.
this->ProcessRecreateEntitiesCreate();
// Process entity removals.
this->systemMgr->ProcessRemovedEntities(this->entityCompMgr,
this->threadsNeedCleanUp);
this->entityCompMgr.ProcessRemoveEntityRequests();
// Process components removals
this->entityCompMgr.ClearRemovedComponents();
// Each network manager takes care of marking its components as unchanged
if (!this->networkMgr)
this->entityCompMgr.SetAllComponentsUnchanged();
}
//////////////////////////////////////////////////
void SimulationRunner::LoadPlugin(const Entity _entity,
const sdf::Plugin &_plugin)
{
this->systemMgr->LoadPlugin(_entity, _plugin);
}
//////////////////////////////////////////////////
void SimulationRunner::LoadServerPlugins(
const std::list<ServerConfig::PluginInfo> &_plugins)
{
// \todo(nkoenig) Remove plugins from the server config after they have
// been added. We might not want to do this if we want to support adding
// the same plugin to multiple entities, for example via a regex
// expression.
//
// Check plugins from the ServerConfig for matching entities.
for (const ServerConfig::PluginInfo &plugin : _plugins)
{
// \todo(anyone) Type + name is not enough to uniquely identify an entity
// \todo(louise) The runner shouldn't care about specific components, this
// logic should be moved somewhere else.
Entity entity{kNullEntity};
if ("model" == plugin.EntityType())
{
entity = this->entityCompMgr.EntityByComponents(
components::Name(plugin.EntityName()), components::Model());
}
else if ("world" == plugin.EntityType())
{
// Allow wildcard for world name
if (plugin.EntityName() == "*")
{
entity = this->entityCompMgr.EntityByComponents(components::World());
}
else
{
entity = this->entityCompMgr.EntityByComponents(
components::Name(plugin.EntityName()), components::World());
}
}
else if ("sensor" == plugin.EntityType())
{
// TODO(louise) Use scoped names for models and worlds too
auto sensors = this->entityCompMgr.EntitiesByComponents(
components::Sensor());
for (auto sensor : sensors)
{
if (scopedName(sensor, this->entityCompMgr, "::", false) ==
plugin.EntityName())
{
entity = sensor;
break;
}
}
}
else if ("visual" == plugin.EntityType())