-
Notifications
You must be signed in to change notification settings - Fork 304
/
Copy pathRenderUtil.cc
3810 lines (3353 loc) · 124 KB
/
RenderUtil.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) 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 <map>
#include <stack>
#include <string>
#include <tuple>
#include <unordered_map>
#include <variant>
#include <vector>
#include <sdf/Actor.hh>
#include <sdf/Collision.hh>
#include <sdf/Element.hh>
#include <sdf/Joint.hh>
#include <sdf/Light.hh>
#include <sdf/Link.hh>
#include <sdf/Model.hh>
#include <sdf/parser.hh>
#include <sdf/Scene.hh>
#include <sdf/SDFImpl.hh>
#include <sdf/Visual.hh>
#include <gz/common/Profiler.hh>
#include <gz/common/Skeleton.hh>
#include <gz/common/SkeletonAnimation.hh>
#include <gz/math/Color.hh>
#include <gz/math/Helpers.hh>
#include <gz/math/Matrix4.hh>
#include <gz/math/Pose3.hh>
#include <gz/msgs/Utility.hh>
#include <gz/rendering/Grid.hh>
#include <gz/rendering/RenderEngine.hh>
#include <gz/rendering/RenderingIface.hh>
#include <gz/rendering/Scene.hh>
#include <gz/rendering/ThermalCamera.hh>
#include <gz/rendering/WireBox.hh>
#include "gz/sim/components/Actor.hh"
#include "gz/sim/components/BoundingBoxCamera.hh"
#include "gz/sim/components/Camera.hh"
#include "gz/sim/components/CastShadows.hh"
#include "gz/sim/components/ChildLinkName.hh"
#include "gz/sim/components/Collision.hh"
#include "gz/sim/components/DepthCamera.hh"
#include "gz/sim/components/GpuLidar.hh"
#include "gz/sim/components/Geometry.hh"
#include "gz/sim/components/Inertial.hh"
#include "gz/sim/components/Joint.hh"
#include "gz/sim/components/JointAxis.hh"
#include "gz/sim/components/JointType.hh"
#include "gz/sim/components/LaserRetro.hh"
#include "gz/sim/components/Light.hh"
#include "gz/sim/components/LightCmd.hh"
#include "gz/sim/components/Link.hh"
#include "gz/sim/components/Material.hh"
#include "gz/sim/components/Model.hh"
#include "gz/sim/components/Name.hh"
#include "gz/sim/components/ParentEntity.hh"
#include "gz/sim/components/ParentLinkName.hh"
#include "gz/sim/components/ParticleEmitter.hh"
#include "gz/sim/components/Pose.hh"
#include "gz/sim/components/RgbdCamera.hh"
#include "gz/sim/components/Scene.hh"
#include "gz/sim/components/SegmentationCamera.hh"
#include "gz/sim/components/SemanticLabel.hh"
#include "gz/sim/components/SourceFilePath.hh"
#include "gz/sim/components/SphericalCoordinates.hh"
#include "gz/sim/components/Temperature.hh"
#include "gz/sim/components/TemperatureRange.hh"
#include "gz/sim/components/ThermalCamera.hh"
#include "gz/sim/components/Transparency.hh"
#include "gz/sim/components/Visibility.hh"
#include "gz/sim/components/Visual.hh"
#include "gz/sim/components/VisualCmd.hh"
#include "gz/sim/components/WideAngleCamera.hh"
#include "gz/sim/components/World.hh"
#include "gz/sim/EntityComponentManager.hh"
#include "gz/sim/rendering/Events.hh"
#include "gz/sim/rendering/MarkerManager.hh"
#include "gz/sim/rendering/RenderUtil.hh"
#include "gz/sim/rendering/SceneManager.hh"
#include "gz/sim/Util.hh"
using namespace gz;
using namespace sim;
// Private data class.
class gz::sim::RenderUtilPrivate
{
/// True if the rendering component is initialized
public: bool initialized = false;
/// \brief Create rendering entities
/// \param[in] _ecm The entity-component manager
/// \param[in] _info Update information
public: void CreateRenderingEntities(const EntityComponentManager &_ecm,
const UpdateInfo &_info);
/// \brief Create rendering entities during the first update. This
/// is called by CreateRenderingEntities. This calls _ecm.Each
/// \param[in] _ecm The entity-component manager
/// \param[in] _info Update information
/// \TODO(anyone) Combine with CreateEntitiesRuntime
public: void CreateEntitiesFirstUpdate(const EntityComponentManager &_ecm,
const UpdateInfo &_info);
/// \brief Create rendering entities during subsequent updates. This
/// is called by CreateRenderingEntities. This calls _ecm.EachNew
/// \param[in] _ecm The entity-component manager
/// \param[in] _info Update information
/// \TODO(anyone) Combine with CreateEntitiesFirstUpdate
public: void CreateEntitiesRuntime(const EntityComponentManager &_ecm,
const UpdateInfo &_info);
/// \brief Remove rendering entities
/// \param[in] _ecm The entity-component manager
public: void RemoveRenderingEntities(const EntityComponentManager &_ecm,
const UpdateInfo &_info);
/// \brief Update rendering entities
/// \param[in] _ecm The entity-component manager
public: void UpdateRenderingEntities(const EntityComponentManager &_ecm);
/// \breif Helper function to add new sensors
/// \param[in] _ecm The entity-component manager
/// \param[in] _entity Sensor entity
/// \param[in] _sdfData Sensor data
/// \param[in] _parent Parent entity
/// \param[in] _topicSuffix Suffix for sensor topic
public: void AddNewSensor(
const EntityComponentManager &_ecm, Entity _entity,
const sdf::Sensor &_sdfData, Entity _parent,
const std::string &_topicSuffix);
/// \brief Helper function to create a visual for a link entity
/// \param[in] _ecm The entity-component manager
/// \param[in] _entity Entity to create the visual for
/// \param[in] _name Name component
/// \param[in] _pose Pose component
/// \param[in] _parent ParentEntity component
public: void CreateLink(
const EntityComponentManager &_ecm,
const Entity &_entity,
const components::Name *_name,
const components::Pose *_pose,
const components::ParentEntity *_parent);
/// \brief Helper function to create a visual for a visual entity
/// \param[in] _ecm The entity-component manager
/// \param[in] _entity Entity to create the visual for
/// \param[in] _name Name component
/// \param[in] _pose Pose component
/// \param[in] _geom Geometry component
/// \param[in] _castShadows CastShadows component
/// \param[in] _transparency Transparency component
/// \param[in] _visibilityFlags VisibilityFlags component
/// \param[in] _parent ParentEntity component
public: void CreateVisual(
const EntityComponentManager &_ecm,
const Entity &_entity,
const components::Name *_name,
const components::Pose *_pose,
const components::Geometry *_geom,
const components::CastShadows *_castShadows,
const components::Transparency *_transparency,
const components::VisibilityFlags *_visibilityFlags,
const components::ParentEntity *_parent);
/// \brief Helper function to create a visual for a light entity
/// \param[in] _ecm The entity-component manager
/// \param[in] _entity Entity to create the visual for
/// \param[in] _light Light component
/// \param[in] _name Name component
/// \param[in] _parent ParentEntity component
public: void CreateLight(
const EntityComponentManager &_ecm,
const Entity &_entity,
const components::Light *_light,
const components::Name *_name,
const components::ParentEntity *_parent);
/// \brief Event manager used for emitting render / scene events
public: EventManager *eventManager{nullptr};
/// \brief Total time elapsed in simulation. This will not increase while
/// paused.
public: std::chrono::steady_clock::duration simTime{0};
/// \brief Name of rendering engine
public: std::string engineName = "ogre2";
/// \brief Name of scene
public: std::string sceneName = "scene";
//// \brief True to enable sky in the scene
public: bool skyEnabled = false;
/// \brief Scene background color. This is optional because a <scene> is
/// always present, which has a default background color value. This
/// backgroundColor variable is used to override the <scene> value.
public: std::optional<math::Color> backgroundColor;
/// \brief Ambient color. This is optional because an <scene> is always
/// present, which has a default ambient light value. This ambientLight
/// variable is used to override the <scene> value.
public: std::optional<math::Color> ambientLight;
/// \brief Scene manager
public: SceneManager sceneManager;
/// \brief Marker manager
public: MarkerManager markerManager;
/// \brief Pointer to rendering engine.
public: rendering::RenderEngine *engine{nullptr};
/// \brief rendering scene to be managed by the scene manager and used to
/// generate sensor data
public: rendering::ScenePtr scene;
/// \brief Flag to indicate if the current GL context should be used
public: bool useCurrentGLContext = false;
/// \brief Window ID handle
public: std::string winID = "";
/// \brief New scenes to be created
public: std::vector<sdf::Scene> newScenes;
/// \brief is headless mode active
public: bool isHeadlessRendering = false;
/// \brief New models to be created. The elements in the tuple are:
/// [0] entity id, [1], SDF DOM, [2] parent entity id, [3] sim iteration
public: std::vector<std::tuple<Entity, sdf::Model, Entity, uint64_t>>
newModels;
/// \brief New links to be created. The elements in the tuple are:
/// [0] entity id, [1] SDF DOM, [2] parent entity id
public: std::vector<std::tuple<Entity, sdf::Link, Entity>> newLinks;
/// \brief New visuals to be created. The elements in the tuple are:
/// [0] entity id, [1] SDF DOM, [2] parent entity id
public: std::vector<std::tuple<Entity, sdf::Visual, Entity>> newVisuals;
/// \brief New actors to be created. The elements in the tuple are:
/// [0] entity id, [1] SDF DOM, [2] actor name, [3] parent entity id
public: std::vector<std::tuple<Entity, sdf::Actor, std::string, Entity>>
newActors;
/// \brief New lights to be created. The elements in the tuple are:
/// [0] entity id, [1] SDF DOM, [2] light name, [3] parent entity id
public: std::vector<std::tuple<Entity, sdf::Light, std::string, Entity>>
newLights;
/// \brief A map of entity light ids and light visuals
public: std::map<Entity, Entity> matchLightWithVisuals;
/// \brief New sensors to be created. The elements in the tuple are:
/// [0] entity id, [1] SDF DOM, [2] parent entity id
public: std::vector<std::tuple<Entity, sdf::Sensor, Entity>>
newSensors;
/// \brief New particle emitter to be created. The elements in the tuple are:
/// [0] entity id, [1] particle emitter, [2] parent entity id
public: std::vector<std::tuple<Entity, msgs::ParticleEmitter, Entity>>
newParticleEmitters;
/// \brief New particle emitter commands to be requested.
/// The map key and value are: entity id of the particle emitter to
/// update, and particle emitter msg
public: std::unordered_map<Entity, msgs::ParticleEmitter>
newParticleEmittersCmds;
/// \brief A list of entities with particle emitter cmds to remove
public: std::vector<Entity> particleCmdsToRemove;
/// \brief Map of ids of entites to be removed and sim iteration when the
/// remove request is received
public: std::unordered_map<Entity, uint64_t> removeEntities;
/// \brief A map of entity ids and pose updates.
public: std::unordered_map<Entity, math::Pose3d> entityPoses;
/// \brief A map of entity ids and light updates.
public: std::unordered_map<Entity, msgs::Light> entityLights;
/// \brief A map of entity ids and light updates.
public: std::vector<Entity> entityLightsCmdToDelete;
/// \brief A map of entity ids and visual updates.
public: std::map<Entity, msgs::Visual> entityVisuals;
/// \brief A vector of entity ids of VisualCmds to delete
public: std::vector<Entity> entityVisualsCmdToDelete;
/// \brief Visual material equality comparision function
/// TODO(anyone) Currently only checks for material colors equality,
/// need to extend to others (e.g., PbrMaterial)
public: std::function<bool(const sdf::Material &, const sdf::Material &)>
materialEql { [](const sdf::Material &_a, const sdf::Material &_b)
{
return
_a.Ambient() == _b.Ambient() &&
_a.Diffuse() == _b.Diffuse() &&
_a.Specular() == _b.Specular() &&
_a.Emissive() == _b.Emissive();
}};
/// \brief A map of entity ids and actor transforms.
public: std::map<Entity, std::map<std::string, math::Matrix4d>>
actorTransforms;
/// \brief A map of entity ids and temperature data.
/// The value of this map (tuple) represents either a single (uniform)
/// temperature, or a heat signature with a min/max temperature. If the string
/// in the tuple is empty, then this entity has a uniform temperature across
/// its surface, and this uniform temperature is stored in the first float of
/// the tuple (the second float and string are unused for uniform temperature
/// entities). If the string in the tuple is not empty, then the string
/// represents the entity's heat signature (a path to a heat signature texture
/// file), and the floats represent the min/max temperatures of the heat
/// signature, respectively.
///
/// All temperatures are in Kelvin.
public: std::map<Entity, std::tuple<float, float, std::string>> entityTemp;
/// \brief A map of entity ids and label data for datasets annotations
public: std::unordered_map<Entity, int> entityLabel;
/// \brief A map of entity ids and wire boxes
public: std::unordered_map<Entity, gz::rendering::WireBoxPtr> wireBoxes;
/// \brief A map of entity ids and trajectory pose updates.
public: std::unordered_map<Entity, math::Pose3d> trajectoryPoses;
/// \brief A map of entity ids and actor animation info.
public: std::unordered_map<Entity, AnimationUpdateData> actorAnimationData;
/// \brief True to update skeletons manually using bone poses
/// (see actorTransforms). False to let render engine update animation
/// based on sim time.
/// \todo(anyone) Let this be turned on from a component
public: bool actorManualSkeletonUpdate = false;
/// \brief Mutex to protect updates
public: std::mutex updateMutex;
//// \brief Flag to indicate whether to create sensors
public: bool enableSensors = false;
/// \brief A set containing all the entities with attached rendering sensors
public: std::unordered_set<Entity> sensorEntities;
/// \brief Callback function for creating sensors.
/// The function args are: entity id, sensor sdf, and parent name.
/// The function returns the id of the rendering sensor created.
public: std::function<std::string(const sim::Entity &, const sdf::Sensor &,
const std::string &)> createSensorCb;
/// \brief Light equality comparison function.
public: std::function<bool(const sdf::Light &, const sdf::Light &)>
lightEql { [](const sdf::Light &_a, const sdf::Light &_b)
{
return
_a.Visualize() == _b.Visualize() &&
_a.Type() == _b.Type() &&
_a.Name() == _b.Name() &&
_a.Diffuse() == _b.Diffuse() &&
_a.Specular() == _b.Specular() &&
math::equal(
_a.AttenuationRange(), _b.AttenuationRange(), 1e-6) &&
math::equal(
_a.LinearAttenuationFactor(),
_b.LinearAttenuationFactor(),
1e-6) &&
math::equal(
_a.ConstantAttenuationFactor(),
_b.ConstantAttenuationFactor(),
1e-6) &&
math::equal(
_a.QuadraticAttenuationFactor(),
_b.QuadraticAttenuationFactor(),
1e-6) &&
_a.CastShadows() == _b.CastShadows() &&
_a.Direction() == _b.Direction() &&
_a.SpotInnerAngle() == _b.SpotInnerAngle() &&
_a.SpotOuterAngle() == _b.SpotOuterAngle() &&
math::equal(_a.SpotFalloff(), _b.SpotFalloff(), 1e-6);
}};
/// \brief Callback function for removing sensors.
/// The function arg is the entity id
public: std::function<void(const sim::Entity &)> removeSensorCb;
/// \brief Currently selected entities, organized by order of selection.
public: std::vector<Entity> selectedEntities;
/// \brief Map of original emissive colors for nodes currently highlighted.
public: std::map<std::string, math::Color> originalEmissive;
/// \brief Whether the transform gizmo is being dragged.
public: bool transformActive{false};
/// \brief Highlight a node and all its children.
/// \param[in] _node Node to be highlighted
public: void HighlightNode(const rendering::NodePtr &_node);
/// \brief Restore a highlighted node to normal.
/// \param[in] _node Node to be restored.
public: void LowlightNode(const rendering::NodePtr &_node);
/// \brief New joint visuals to be created
public: std::vector<Entity> newJoints;
/// \brief Finds the models (joint parent) that are used to create
/// joint visuals in RenderUtil::Update
/// \param[in] _ecm The entity-component manager
public: void FindJointModels(const EntityComponentManager &_ecm);
/// \brief A list of models used to create new joint visuals
public: std::vector<Entity> newJointModels;
/// \brief A map of joint entity ids and their SDF DOM
public: std::map<Entity, sdf::Joint> entityJoints;
/// \brief A map of model entities and their corresponding children links
public: std::map<Entity, std::vector<Entity>> modelToJointEntities;
/// \brief A map of created joint entities and if they are currently
/// visible
public: std::map<Entity, bool> viewingJoints;
/// \brief A list of joint visuals for which the parent visual poses
/// have to be updated.
public: std::vector<Entity> updateJointParentPoses;
/// \brief A map of models entities and link attributes used
/// to create joint visuals
public: std::map<Entity, std::map<std::string, Entity>>
matchLinksWithEntities;
/// \brief New center of mass visuals to be created
public: std::vector<Entity> newCOMVisuals;
/// \brief A list of links used to create new center of mass visuals
public: std::vector<Entity> newCOMLinks;
/// \brief A map of link entities and if their center of mass visuals
/// are currently visible
public: std::map<Entity, bool> viewingCOM;
/// \brief New inertias to be created
public: std::vector<Entity> newInertias;
/// \brief A map of links and their center of mass visuals
public: std::map<Entity, Entity> linkToCOMVisuals;
/// \brief Finds the child links for given entity from the ECM
/// \param[in] _ecm The entity-component manager
/// \param[in] _entity Entity to find child links
/// \return A vector of child links found for the entity
public: std::vector<Entity> FindChildLinksFromECM(
const EntityComponentManager &_ecm, const Entity &_entity);
/// \brief Finds the links (inertial parent) that are used to create child
/// inertia and center of mass visuals in RenderUtil::Update
/// \param[in] _ecm The entity-component manager
public: void FindInertialLinks(const EntityComponentManager &_ecm);
/// \brief A list of links used to create new inertia visuals
public: std::vector<Entity> newInertiaLinks;
/// \brief A map of entity ids and their inertials
public: std::map<Entity, math::Inertiald> entityInertials;
/// \brief A map of link entities and if their inertias are currently
/// visible
public: std::map<Entity, bool> viewingInertias;
/// \brief A map of links and their inertia visuals
public: std::map<Entity, Entity> linkToInertiaVisuals;
/// \brief New wireframe visuals to be toggled
public: std::vector<Entity> newWireframes;
/// \brief New wireframe visuals to be toggled
public: std::vector<Entity> newTransparentEntities;
/// \brief Finds the links (visual parent) that are used to toggle wireframe
/// and transparent view for visuals in RenderUtil::Update
/// \param[in] _ecm The entity-component manager
public: void PopulateViewModeVisualLinks(const EntityComponentManager &_ecm);
/// \brief A list of links used to toggle wireframe mode for visuals
public: std::vector<Entity> newWireframeVisualLinks;
/// \brief A list of links used to toggle transparent mode for visuals
public: std::vector<Entity> newTransparentVisualLinks;
/// \brief A map of link entities and their corresponding children visuals
public: std::map<Entity, std::vector<Entity>> linkToVisualEntities;
/// \brief A map of created wireframe visuals and if they are currently
/// visible
public: std::map<Entity, bool> viewingWireframes;
/// \brief A map of created transparent visuals and if they are currently
/// visible
public: std::map<Entity, bool> viewingTransparent;
/// \brief New collisions to be created
public: std::vector<Entity> newCollisions;
/// \brief Finds the links (collision parent) that are used to create child
/// collision visuals in RenderUtil::Update
/// \param[in] _ecm The entity-component manager
public: void FindCollisionLinks(const EntityComponentManager &_ecm);
/// \brief A list of links used to create new collision visuals
public: std::vector<Entity> newCollisionLinks;
/// \brief A map of collision entity ids and their SDF DOM
public: std::map<Entity, sdf::Collision> entityCollisions;
/// \brief A map of model entities and their corresponding children links
public: std::map<Entity, std::vector<Entity>> modelToLinkEntities;
/// \brief A map of link entities and their corresponding children collisions
public: std::map<Entity, std::vector<Entity>> linkToCollisionEntities;
/// \brief A map of created collision entities and if they are currently
/// visible
public: std::map<Entity, bool> viewingCollisions;
/// \brief A map of model entities and their corresponding children models
public: std::map<Entity, std::vector<Entity>> modelToModelEntities;
/// \brief A map of entity id to thermal camera sensor configuration
/// properties. The elements in the tuple are:
/// <resolution, temperature range (min, max)>
public: std::unordered_map<Entity,
std::tuple<double, components::TemperatureRangeInfo>> thermalCameraData;
/// \brief Update the visuals with label user data
/// \param[in] _entityLabel Map with key visual entity id and value label
public: void UpdateVisualLabels(
const std::unordered_map<Entity, int> &_entityLabel);
/// \brief A helper function that removes the sensor associated with an
/// entity, if an associated sensor exists. This should be called in
/// RenderUtil::Update.
/// \param[in] _entity The entity that should be checked for an associated
/// sensor.
public: void RemoveSensor(const Entity _entity);
/// \brief A helper function that removes the bounding box associated with an
/// entity, if an associated bounding box exists. This should be called in
/// RenderUtil::Update.
/// \param[in] _entity The entity that should be checked for an associated
/// bounding box.
public: void RemoveBoundingBox(const Entity _entity);
/// \brief A helper function for updating lights. This should be called in
/// RenderUtil::Update.
/// \param[in] _entityLights A map of entity IDs to their light updates.
public: void UpdateLights(
const std::unordered_map<Entity, msgs::Light> &_entityLights);
/// \brief A helper function for updating the thermal camera. This should be
/// called in RenderUtil::Update.
/// \param[in] _thermalCamData The thermal camera data that needs to be
/// updated.
/// \sa thermalCameraData
public: void UpdateThermalCamera(const std::unordered_map<Entity,
std::tuple<double, components::TemperatureRangeInfo>> &_thermalCamData);
/// \brief Helper function for updating animation. This should be called in
/// RenderUtil::Update.
/// \param[in] _actorAnimationData A map of entities to their animation update
/// data.
/// \param[in] _entityPoses A map of entity ids and pose updates.
/// \param[in] _trajectoryPoses A map of entity ids and trajectory
/// pose updates.
/// \sa actorManualSkeletonUpdate
public: void UpdateAnimation(const std::unordered_map<Entity,
AnimationUpdateData> &_actorAnimationData,
const std::unordered_map<Entity, math::Pose3d> &_entityPoses,
const std::unordered_map<Entity, math::Pose3d> &_trajectoryPoses);
};
//////////////////////////////////////////////////
RenderUtil::RenderUtil() : dataPtr(std::make_unique<RenderUtilPrivate>())
{
}
//////////////////////////////////////////////////
RenderUtil::~RenderUtil() = default;
//////////////////////////////////////////////////
rendering::ScenePtr RenderUtil::Scene() const
{
return this->dataPtr->scene;
}
//////////////////////////////////////////////////
void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/,
EntityComponentManager &_ecm)
{
std::lock_guard<std::mutex> lock(this->dataPtr->updateMutex);
// Remove the commands from the entity
// these are commands from the last iteration. We want to make sure all
// systems have a chance to process them first before they are removed.
for (const auto &entity : this->dataPtr->particleCmdsToRemove)
_ecm.RemoveComponent<components::ParticleEmitterCmd>(entity);
this->dataPtr->particleCmdsToRemove.clear();
// particle emitters commands
_ecm.Each<components::ParticleEmitterCmd>(
[&](const Entity &_entity,
const components::ParticleEmitterCmd *_emitterCmd) -> bool
{
// store emitter properties and update them in rendering thread
this->dataPtr->newParticleEmittersCmds[_entity] =
_emitterCmd->Data();
// update pose comp here
if (_emitterCmd->Data().has_pose())
{
auto poseComp = _ecm.Component<components::Pose>(_entity);
if (poseComp)
poseComp->Data() = msgs::Convert(_emitterCmd->Data().pose());
}
// Store the entity ids to clear outside of the `Each` loop.
this->dataPtr->particleCmdsToRemove.push_back(_entity);
return true;
});
// Update lights
auto olderEntitiesLightsCmdToDelete =
std::move(this->dataPtr->entityLightsCmdToDelete);
this->dataPtr->entityLightsCmdToDelete.clear();
_ecm.Each<components::LightCmd>(
[&](const Entity &_entity,
const components::LightCmd * _lightCmd) -> bool
{
this->dataPtr->entityLights[_entity] = _lightCmd->Data();
this->dataPtr->entityLightsCmdToDelete.push_back(_entity);
auto lightComp = _ecm.Component<components::Light>(_entity);
if (lightComp)
{
sdf::Light sdfLight = convert<sdf::Light>(_lightCmd->Data());
auto state = lightComp->SetData(sdfLight,
this->dataPtr->lightEql) ?
ComponentState::OneTimeChange :
ComponentState::NoChange;
_ecm.SetChanged(_entity, components::Light::typeId, state);
}
return true;
});
for (const auto entity : olderEntitiesLightsCmdToDelete)
{
_ecm.RemoveComponent<components::LightCmd>(entity);
}
// Update thermal cameras
_ecm.Each<components::ThermalCamera>(
[&](const Entity &_entity,
const components::ThermalCamera *)->bool
{
// set properties from thermal sensor plugin
// Set defaults to invaid values so we know they have not been set.
// set UpdateECM(). We check for valid values first before setting
// these thermal camera properties..
double resolution = 0.0;
components::TemperatureRangeInfo range;
range.min = std::numeric_limits<double>::max();
range.max = 0;
// resolution
auto resolutionComp =
_ecm.Component<components::TemperatureLinearResolution>(_entity);
if (resolutionComp != nullptr)
{
resolution = resolutionComp->Data();
_ecm.RemoveComponent<components::TemperatureLinearResolution>(
_entity);
}
// min / max temp
auto tempRangeComp =
_ecm.Component<components::TemperatureRange>(_entity);
if (tempRangeComp != nullptr)
{
range = tempRangeComp->Data();
_ecm.RemoveComponent<components::TemperatureRange>(_entity);
}
if (resolutionComp || tempRangeComp)
{
this->dataPtr->thermalCameraData[_entity] =
std::make_tuple(resolution, range);
}
return true;
});
// visual commands
{
auto olderEntityVisualsCmdToDelete
= std::move(this->dataPtr->entityVisualsCmdToDelete);
this->dataPtr->entityVisualsCmdToDelete.clear();
// TODO(anyone) Currently only updates material colors,
// need to extend to others
_ecm.Each<components::VisualCmd>(
[&](const Entity &_entity,
const components::VisualCmd *_visualCmd) -> bool
{
this->dataPtr->entityVisuals[_entity] = _visualCmd->Data();
this->dataPtr->entityVisualsCmdToDelete.push_back(_entity);
auto materialComp = _ecm.Component<components::Material>(_entity);
if (materialComp)
{
msgs::Material materialMsg = _visualCmd->Data().material();
sdf::Material sdfMaterial = convert<sdf::Material>(materialMsg);
auto state =
materialComp->SetData(sdfMaterial, this->dataPtr->materialEql) ?
ComponentState::OneTimeChange : ComponentState::NoChange;
_ecm.SetChanged(_entity, components::Material::typeId, state);
}
return true;
});
for (const auto entity : olderEntityVisualsCmdToDelete)
{
_ecm.RemoveComponent<components::VisualCmd>(entity);
}
}
}
//////////////////////////////////////////////////
void RenderUtil::UpdateFromECM(const UpdateInfo &_info,
const EntityComponentManager &_ecm)
{
GZ_PROFILE("RenderUtil::UpdateFromECM");
std::lock_guard<std::mutex> lock(this->dataPtr->updateMutex);
this->dataPtr->simTime = _info.simTime;
this->dataPtr->CreateRenderingEntities(_ecm, _info);
this->dataPtr->UpdateRenderingEntities(_ecm);
this->dataPtr->RemoveRenderingEntities(_ecm, _info);
this->dataPtr->markerManager.SetSimTime(_info.simTime);
this->dataPtr->PopulateViewModeVisualLinks(_ecm);
this->dataPtr->FindInertialLinks(_ecm);
this->dataPtr->FindJointModels(_ecm);
this->dataPtr->FindCollisionLinks(_ecm);
// Get the SphericalCoordinate object from the world
// and supply it to the SceneManager
auto worldEntity = _ecm.EntityByComponents(components::World());
auto sphericalCoordinatesComponent =
_ecm.Component<components::SphericalCoordinates>(
worldEntity);
if (sphericalCoordinatesComponent)
{
this->dataPtr->sceneManager.SetSphericalCoordinates(
sphericalCoordinatesComponent->Data());
}
}
//////////////////////////////////////////////////
std::vector<Entity> RenderUtilPrivate::FindChildLinksFromECM(
const EntityComponentManager &_ecm, const Entity &_entity)
{
std::vector<Entity> links;
if (_ecm.EntityMatches(_entity,
std::set<ComponentTypeId>{components::Model::typeId}))
{
std::stack<Entity> modelStack;
modelStack.push(_entity);
std::vector<Entity> childLinks, childModels;
while (!modelStack.empty())
{
Entity model = modelStack.top();
modelStack.pop();
childLinks = _ecm.EntitiesByComponents(components::ParentEntity(model),
components::Link());
links.insert(links.end(),
childLinks.begin(),
childLinks.end());
childModels =
_ecm.EntitiesByComponents(components::ParentEntity(model),
components::Model());
for (const auto &childModel : childModels)
{
modelStack.push(childModel);
}
}
}
else if (_ecm.EntityMatches(_entity,
std::set<ComponentTypeId>{components::Link::typeId}))
{
links.push_back(_entity);
}
return links;
}
//////////////////////////////////////////////////
void RenderUtilPrivate::FindInertialLinks(const EntityComponentManager &_ecm)
{
for (const auto &entity : this->newInertias)
{
std::vector<Entity> links;
if (_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Model::typeId}) ||
_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Link::typeId}))
{
links = this->FindChildLinksFromECM(_ecm, entity);
}
else
{
gzerr << "Entity [" << entity
<< "] for viewing inertia must be a model or link"
<< std::endl;
continue;
}
this->newInertiaLinks.insert(this->newInertiaLinks.end(),
links.begin(),
links.end());
}
this->newInertias.clear();
for (const auto &entity : this->newCOMVisuals)
{
std::vector<Entity> links;
if (_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Model::typeId}) ||
_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Link::typeId}))
{
links = this->FindChildLinksFromECM(_ecm, entity);
}
else
{
gzerr << "Entity [" << entity
<< "] for viewing center of mass must be a model or link"
<< std::endl;
continue;
}
this->newCOMLinks.insert(this->newCOMLinks.end(),
links.begin(),
links.end());
}
this->newCOMVisuals.clear();
}
//////////////////////////////////////////////////
void RenderUtilPrivate::FindJointModels(const EntityComponentManager &_ecm)
{
if (this->newJoints.empty())
{
return;
}
for (const auto &entity : this->newJoints)
{
std::vector<Entity> models;
if (_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Model::typeId}))
{
std::stack<Entity> modelStack;
modelStack.push(entity);
std::vector<Entity> childModels;
while (!modelStack.empty())
{
Entity model = modelStack.top();
modelStack.pop();
models.push_back(model);
childModels =
_ecm.EntitiesByComponents(components::ParentEntity(model),
components::Model());
for (const auto &childModel : childModels)
{
modelStack.push(childModel);
}
}
}
else
{
gzerr << "Entity [" << entity
<< "] for viewing joints must be a model"
<< std::endl;
continue;
}
this->newJointModels.insert(this->newJointModels.end(),
models.begin(),
models.end());
}
this->newJoints.clear();
}
//////////////////////////////////////////////////
void RenderUtilPrivate::PopulateViewModeVisualLinks(
const EntityComponentManager &_ecm)
{
// Find links to toggle wireframes
for (const auto &entity : this->newWireframes)
{
std::vector<Entity> links;
if (_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Model::typeId}) ||
_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Link::typeId}))
{
links = this->FindChildLinksFromECM(_ecm, entity);
}
else
{
gzerr << "Entity [" << entity
<< "] for viewing wireframe must be a model or link"
<< std::endl;
continue;
}
this->newWireframeVisualLinks.insert(this->newWireframeVisualLinks.end(),
links.begin(),
links.end());
}
this->newWireframes.clear();
// Find links to view as transparent
for (const auto &entity : this->newTransparentEntities)
{
std::vector<Entity> links;
if (_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Model::typeId}) ||
_ecm.EntityMatches(entity,
std::set<ComponentTypeId>{components::Link::typeId}))
{
links = this->FindChildLinksFromECM(_ecm, entity);
}
else
{
gzerr << "Entity [" << entity
<< "] for viewing as transparent must be a model or link"
<< std::endl;
continue;
}
this->newTransparentVisualLinks.insert(
this->newTransparentVisualLinks.end(),
links.begin(),
links.end());
}
this->newTransparentEntities.clear();
}
//////////////////////////////////////////////////
void RenderUtilPrivate::FindCollisionLinks(const EntityComponentManager &_ecm)
{
if (this->newCollisions.empty())
return;
for (const auto &entity : this->newCollisions)