forked from gazebosim/gz-sim
-
Notifications
You must be signed in to change notification settings - Fork 0
/
EntityComponentManager.cc
2316 lines (2019 loc) · 76.8 KB
/
EntityComponentManager.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
863
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 "gz/sim/EntityComponentManager.hh"
#include "EntityComponentManagerDiff.hh"
#include <map>
#include <memory>
#include <set>
#include <sstream>
#include <string>
#include <unordered_map>
#include <unordered_set>
#include <utility>
#include <vector>
#include <gz/common/Profiler.hh>
#include <gz/math/graph/GraphAlgorithms.hh>
#include "gz/sim/components/CanonicalLink.hh"
#include "gz/sim/components/ChildLinkName.hh"
#include "gz/sim/components/Component.hh"
#include "gz/sim/components/Factory.hh"
#include "gz/sim/components/Joint.hh"
#include "gz/sim/components/Link.hh"
#include "gz/sim/components/Name.hh"
#include "gz/sim/components/ParentEntity.hh"
#include "gz/sim/components/ParentLinkName.hh"
#include "gz/sim/components/Recreate.hh"
#include "gz/sim/components/World.hh"
using namespace gz;
using namespace sim;
class gz::sim::EntityComponentManagerPrivate
{
/// \brief Implementation of the CreateEntity function, which takes a specific
/// entity as input.
/// \param[in] _entity Entity to be created.
/// \return Created entity, which should match the input.
public: Entity CreateEntityImplementation(Entity _entity);
/// \brief Recursively insert an entity and all its descendants into a given
/// set.
/// \param[in] _entity Entity to be inserted.
/// \param[in, out] _set Set to be filled.
public: void InsertEntityRecursive(Entity _entity,
std::unordered_set<Entity> &_set);
/// \brief Recursively erase an entity and all its descendants from a given
/// set.
/// \param[in] _entity Entity to be erased.
/// \param[in, out] _set Set to erase from.
public: void EraseEntityRecursive(Entity _entity,
std::unordered_set<Entity> &_set);
/// \brief Allots the work for multiple threads prior to running
/// `AddEntityToMessage`.
public: void CalculateStateThreadLoad();
/// \brief Copies the contents of `_from` into this object.
/// \note This is a member function instead of a copy constructor so that
/// it can have additional parameters if the need arises in the future.
/// Additionally, not every data member is copied making its behavior
/// different from what would be expected from a copy constructor.
/// \param[in] _from Object to copy from
public: void CopyFrom(const EntityComponentManagerPrivate &_from);
/// \brief Create a message for the removed components
/// \param[in] _entity Entity with the removed components
/// \param[in, out] _msg Entity message
/// \param[in] _types _types Type IDs of components to be serialized. Leave
/// empty to get all removed components.
public: void SetRemovedComponentsMsgs(Entity &_entity,
msgs::SerializedEntity *_msg,
const std::unordered_set<ComponentTypeId> &_types = {});
/// \brief Create a message for the removed components
/// \param[in] _entity Entity with the removed components
/// \param[in, out] _msg State message
/// \param[in] _types _types Type IDs of components to be serialized. Leave
/// empty to get all removed components.
public: void SetRemovedComponentsMsgs(Entity &_entity,
msgs::SerializedStateMap &_msg,
const std::unordered_set<ComponentTypeId> &_types = {});
/// \brief Add newly modified (created/modified/removed) components to
/// modifiedComponents list. The entity is added to the list when it is not
/// a newly created entity or is not an entity to be removed
/// \param[in] _entity Entity that has component newly modified
public: void AddModifiedComponent(const Entity &_entity);
/// \brief Check whether a component is marked as a component that is
/// currently removed or not.
/// \param[in] _entity The entity
/// \param[in] _typeId The type ID for the component that belongs to _entity
/// \return True if _entity has a component of type _typeId that is currently
/// removed. False otherwise
public: bool ComponentMarkedAsRemoved(const Entity _entity,
const ComponentTypeId _typeId) const;
/// \brief Set a cloned joint's parent or child link name.
/// \param[in] _joint The cloned joint.
/// \param[in] _originalLink The original joint's parent or child link.
/// \param[in] _ecm Entity component manager.
/// \tparam The component type, which must be either
/// components::ParentLinkName or components::ChildLinkName
/// \return True if _joint's parent or child link name was set.
/// False otherwise
/// \note This method should only be called in EntityComponentManager::Clone.
/// This is a temporary workaround until we find a way to clone entites and
/// components that don't require special treatment for particular component
/// types.
public: template<typename ComponentTypeT>
bool ClonedJointLinkName(Entity _joint, Entity _originalLink,
EntityComponentManager *_ecm);
/// \brief All component types that have ever been created.
public: std::unordered_set<ComponentTypeId> createdCompTypes;
/// \brief A graph holding all entities, arranged according to their
/// parenting.
public: EntityGraph entities;
/// \brief Components that have been changed through a periodic change.
/// The key is the type of component which has changed, and the value is the
/// entities that had this type of component changed.
public: std::unordered_map<ComponentTypeId, std::unordered_set<Entity>>
periodicChangedComponents;
/// \brief Components that have been changed through a one-time change.
/// The key is the type of component which has changed, and the value is the
/// entities that had this type of component changed.
public: std::unordered_map<ComponentTypeId, std::unordered_set<Entity>>
oneTimeChangedComponents;
/// \brief Entities that have just been created
public: std::unordered_set<Entity> newlyCreatedEntities;
/// \brief Entities that need to be removed.
public: std::unordered_set<Entity> toRemoveEntities;
/// \brief Entities that have components newly modified
/// (created/modified/removed) but are not entities that have been
/// newly created or removed (ie. newlyCreatedEntities or toRemoveEntities).
/// This is used for the ChangedState functions
public: std::unordered_set<Entity> modifiedComponents;
/// \brief Flag that indicates if all entities should be removed.
public: bool removeAllEntities{false};
/// \brief A mutex to protect newly created entities.
public: std::mutex entityCreatedMutex;
/// \brief A mutex to protect entity remove.
public: std::mutex entityRemoveMutex;
/// \brief A mutex to protect from concurrent writes to views
public: mutable std::mutex viewsMutex;
/// \brief A mutex to protect removed components
public: mutable std::mutex removedComponentsMutex;
/// \brief The set of all views.
/// The value is a pair of the view itself and a mutex that can be used for
/// locking the view to ensure thread safety when adding entities to the view.
public: mutable std::unordered_map<detail::ComponentTypeKey,
std::pair<std::unique_ptr<detail::BaseView>,
std::unique_ptr<std::mutex>>, detail::ComponentTypeHasher> views;
/// \brief A flag that indicates whether views should be locked while adding
/// new entities to them or not.
public: bool lockAddEntitiesToViews{false};
/// \brief Cache of previously queried descendants. The key is the parent
/// entity for which descendants were queried, and the value are all its
/// descendants.
public: mutable std::unordered_map<Entity, std::unordered_set<Entity>>
descendantCache;
/// \brief Keep track of entities already used to ensure uniqueness.
public: uint64_t entityCount{0};
/// \brief Unordered map of removed components. The key is the entity to
/// which belongs the component, and the value is a set of the component types
/// being removed.
public: std::unordered_map<Entity, std::unordered_set<ComponentTypeId>>
removedComponents;
/// \brief All components that have been removed. The difference between
/// removedComponents and componentsMarkedAsRemoved is that removedComponents
/// keeps track of components that were removed in the current simulation
/// step, while componentsMarkedAsRemoved keeps track of components that are
/// currently removed based on all simulation steps.
public: std::unordered_map<Entity, std::unordered_set<ComponentTypeId>>
componentsMarkedAsRemoved;
/// \brief A map of an entity to its components
public: std::unordered_map<Entity,
std::vector<std::unique_ptr<components::BaseComponent>>>
componentStorage;
/// \brief A map that keeps track of where each type of component is
/// located in the componentStorage vector. Since the componentStorage vector
/// is of type BaseComponent, we need to keep track of which component type
/// corresponds to a given index in the vector so that we can cast the
/// BaseComponent to this type if needed.
///
/// The key of this map is the Entity, and the value is a map of the
/// component type to the corresponding index in the
/// componentStorage vector (a component of a particular type is
/// only a key for the value map if a component of this type exists in
/// the componentStorage vector)
///
/// NOTE: Any modification of this data structure must be followed
/// by setting `componentTypeIndexDirty` to true.
public: std::unordered_map<Entity,
std::unordered_map<ComponentTypeId, std::size_t>>
componentTypeIndex;
/// \brief A vector of iterators to evenly distributed spots in the
/// `componentTypeIndex` map. Threads in the `State` function use this
/// vector for easy access of their pre-allocated work. This vector
/// is recalculated if `componentTypeIndex` is changed (when
/// `componentTypeIndexDirty` == true).
public: std::vector<std::unordered_map<Entity,
std::unordered_map<ComponentTypeId, std::size_t>>::iterator>
componentTypeIndexIterators;
/// \brief True if the componentTypeIndex map was changed. Primarily used
/// by the multithreading functionality in `State()` to allocate work to
/// each thread.
public: bool componentTypeIndexDirty{true};
/// \brief During cloning, we populate two maps:
/// - map of cloned model entities to the non-cloned model's canonical link
/// - map of non-cloned canonical links to the cloned canonical link
/// After cloning is done, these maps can be used to update the cloned model's
/// canonical link to be the cloned canonical link instead of the original
/// model's canonical link. We populate maps during cloning and then update
/// canonical links after cloning since cloning is done top-down, and
/// canonical links are children of models (when a model is cloned, its
/// canonical link has not been cloned yet, so we have no way of knowing what
/// to set the cloned model's canonical link to until the canonical link has
/// been cloned).
/// \TODO(anyone) We shouldn't be giving canonical links special treatment.
/// This may happen to any component that holds an Entity, so we should figure
/// out a way to generalize this for any such component.
public: std::unordered_map<Entity, Entity> oldModelCanonicalLink;
/// \brief See above
public: std::unordered_map<Entity, Entity> oldToClonedCanonicalLink;
/// \brief During cloning, we populate two maps:
/// - map of link entities to their cloned link
/// - map of cloned joint entities to the original joint entity's parent and
/// child links
/// After cloning is done, these maps can be used to update the cloned joint
/// entity's parent and child links to the cloned parent and child links.
/// \TODO(anyone) We shouldn't be giving joints special treatment.
/// We should figure out a way to update a joint's parent/child links without
/// having to explicitly search/track for the cloned links.
public: std::unordered_map<Entity, Entity> originalToClonedLink;
/// \brief See above
/// The key is the cloned joint entity, and the value is a pair where the
/// first element is the original joint's parent link, and the second element
/// is the original joint's child link
public: std::unordered_map<Entity, std::pair<Entity, Entity>>
clonedToOriginalJointLinks;
/// \brief Set of entities that are prevented from removal.
public: std::unordered_set<Entity> pinnedEntities;
};
//////////////////////////////////////////////////
EntityComponentManager::EntityComponentManager()
: dataPtr(new EntityComponentManagerPrivate)
{
}
//////////////////////////////////////////////////
EntityComponentManager::~EntityComponentManager() = default;
//////////////////////////////////////////////////
void EntityComponentManagerPrivate::CopyFrom(
const EntityComponentManagerPrivate &_from)
{
this->createdCompTypes = _from.createdCompTypes;
this->entities = _from.entities;
this->periodicChangedComponents = _from.periodicChangedComponents;
this->oneTimeChangedComponents = _from.oneTimeChangedComponents;
this->newlyCreatedEntities = _from.newlyCreatedEntities;
this->toRemoveEntities = _from.toRemoveEntities;
this->modifiedComponents = _from.modifiedComponents;
this->removeAllEntities = _from.removeAllEntities;
this->views.clear();
this->lockAddEntitiesToViews = _from.lockAddEntitiesToViews;
this->descendantCache.clear();
this->entityCount = _from.entityCount;
this->removedComponents = _from.removedComponents;
this->componentsMarkedAsRemoved = _from.componentsMarkedAsRemoved;
for (const auto &[entity, comps] : _from.componentStorage)
{
this->componentStorage[entity].clear();
for (const auto &comp : comps)
{
this->componentStorage[entity].emplace_back(comp->Clone());
}
}
this->componentTypeIndex = _from.componentTypeIndex;
this->componentTypeIndexIterators.clear();
this->componentTypeIndexDirty = true;
// Not copying maps related to cloning since they are transient variables
// that are used as return values of some member functions.
this->pinnedEntities = _from.pinnedEntities;
}
//////////////////////////////////////////////////
size_t EntityComponentManager::EntityCount() const
{
return this->dataPtr->entities.Vertices().size();
}
/////////////////////////////////////////////////
Entity EntityComponentManager::CreateEntity()
{
Entity entity = this->dataPtr->entityCount;
if (entity == std::numeric_limits<uint64_t>::max())
{
gzwarn << "Reached maximum number of entities [" << entity << "]"
<< std::endl;
return entity;
}
return this->dataPtr->CreateEntityImplementation(entity);
}
/////////////////////////////////////////////////
Entity EntityComponentManagerPrivate::CreateEntityImplementation(Entity _entity)
{
GZ_PROFILE("EntityComponentManager::CreateEntityImplementation");
this->entities.AddVertex(std::to_string(_entity), _entity, _entity);
// Add entity to the list of newly created entities
{
std::lock_guard<std::mutex> lock(this->entityCreatedMutex);
this->newlyCreatedEntities.insert(_entity);
}
// Reset descendants cache
this->descendantCache.clear();
const auto result = this->componentStorage.insert({_entity,
std::vector<std::unique_ptr<components::BaseComponent>>()});
if (!result.second)
{
gzwarn << "Attempted to add entity [" << _entity
<< "] to component storage, but this entity is already in component "
<< "storage.\n";
}
const auto result2 = this->componentTypeIndex.insert({_entity,
std::unordered_map<ComponentTypeId, std::size_t>()});
if (!result2.second)
{
gzwarn << "Attempted to add entity [" << _entity
<< "] to component type index, but this entity is already in component "
<< "type index.\n";
}
return _entity;
}
/////////////////////////////////////////////////
Entity EntityComponentManager::Clone(Entity _entity, Entity _parent,
const std::string &_name, bool _allowRename)
{
// Clear maps so they're populated for the entity being cloned
this->dataPtr->oldToClonedCanonicalLink.clear();
this->dataPtr->oldModelCanonicalLink.clear();
this->dataPtr->originalToClonedLink.clear();
this->dataPtr->clonedToOriginalJointLinks.clear();
auto clonedEntity = this->CloneImpl(_entity, _parent, _name, _allowRename);
if (kNullEntity != clonedEntity)
{
// make sure that cloned models have their canonical link updated to the
// cloned canonical link
for (const auto &[clonedModel, oldCanonicalLink] :
this->dataPtr->oldModelCanonicalLink)
{
auto iter = this->dataPtr->oldToClonedCanonicalLink.find(
oldCanonicalLink);
if (iter == this->dataPtr->oldToClonedCanonicalLink.end())
{
gzerr << "Error: attempted to clone model(s) with canonical link(s), "
<< "but entity [" << oldCanonicalLink << "] was not cloned as a "
<< "canonical link." << std::endl;
continue;
}
const auto clonedCanonicalLink = iter->second;
this->SetComponentData<components::ModelCanonicalLink>(clonedModel,
clonedCanonicalLink);
}
// make sure that cloned joints have their parent/child links
// updated to the cloned parent/child links
for (const auto &[clonedJoint, originalJointLinks] :
this->dataPtr->clonedToOriginalJointLinks)
{
auto originalParentLink = originalJointLinks.first;
if (!this->dataPtr->ClonedJointLinkName<components::ParentLinkName>(
clonedJoint, originalParentLink, this))
{
gzerr << "Error updating the cloned parent link name for cloned "
<< "joint [" << clonedJoint << "]\n";
continue;
}
auto originalChildLink = originalJointLinks.second;
if (!this->dataPtr->ClonedJointLinkName<components::ChildLinkName>(
clonedJoint, originalChildLink, this))
{
gzerr << "Error updating the cloned child link name for cloned "
<< "joint [" << clonedJoint << "]\n";
continue;
}
}
}
return clonedEntity;
}
/////////////////////////////////////////////////
Entity EntityComponentManager::CloneImpl(Entity _entity, Entity _parent,
const std::string &_name, bool _allowRename)
{
auto uniqueNameGenerated = false;
// Before cloning, we should make sure that:
// 1. The entity to be cloned exists
// 2. We can generate a unique name for the cloned entity
if (!this->HasEntity(_entity))
{
gzerr << "Requested to clone entity [" << _entity
<< "], but this entity does not exist." << std::endl;
return kNullEntity;
}
else if (!_name.empty() && !_allowRename)
{
// Get the entity's original parent. This is used to make sure we get
// the correct entity. For example, two different models may have a
// child with the name "link".
auto origParentComp =
this->Component<components::ParentEntity>(_entity);
// If there is an entity with the same name and user indicated renaming is
// not allowed then return null entity.
// If the entity or one of its ancestor has a Recreate component then carry
// on since the ECM is supposed to create a new entity with the same name.
Entity ent = this->EntityByComponents(components::Name(_name),
components::ParentEntity(origParentComp->Data()));
bool hasRecreateComp = false;
Entity recreateEnt = ent;
while (recreateEnt != kNullEntity && !hasRecreateComp)
{
hasRecreateComp = this->Component<components::Recreate>(recreateEnt) !=
nullptr;
auto parentComp = this->Component<components::ParentEntity>(recreateEnt);
recreateEnt = parentComp ? parentComp->Data() : kNullEntity;
}
if (kNullEntity != ent && !hasRecreateComp)
{
gzerr << "Requested to clone entity [" << _entity
<< "] with a name of [" << _name << "], but another entity already "
<< "has this name." << std::endl;
return kNullEntity;
}
uniqueNameGenerated = true;
}
auto clonedEntity = this->CreateEntity();
if (_parent != kNullEntity)
{
this->SetParentEntity(clonedEntity, _parent);
this->CreateComponent(clonedEntity, components::ParentEntity(_parent));
}
// make sure that the cloned entity has a unique name
auto clonedName = _name;
if (!uniqueNameGenerated)
{
if (clonedName.empty())
{
auto originalNameComp = this->Component<components::Name>(_entity);
clonedName =
originalNameComp ? originalNameComp->Data() : "cloned_entity";
}
uint64_t suffix = 1;
while (kNullEntity != this->EntityByComponents(
components::Name(clonedName "_" std::to_string(suffix))))
suffix ;
clonedName = "_" std::to_string(suffix);
}
this->CreateComponent(clonedEntity, components::Name(clonedName));
// copy all components from _entity to clonedEntity
for (const auto &type : this->ComponentTypes(_entity))
{
// skip the Name and ParentEntity components since those were already
// handled above
if ((type == components::Name::typeId) ||
(type == components::ParentEntity::typeId))
continue;
auto originalComp = this->ComponentImplementation(_entity, type);
auto clonedComp = originalComp->Clone();
auto updateData =
this->CreateComponentImplementation(clonedEntity, type, clonedComp.get());
if (updateData)
{
// When a cloned entity is removed, it erases all components/data so a new
// cloned entity should not have components to be updated
// LCOV_EXCL_START
gzerr << "Internal error: The component's data needs to be updated but "
<< "this should not happen." << std::endl;
// LCOV_EXCL_STOP
}
}
// keep track of canonical link information (for clones of models, the cloned
// model should not share the same canonical link as the original model)
if (auto modelCanonLinkComp =
this->Component<components::ModelCanonicalLink>(clonedEntity))
{
// we're cloning a model, so we map the cloned model to the original
// model's canonical link
this->dataPtr->oldModelCanonicalLink[clonedEntity] =
modelCanonLinkComp->Data();
}
else if (this->Component<components::CanonicalLink>(clonedEntity))
{
// we're cloning a canonical link, so we map the original canonical link
// to the cloned canonical link
this->dataPtr->oldToClonedCanonicalLink[_entity] = clonedEntity;
}
// keep track of all joints and links that have been cloned so that cloned
// joints can be updated to their cloned parent/child links
if (this->Component<components::Joint>(clonedEntity))
{
// this is a joint, so we need to find the original joint's parent and child
// link entities
Entity originalParentLink = kNullEntity;
Entity originalChildLink = kNullEntity;
auto origParentComp =
this->Component<components::ParentEntity>(_entity);
const auto &parentName =
this->Component<components::ParentLinkName>(_entity);
if (parentName && origParentComp)
{
// Handle the case where the parent link name is the world.
if (common::lowercase(parentName->Data()) == "world")
{
originalParentLink = this->Component<components::ParentEntity>(
origParentComp->Data())->Data();
}
else
{
originalParentLink =
this->EntityByComponents<components::Name, components::ParentEntity>(
components::Name(parentName->Data()),
components::ParentEntity(origParentComp->Data()));
}
}
const auto &childName = this->Component<components::ChildLinkName>(_entity);
if (childName && origParentComp)
{
originalChildLink =
this->EntityByComponents<components::Name, components::ParentEntity>(
components::Name(childName->Data()),
components::ParentEntity(origParentComp->Data()));
}
if (!originalParentLink || !originalChildLink)
{
gzerr << "The cloned joint entity [" << clonedEntity << "] was unable "
<< "to find the original joint entity's parent and/or child link.\n";
this->RequestRemoveEntity(clonedEntity);
return kNullEntity;
}
this->dataPtr->clonedToOriginalJointLinks[clonedEntity] =
{originalParentLink, originalChildLink};
}
else if (this->Component<components::Link>(clonedEntity) ||
this->Component<components::CanonicalLink>(clonedEntity))
{
// save a mapping between the original link and the cloned link
this->dataPtr->originalToClonedLink[_entity] = clonedEntity;
}
for (const auto &childEntity :
this->EntitiesByComponents(components::ParentEntity(_entity)))
{
std::string name;
if (!_allowRename)
{
auto nameComp = this->Component<components::Name>(childEntity);
name = nameComp->Data();
}
auto clonedChild = this->CloneImpl(childEntity, clonedEntity, name,
_allowRename);
if (kNullEntity == clonedChild)
{
gzerr << "Cloning child entity [" << childEntity << "] failed.\n";
this->RequestRemoveEntity(clonedEntity);
return kNullEntity;
}
}
return clonedEntity;
}
/////////////////////////////////////////////////
void EntityComponentManager::ClearNewlyCreatedEntities()
{
std::lock_guard<std::mutex> lock(this->dataPtr->entityCreatedMutex);
this->dataPtr->newlyCreatedEntities.clear();
for (auto &view : this->dataPtr->views)
{
view.second.first->ResetNewEntityState();
}
}
/////////////////////////////////////////////////
bool EntityComponentManager::HasRemovedComponents() const
{
std::lock_guard<std::mutex> lock(this->dataPtr->removedComponentsMutex);
return !this->dataPtr->removedComponents.empty();
}
/////////////////////////////////////////////////
void EntityComponentManager::ClearRemovedComponents()
{
std::lock_guard<std::mutex> lock(this->dataPtr->removedComponentsMutex);
this->dataPtr->removedComponents.clear();
}
/////////////////////////////////////////////////
void EntityComponentManagerPrivate::InsertEntityRecursive(Entity _entity,
std::unordered_set<Entity> &_set)
{
for (const auto &vertex : this->entities.AdjacentsFrom(_entity))
{
this->InsertEntityRecursive(vertex.first, _set);
}
_set.insert(_entity);
}
/////////////////////////////////////////////////
void EntityComponentManagerPrivate::EraseEntityRecursive(Entity _entity,
std::unordered_set<Entity> &_set)
{
for (const auto &vertex : this->entities.AdjacentsFrom(_entity))
{
this->EraseEntityRecursive(vertex.first, _set);
}
_set.erase(_entity);
}
/////////////////////////////////////////////////
void EntityComponentManager::RequestRemoveEntity(Entity _entity,
bool _recursive)
{
// Store the to-be-removed entities in a temporary set so we can call
// UpdateViews on each of them
std::unordered_set<Entity> tmpToRemoveEntities;
if (!_recursive)
{
tmpToRemoveEntities.insert(_entity);
}
else
{
this->dataPtr->InsertEntityRecursive(_entity, tmpToRemoveEntities);
}
// Remove entities from tmpToRemoveEntities that are marked as
// unremovable.
for (auto iter = tmpToRemoveEntities.begin();
iter != tmpToRemoveEntities.end();)
{
if (std::find(this->dataPtr->pinnedEntities.begin(),
this->dataPtr->pinnedEntities.end(), *iter) !=
this->dataPtr->pinnedEntities.end())
{
iter = tmpToRemoveEntities.erase(iter);
}
else
{
iter;
}
}
{
std::lock_guard<std::mutex> lock(this->dataPtr->entityRemoveMutex);
this->dataPtr->toRemoveEntities.insert(tmpToRemoveEntities.begin(),
tmpToRemoveEntities.end());
}
for (const auto &removedEntity : tmpToRemoveEntities)
{
for (auto &view : this->dataPtr->views)
{
view.second.first->MarkEntityToRemove(removedEntity);
}
}
}
/////////////////////////////////////////////////
void EntityComponentManager::RequestRemoveEntities()
{
if (this->dataPtr->pinnedEntities.empty())
{
{
std::lock_guard<std::mutex> lock(this->dataPtr->entityRemoveMutex);
this->dataPtr->removeAllEntities = true;
}
this->RebuildViews();
}
else
{
std::unordered_set<Entity> tmpToRemoveEntities;
// Store the to-be-removed entities in a temporary set so we can
// mark each of them to be removed from views that contain them.
for (const auto &vertex : this->dataPtr->entities.Vertices())
{
if (std::find(this->dataPtr->pinnedEntities.begin(),
this->dataPtr->pinnedEntities.end(), vertex.first) ==
this->dataPtr->pinnedEntities.end())
{
tmpToRemoveEntities.insert(vertex.first);
}
}
{
std::lock_guard<std::mutex> lock(this->dataPtr->entityRemoveMutex);
this->dataPtr->toRemoveEntities.insert(tmpToRemoveEntities.begin(),
tmpToRemoveEntities.end());
}
for (const auto &removedEntity : tmpToRemoveEntities)
{
for (auto &view : this->dataPtr->views)
{
view.second.first->MarkEntityToRemove(removedEntity);
}
}
}
}
/////////////////////////////////////////////////
void EntityComponentManager::ProcessRemoveEntityRequests()
{
GZ_PROFILE("EntityComponentManager::ProcessRemoveEntityRequests");
std::lock_guard<std::mutex> lock(this->dataPtr->entityRemoveMutex);
// Short-cut if erasing all entities
if (this->dataPtr->removeAllEntities)
{
GZ_PROFILE("RemoveAll");
this->dataPtr->removeAllEntities = false;
this->dataPtr->entities = EntityGraph();
this->dataPtr->toRemoveEntities.clear();
this->dataPtr->componentsMarkedAsRemoved.clear();
// reset the entity component storage
this->dataPtr->componentStorage.clear();
this->dataPtr->componentTypeIndex.clear();
this->dataPtr->componentTypeIndexDirty = true;
// All views are now invalid.
this->dataPtr->views.clear();
}
else
{
GZ_PROFILE("Remove");
// Otherwise iterate through the list of entities to remove.
for (const Entity entity : this->dataPtr->toRemoveEntities)
{
// Make sure the entity exists and is not removed.
if (!this->HasEntity(entity))
continue;
// Remove from graph
this->dataPtr->entities.RemoveVertex(entity);
this->dataPtr->componentsMarkedAsRemoved.erase(entity);
this->dataPtr->componentStorage.erase(entity);
this->dataPtr->componentTypeIndex.erase(entity);
this->dataPtr->componentTypeIndexDirty = true;
// Remove the entity from views.
for (auto &view : this->dataPtr->views)
{
view.second.first->RemoveEntity(entity);
}
}
// Clear the set of entities to remove.
this->dataPtr->toRemoveEntities.clear();
}
// Reset descendants cache
this->dataPtr->descendantCache.clear();
}
/////////////////////////////////////////////////
bool EntityComponentManager::RemoveComponent(
const Entity _entity, const ComponentTypeId &_typeId)
{
GZ_PROFILE("EntityComponentManager::RemoveComponent");
// Make sure the entity exists and has the component.
if (!this->EntityHasComponentType(_entity, _typeId))
return false;
auto oneTimeIter = this->dataPtr->oneTimeChangedComponents.find(_typeId);
if (oneTimeIter != this->dataPtr->oneTimeChangedComponents.end())
{
oneTimeIter->second.erase(_entity);
if (oneTimeIter->second.empty())
this->dataPtr->oneTimeChangedComponents.erase(oneTimeIter);
}
auto periodicIter = this->dataPtr->periodicChangedComponents.find(_typeId);
if (periodicIter != this->dataPtr->periodicChangedComponents.end())
{
periodicIter->second.erase(_entity);
if (periodicIter->second.empty())
this->dataPtr->periodicChangedComponents.erase(periodicIter);
}
auto compPtr = this->ComponentImplementation(_entity, _typeId);
if (compPtr)
{
this->dataPtr->componentsMarkedAsRemoved[_entity].insert(_typeId);
// update views to reflect the component removal
for (auto &viewPair : this->dataPtr->views)
viewPair.second.first->NotifyComponentRemoval(_entity, _typeId);
}
this->dataPtr->AddModifiedComponent(_entity);
// Add component to map of removed components
{
std::lock_guard<std::mutex> lock(this->dataPtr->removedComponentsMutex);
this->dataPtr->removedComponents[_entity].insert(_typeId);
}
return true;
}
/////////////////////////////////////////////////
bool EntityComponentManager::EntityHasComponentType(const Entity _entity,
const ComponentTypeId &_typeId) const
{
if (!this->HasEntity(_entity))
return false;
auto comp = this->ComponentImplementation(_entity, _typeId);
return comp != nullptr;
}
/////////////////////////////////////////////////
bool EntityComponentManager::IsNewEntity(const Entity _entity) const
{
std::lock_guard<std::mutex> lock(this->dataPtr->entityCreatedMutex);
return this->dataPtr->newlyCreatedEntities.find(_entity) !=
this->dataPtr->newlyCreatedEntities.end();
}
/////////////////////////////////////////////////
bool EntityComponentManager::IsMarkedForRemoval(const Entity _entity) const
{
std::lock_guard<std::mutex> lock(this->dataPtr->entityRemoveMutex);
if (this->dataPtr->removeAllEntities)
{
return true;
}
return this->dataPtr->toRemoveEntities.find(_entity) !=
this->dataPtr->toRemoveEntities.end();
}
/////////////////////////////////////////////////
ComponentState EntityComponentManager::ComponentState(const Entity _entity,
const ComponentTypeId _typeId) const
{
auto result = ComponentState::NoChange;
auto ctIter = this->dataPtr->componentTypeIndex.find(_entity);
if (ctIter == this->dataPtr->componentTypeIndex.end())
return result;
auto typeIter = ctIter->second.find(_typeId);
if (typeIter == ctIter->second.end() ||
this->dataPtr->ComponentMarkedAsRemoved(_entity, _typeId))
return result;
auto typeId = typeIter->first;
auto oneTimeIter = this->dataPtr->oneTimeChangedComponents.find(typeId);
if (oneTimeIter != this->dataPtr->oneTimeChangedComponents.end() &&
oneTimeIter->second.find(_entity) != oneTimeIter->second.end())
{
result = ComponentState::OneTimeChange;
}
else
{
auto periodicIter =
this->dataPtr->periodicChangedComponents.find(typeId);
if (periodicIter != this->dataPtr->periodicChangedComponents.end() &&
periodicIter->second.find(_entity) != periodicIter->second.end())
result = ComponentState::PeriodicChange;
}
return result;
}
/////////////////////////////////////////////////
bool EntityComponentManager::HasNewEntities() const
{
std::lock_guard<std::mutex> lock(this->dataPtr->entityCreatedMutex);
return !this->dataPtr->newlyCreatedEntities.empty();
}
/////////////////////////////////////////////////
bool EntityComponentManager::HasEntitiesMarkedForRemoval() const
{
std::lock_guard<std::mutex> lock(this->dataPtr->entityRemoveMutex);
return this->dataPtr->removeAllEntities ||
!this->dataPtr->toRemoveEntities.empty();
}
/////////////////////////////////////////////////
bool EntityComponentManager::HasOneTimeComponentChanges() const
{
return !this->dataPtr->oneTimeChangedComponents.empty();
}
/////////////////////////////////////////////////
bool EntityComponentManager::HasPeriodicComponentChanges() const
{
return !this->dataPtr->periodicChangedComponents.empty();
}
/////////////////////////////////////////////////
std::unordered_set<ComponentTypeId>
EntityComponentManager::ComponentTypesWithPeriodicChanges() const
{
std::unordered_set<ComponentTypeId> periodicComponents;
for (const auto& typeToEntityPtrs : this->dataPtr->periodicChangedComponents)
{
periodicComponents.insert(typeToEntityPtrs.first);
}
return periodicComponents;
}
/////////////////////////////////////////////////
void EntityComponentManager::UpdatePeriodicChangeCache(
std::unordered_map<ComponentTypeId,