forked from gazebosim/gz-sim
-
Notifications
You must be signed in to change notification settings - Fork 0
/
SceneManager.cc
1780 lines (1564 loc) · 54.4 KB
/
SceneManager.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 <sdf/Box.hh>
#include <sdf/Capsule.hh>
#include <sdf/Collision.hh>
#include <sdf/Cylinder.hh>
#include <sdf/Ellipsoid.hh>
#include <sdf/Heightmap.hh>
#include <sdf/Mesh.hh>
#include <sdf/Pbr.hh>
#include <sdf/Plane.hh>
#include <sdf/Sphere.hh>
#include <ignition/common/Animation.hh>
#include <ignition/common/Console.hh>
#include <ignition/common/HeightmapData.hh>
#include <ignition/common/ImageHeightmap.hh>
#include <ignition/common/KeyFrame.hh>
#include <ignition/common/MeshManager.hh>
#include <ignition/common/Skeleton.hh>
#include <ignition/common/SkeletonAnimation.hh>
#include <ignition/msgs/Utility.hh>
#include "ignition/rendering/Capsule.hh"
#include <ignition/rendering/Geometry.hh>
#include <ignition/rendering/Heightmap.hh>
#include <ignition/rendering/HeightmapDescriptor.hh>
#include <ignition/rendering/InertiaVisual.hh>
#include <ignition/rendering/Light.hh>
#include <ignition/rendering/LightVisual.hh>
#include <ignition/rendering/Material.hh>
#include <ignition/rendering/ParticleEmitter.hh>
#include <ignition/rendering/Scene.hh>
#include <ignition/rendering/Visual.hh>
#include "ignition/gazebo/Conversions.hh"
#include "ignition/gazebo/Util.hh"
#include "ignition/gazebo/rendering/SceneManager.hh"
using namespace ignition;
using namespace gazebo;
using namespace std::chrono_literals;
using TP = std::chrono::steady_clock::time_point;
/// \brief Private data class.
class ignition::gazebo::SceneManagerPrivate
{
/// \brief Keep track of world ID, which is equivalent to the scene's
/// root visual.
/// Defaults to zero, which is considered invalid by Ignition Gazebo.
public: Entity worldId{0};
//// \brief Pointer to the rendering scene
public: rendering::ScenePtr scene;
/// \brief Map of visual entity in Gazebo to visual pointers.
public: std::map<Entity, rendering::VisualPtr> visuals;
/// \brief Map of actor entity in Gazebo to actor pointers.
public: std::map<Entity, rendering::MeshPtr> actors;
/// \brief Map of actor entity in Gazebo to actor animations.
public: std::map<Entity, common::SkeletonPtr> actorSkeletons;
/// \brief Map of actor entity to the associated trajectories.
public: std::map<Entity, std::vector<common::TrajectoryInfo>>
actorTrajectories;
/// \brief Map of light entity in Gazebo to light pointers.
public: std::map<Entity, rendering::LightPtr> lights;
/// \brief Map of particle emitter entity in Gazebo to particle emitter
/// rendering pointers.
public: std::map<Entity, rendering::ParticleEmitterPtr> particleEmitters;
/// \brief Map of sensor entity in Gazebo to sensor pointers.
public: std::map<Entity, rendering::SensorPtr> sensors;
/// \brief Helper function to compute actor trajectory at specified tiime
/// \param[in] _id Actor entity's unique id
/// \param[in] _time Simulation time
/// \return AnimationUpdateData with trajectory related fields filled. It
/// also sets the time point in which the animation should be played
public: AnimationUpdateData ActorTrajectoryAt(
Entity _id, const std::chrono::steady_clock::duration &_time) const;
};
/////////////////////////////////////////////////
SceneManager::SceneManager()
: dataPtr(std::make_unique<SceneManagerPrivate>())
{
}
/////////////////////////////////////////////////
SceneManager::~SceneManager() = default;
/////////////////////////////////////////////////
void SceneManager::SetScene(rendering::ScenePtr _scene)
{
this->dataPtr->scene = std::move(_scene);
}
/////////////////////////////////////////////////
rendering::ScenePtr SceneManager::Scene() const
{
return this->dataPtr->scene;
}
/////////////////////////////////////////////////
void SceneManager::SetWorldId(Entity _id)
{
this->dataPtr->worldId = _id;
}
/////////////////////////////////////////////////
Entity SceneManager::WorldId() const
{
return this->dataPtr->worldId;
}
/////////////////////////////////////////////////
rendering::VisualPtr SceneManager::CreateModel(Entity _id,
const sdf::Model &_model, Entity _parentId)
{
if (!this->dataPtr->scene)
return rendering::VisualPtr();
if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end())
{
ignerr << "Entity with Id: [" << _id << "] already exists in the scene"
<< std::endl;
return rendering::VisualPtr();
}
std::string name = _model.Name().empty() ? std::to_string(_id) :
_model.Name();
rendering::VisualPtr parent;
if (_parentId != this->dataPtr->worldId)
{
auto it = this->dataPtr->visuals.find(_parentId);
if (it == this->dataPtr->visuals.end())
{
ignerr << "Parent entity with Id: [" << _parentId << "] not found. "
<< "Not adding model visual with ID[" << _id
<< "] and name [" << name << "] to the rendering scene."
<< std::endl;
return rendering::VisualPtr();
}
parent = it->second;
}
if (parent)
name = parent->Name() + "::" + name;
if (this->dataPtr->scene->HasVisualName(name))
{
ignerr << "Visual: [" << name << "] already exists" << std::endl;
return rendering::VisualPtr();
}
rendering::VisualPtr modelVis = this->dataPtr->scene->CreateVisual(name);
modelVis->SetUserData("gazebo-entity", static_cast<int>(_id));
modelVis->SetUserData("pause-update", static_cast<int>(0));
modelVis->SetLocalPose(_model.RawPose());
this->dataPtr->visuals[_id] = modelVis;
if (parent)
parent->AddChild(modelVis);
else
this->dataPtr->scene->RootVisual()->AddChild(modelVis);
return modelVis;
}
/////////////////////////////////////////////////
rendering::VisualPtr SceneManager::CreateLink(Entity _id,
const sdf::Link &_link, Entity _parentId)
{
if (!this->dataPtr->scene)
return rendering::VisualPtr();
if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end())
{
ignerr << "Entity with Id: [" << _id << "] already exists in the scene"
<< std::endl;
return rendering::VisualPtr();
}
rendering::VisualPtr parent;
if (_parentId != this->dataPtr->worldId)
{
auto it = this->dataPtr->visuals.find(_parentId);
if (it == this->dataPtr->visuals.end())
{
// It is possible to get here if the model entity is created then
// removed in between render updates.
return rendering::VisualPtr();
}
parent = it->second;
}
std::string name = _link.Name().empty() ? std::to_string(_id) :
_link.Name();
if (parent)
name = parent->Name() + "::" + name;
rendering::VisualPtr linkVis = this->dataPtr->scene->CreateVisual(name);
linkVis->SetUserData("gazebo-entity", static_cast<int>(_id));
linkVis->SetUserData("pause-update", static_cast<int>(0));
linkVis->SetLocalPose(_link.RawPose());
linkVis->SetUserData("gazebo-entity", static_cast<int>(_id));
this->dataPtr->visuals[_id] = linkVis;
if (parent)
parent->AddChild(linkVis);
return linkVis;
}
/////////////////////////////////////////////////
rendering::VisualPtr SceneManager::CreateVisual(Entity _id,
const sdf::Visual &_visual, Entity _parentId)
{
if (!this->dataPtr->scene)
return rendering::VisualPtr();
if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end())
{
ignerr << "Entity with Id: [" << _id << "] already exists in the scene"
<< std::endl;
return rendering::VisualPtr();
}
rendering::VisualPtr parent;
if (_parentId != this->dataPtr->worldId)
{
auto it = this->dataPtr->visuals.find(_parentId);
if (it == this->dataPtr->visuals.end())
{
// It is possible to get here if the model entity is created then
// removed in between render updates.
return rendering::VisualPtr();
}
parent = it->second;
}
if (!_visual.Geom())
return rendering::VisualPtr();
std::string name = _visual.Name().empty() ? std::to_string(_id) :
_visual.Name();
if (parent)
name = parent->Name() + "::" + name;
rendering::VisualPtr visualVis = this->dataPtr->scene->CreateVisual(name);
visualVis->SetUserData("gazebo-entity", static_cast<int>(_id));
visualVis->SetUserData("pause-update", static_cast<int>(0));
visualVis->SetLocalPose(_visual.RawPose());
if (_visual.HasLaserRetro())
{
visualVis->SetUserData("laser_retro", _visual.LaserRetro());
}
math::Vector3d scale = math::Vector3d::One;
math::Pose3d localPose;
rendering::GeometryPtr geom =
this->LoadGeometry(*_visual.Geom(), scale, localPose);
if (geom)
{
/// localPose is currently used to handle the normal vector in plane visuals
/// In general, this can be used to store any local transforms between the
/// parent Visual and geometry.
if (localPose != math::Pose3d::Zero)
{
rendering::VisualPtr geomVis =
this->dataPtr->scene->CreateVisual(name + "_geom");
geomVis->AddGeometry(geom);
geomVis->SetLocalPose(localPose);
visualVis->AddChild(geomVis);
}
else
{
visualVis->AddGeometry(geom);
}
visualVis->SetLocalScale(scale);
// set material
rendering::MaterialPtr material{nullptr};
if (_visual.Geom()->Type() == sdf::GeometryType::HEIGHTMAP)
{
// Heightmap's material is loaded together with it.
}
else if (_visual.Material())
{
material = this->LoadMaterial(*_visual.Material());
}
// Don't set a default material for meshes because they
// may have their own
// TODO(anyone) support overriding mesh material
else if (_visual.Geom()->Type() != sdf::GeometryType::MESH)
{
// create default material
material = this->dataPtr->scene->Material("ign-grey");
if (!material)
{
material = this->dataPtr->scene->CreateMaterial("ign-grey");
material->SetAmbient(0.3, 0.3, 0.3);
material->SetDiffuse(0.7, 0.7, 0.7);
material->SetSpecular(1.0, 1.0, 1.0);
material->SetRoughness(0.2f);
material->SetMetalness(1.0f);
}
}
else
{
// meshes created by mesh loader may have their own materials
// update/override their properties based on input sdf element values
auto mesh = std::dynamic_pointer_cast<rendering::Mesh>(geom);
for (unsigned int i = 0; i < mesh->SubMeshCount(); ++i)
{
auto submesh = mesh->SubMeshByIndex(i);
auto submeshMat = submesh->Material();
if (submeshMat)
{
double productAlpha = (1.0-_visual.Transparency()) *
(1.0 - submeshMat->Transparency());
submeshMat->SetTransparency(1 - productAlpha);
submeshMat->SetCastShadows(_visual.CastShadows());
}
}
}
if (material)
{
// set transparency
material->SetTransparency(_visual.Transparency());
// cast shadows
material->SetCastShadows(_visual.CastShadows());
geom->SetMaterial(material);
// todo(anyone) SetMaterial function clones the input material.
// but does not take ownership of it so we need to destroy it here.
// This is not ideal. We should let ign-rendering handle the lifetime
// of this material
this->dataPtr->scene->DestroyMaterial(material);
}
}
else
{
ignerr << "Failed to load geometry for visual: " << _visual.Name()
<< std::endl;
}
// visibility flags
visualVis->SetVisibilityFlags(_visual.VisibilityFlags());
this->dataPtr->visuals[_id] = visualVis;
if (parent)
parent->AddChild(visualVis);
return visualVis;
}
/////////////////////////////////////////////////
rendering::VisualPtr SceneManager::VisualById(Entity _id)
{
if (this->dataPtr->visuals.find(_id) == this->dataPtr->visuals.end())
{
ignerr << "Could not find visual for entity: " << _id << std::endl;
return nullptr;
}
return this->dataPtr->visuals[_id];
}
/////////////////////////////////////////////////
rendering::VisualPtr SceneManager::CreateCollision(Entity _id,
const sdf::Collision &_collision, Entity _parentId)
{
sdf::Material material;
material.SetAmbient(math::Color(1.0f, 0.5088f, 0.0468f, 0.7f));
material.SetDiffuse(math::Color(1.0f, 0.5088f, 0.0468f, 0.7f));
sdf::Visual visual;
visual.SetGeom(*_collision.Geom());
visual.SetMaterial(material);
visual.SetCastShadows(false);
visual.SetRawPose(_collision.RawPose());
visual.SetName(_collision.Name());
rendering::VisualPtr collisionVis = CreateVisual(_id, visual, _parentId);
return collisionVis;
}
/////////////////////////////////////////////////
rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom,
math::Vector3d &_scale, math::Pose3d &_localPose)
{
if (!this->dataPtr->scene)
return rendering::GeometryPtr();
math::Vector3d scale = math::Vector3d::One;
math::Pose3d localPose = math::Pose3d::Zero;
rendering::GeometryPtr geom{nullptr};
if (_geom.Type() == sdf::GeometryType::BOX)
{
geom = this->dataPtr->scene->CreateBox();
scale = _geom.BoxShape()->Size();
}
else if (_geom.Type() == sdf::GeometryType::CAPSULE)
{
auto capsule = this->dataPtr->scene->CreateCapsule();
capsule->SetRadius(_geom.CapsuleShape()->Radius());
capsule->SetLength(_geom.CapsuleShape()->Length());
geom = capsule;
}
else if (_geom.Type() == sdf::GeometryType::CYLINDER)
{
geom = this->dataPtr->scene->CreateCylinder();
scale.X() = _geom.CylinderShape()->Radius() * 2;
scale.Y() = scale.X();
scale.Z() = _geom.CylinderShape()->Length();
}
else if (_geom.Type() == sdf::GeometryType::ELLIPSOID)
{
geom = this->dataPtr->scene->CreateSphere();
scale.X() = _geom.EllipsoidShape()->Radii().X() * 2;
scale.Y() = _geom.EllipsoidShape()->Radii().Y() * 2;
scale.Z() = _geom.EllipsoidShape()->Radii().Z() * 2;
}
else if (_geom.Type() == sdf::GeometryType::PLANE)
{
geom = this->dataPtr->scene->CreatePlane();
scale.X() = _geom.PlaneShape()->Size().X();
scale.Y() = _geom.PlaneShape()->Size().Y();
// Create a rotation for the plane mesh to account for the normal vector.
// The rotation is the angle between the +z(0,0,1) vector and the
// normal, which are both expressed in the local (Visual) frame.
math::Vector3d normal = _geom.PlaneShape()->Normal();
localPose.Rot().From2Axes(math::Vector3d::UnitZ, normal.Normalized());
}
else if (_geom.Type() == sdf::GeometryType::SPHERE)
{
geom = this->dataPtr->scene->CreateSphere();
scale.X() = _geom.SphereShape()->Radius() * 2;
scale.Y() = scale.X();
scale.Z() = scale.X();
}
else if (_geom.Type() == sdf::GeometryType::MESH)
{
auto fullPath = asFullPath(_geom.MeshShape()->Uri(),
_geom.MeshShape()->FilePath());
if (fullPath.empty())
{
ignerr << "Mesh geometry missing uri" << std::endl;
return geom;
}
rendering::MeshDescriptor descriptor;
// Assume absolute path to mesh file
descriptor.meshName = fullPath;
descriptor.subMeshName = _geom.MeshShape()->Submesh();
descriptor.centerSubMesh = _geom.MeshShape()->CenterSubmesh();
ignition::common::MeshManager *meshManager =
ignition::common::MeshManager::Instance();
descriptor.mesh = meshManager->Load(descriptor.meshName);
geom = this->dataPtr->scene->CreateMesh(descriptor);
scale = _geom.MeshShape()->Scale();
}
else if (_geom.Type() == sdf::GeometryType::HEIGHTMAP)
{
auto fullPath = asFullPath(_geom.HeightmapShape()->Uri(),
_geom.HeightmapShape()->FilePath());
if (fullPath.empty())
{
ignerr << "Heightmap geometry missing URI" << std::endl;
return geom;
}
auto data = std::make_shared<common::ImageHeightmap>();
if (data->Load(fullPath) < 0)
{
ignerr << "Failed to load heightmap image data from [" << fullPath << "]"
<< std::endl;
return geom;
}
rendering::HeightmapDescriptor descriptor;
descriptor.SetData(data);
descriptor.SetSize(_geom.HeightmapShape()->Size());
descriptor.SetSampling(_geom.HeightmapShape()->Sampling());
for (uint64_t i = 0; i < _geom.HeightmapShape()->TextureCount(); ++i)
{
auto textureSdf = _geom.HeightmapShape()->TextureByIndex(i);
rendering::HeightmapTexture textureDesc;
textureDesc.SetSize(textureSdf->Size());
textureDesc.SetDiffuse(asFullPath(textureSdf->Diffuse(),
_geom.HeightmapShape()->FilePath()));
textureDesc.SetNormal(asFullPath(textureSdf->Normal(),
_geom.HeightmapShape()->FilePath()));
descriptor.AddTexture(textureDesc);
}
for (uint64_t i = 0; i < _geom.HeightmapShape()->BlendCount(); ++i)
{
auto blendSdf = _geom.HeightmapShape()->BlendByIndex(i);
rendering::HeightmapBlend blendDesc;
blendDesc.SetMinHeight(blendSdf->MinHeight());
blendDesc.SetFadeDistance(blendSdf->FadeDistance());
descriptor.AddBlend(blendDesc);
}
geom = this->dataPtr->scene->CreateHeightmap(descriptor);
if (nullptr == geom)
{
ignerr << "Failed to create heightmap [" << fullPath << "]" << std::endl;
}
scale = _geom.HeightmapShape()->Size();
}
else
{
ignerr << "Unsupported geometry type" << std::endl;
}
_scale = scale;
_localPose = localPose;
return geom;
}
/////////////////////////////////////////////////
rendering::MaterialPtr SceneManager::LoadMaterial(
const sdf::Material &_material)
{
if (!this->dataPtr->scene)
return rendering::MaterialPtr();
rendering::MaterialPtr material = this->dataPtr->scene->CreateMaterial();
material->SetAmbient(_material.Ambient());
material->SetDiffuse(_material.Diffuse());
material->SetSpecular(_material.Specular());
material->SetEmissive(_material.Emissive());
material->SetRenderOrder(_material.RenderOrder());
// parse PBR params
const sdf::Pbr *pbr = _material.PbrMaterial();
if (pbr)
{
sdf::PbrWorkflow *workflow = nullptr;
const sdf::PbrWorkflow *metal =
pbr->Workflow(sdf::PbrWorkflowType::METAL);
if (metal)
{
double roughness = metal->Roughness();
double metalness = metal->Metalness();
material->SetRoughness(roughness);
material->SetMetalness(metalness);
// roughness map
std::string roughnessMap = metal->RoughnessMap();
if (!roughnessMap.empty())
{
std::string fullPath = common::findFile(
asFullPath(roughnessMap, _material.FilePath()));
if (!fullPath.empty())
material->SetRoughnessMap(fullPath);
else
ignerr << "Unable to find file [" << roughnessMap << "]\n";
}
// metalness map
std::string metalnessMap = metal->MetalnessMap();
if (!metalnessMap.empty())
{
std::string fullPath = common::findFile(
asFullPath(metalnessMap, _material.FilePath()));
if (!fullPath.empty())
material->SetMetalnessMap(fullPath);
else
ignerr << "Unable to find file [" << metalnessMap << "]\n";
}
workflow = const_cast<sdf::PbrWorkflow *>(metal);
}
else
{
ignerr << "PBR material: currently only metal workflow is supported"
<< std::endl;
}
// albedo map
std::string albedoMap = workflow->AlbedoMap();
if (!albedoMap.empty())
{
std::string fullPath = common::findFile(
asFullPath(albedoMap, _material.FilePath()));
if (!fullPath.empty())
{
material->SetTexture(fullPath);
// Use alpha channel for transparency
material->SetAlphaFromTexture(true, 0.5, _material.DoubleSided());
}
else
ignerr << "Unable to find file [" << albedoMap << "]\n";
}
// normal map
std::string normalMap = workflow->NormalMap();
if (!normalMap.empty())
{
std::string fullPath = common::findFile(
asFullPath(normalMap, _material.FilePath()));
if (!fullPath.empty())
material->SetNormalMap(fullPath);
else
ignerr << "Unable to find file [" << normalMap << "]\n";
}
// environment map
std::string environmentMap = workflow->EnvironmentMap();
if (!environmentMap.empty())
{
std::string fullPath = common::findFile(
asFullPath(environmentMap, _material.FilePath()));
if (!fullPath.empty())
material->SetEnvironmentMap(fullPath);
else
ignerr << "Unable to find file [" << environmentMap << "]\n";
}
// emissive map
std::string emissiveMap = workflow->EmissiveMap();
if (!emissiveMap.empty())
{
std::string fullPath = common::findFile(
asFullPath(emissiveMap, _material.FilePath()));
if (!fullPath.empty())
material->SetEmissiveMap(fullPath);
else
ignerr << "Unable to find file [" << emissiveMap << "]\n";
}
// light map
std::string lightMap = workflow->LightMap();
if (!lightMap.empty())
{
std::string fullPath = common::findFile(
asFullPath(lightMap, _material.FilePath()));
if (!fullPath.empty())
{
unsigned int uvSet = workflow->LightMapTexCoordSet();
material->SetLightMap(fullPath, uvSet);
}
else
{
ignerr << "Unable to find file [" << lightMap << "]\n";
}
}
}
return material;
}
/////////////////////////////////////////////////
rendering::VisualPtr SceneManager::CreateActor(Entity _id,
const sdf::Actor &_actor, Entity _parentId)
{
if (!this->dataPtr->scene)
return rendering::VisualPtr();
// creating an actor needs to create the visual and the mesh
// the visual is stored in: this->dataPtr->visuals
// the mesh is stored in: this->dataPtr->actors
if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end())
{
ignerr << "Entity with Id: [" << _id << "] already exists in the scene"
<< std::endl;
return rendering::VisualPtr();
}
std::string name = _actor.Name().empty() ? std::to_string(_id) :
_actor.Name();
rendering::VisualPtr parent;
if (_parentId != this->dataPtr->worldId)
{
auto it = this->dataPtr->visuals.find(_parentId);
if (it == this->dataPtr->visuals.end())
{
ignerr << "Parent entity with Id: [" << _parentId << "] not found. "
<< "Not adding actor with ID[" << _id
<< "] and name [" << name << "] to the rendering scene."
<< std::endl;
return rendering::VisualPtr();
}
parent = it->second;
}
if (parent)
name = parent->Name() + "::" + name;
rendering::MeshDescriptor descriptor;
descriptor.meshName = asFullPath(_actor.SkinFilename(), _actor.FilePath());
common::MeshManager *meshManager = common::MeshManager::Instance();
descriptor.mesh = meshManager->Load(descriptor.meshName);
if (nullptr == descriptor.mesh)
{
ignerr << "Actor skin mesh [" << descriptor.meshName << "] not found."
<< std::endl;
return rendering::VisualPtr();
}
// todo(anyone) create a copy of meshSkel so we don't modify the original
// when adding animations!
common::SkeletonPtr meshSkel = descriptor.mesh->MeshSkeleton();
if (nullptr == meshSkel)
{
ignerr << "Mesh skeleton in [" << descriptor.meshName << "] not found."
<< std::endl;
return rendering::VisualPtr();
}
unsigned int numAnims = 0;
std::map<std::string, unsigned int> mapAnimNameId;
mapAnimNameId[descriptor.meshName] = numAnims++;
// Load all animations
for (unsigned i = 0; i < _actor.AnimationCount(); ++i)
{
std::string animName = _actor.AnimationByIndex(i)->Name();
std::string animFilename = asFullPath(
_actor.AnimationByIndex(i)->Filename(),
_actor.AnimationByIndex(i)->FilePath());
double animScale = _actor.AnimationByIndex(i)->Scale();
std::string extension = animFilename.substr(animFilename.rfind('.') + 1,
animFilename.size());
std::transform(extension.begin(), extension.end(),
extension.begin(), ::tolower);
if (extension == "bvh")
{
// do not add duplicate animation
// start checking from index 1 since index 0 is reserved by skin mesh
bool addAnim = true;
for (unsigned int a = 1; a < meshSkel->AnimationCount(); ++a)
{
if (meshSkel->Animation(a)->Name() == animFilename)
{
addAnim = false;
break;
}
}
if (addAnim)
meshSkel->AddBvhAnimation(animFilename, animScale);
mapAnimNameId[animName] = numAnims++;
}
else if (extension == "dae")
{
// Load the mesh if it has not been loaded before
const common::Mesh *animMesh = nullptr;
if (!meshManager->HasMesh(animFilename))
{
animMesh = meshManager->Load(animFilename);
if (animMesh->MeshSkeleton()->AnimationCount() > 1)
{
ignwarn << "File [" << animFilename
<< "] has more than one animation, but only the 1st one is used."
<< std::endl;
}
}
animMesh = meshManager->MeshByName(animFilename);
// add the first animation
auto firstAnim = animMesh->MeshSkeleton()->Animation(0);
if (nullptr == firstAnim)
{
ignerr << "Failed to get animations from [" << animFilename
<< "]" << std::endl;
return nullptr;
}
// do not add duplicate animation
// start checking from index 1 since index 0 is reserved by skin mesh
bool addAnim = true;
for (unsigned int a = 1; a < meshSkel->AnimationCount(); ++a)
{
if (meshSkel->Animation(a)->Name() == animName)
{
addAnim = false;
break;
}
}
if (addAnim)
{
// collada loader loads animations with name that defaults to
// "animation0", "animation"1", etc causing conflicts in names
// when multiple animations are added to meshSkel.
// We have to clone the skeleton animation before giving it a unique
// name otherwise if mulitple instances of the same animation were added
// to meshSkel, changing the name that would also change the name of
// other instances of the animation
// todo(anyone) cloning is inefficient and error-prone. We should
// add a copy constructor to animation classes in ign-common.
// The proper fix is probably to update ign-rendering to allow it to
// load multiple animations of the same name
common::SkeletonAnimation *skelAnim =
new common::SkeletonAnimation(animName);
for (unsigned int j = 0; j < meshSkel->NodeCount(); ++j)
{
common::SkeletonNode *node = meshSkel->NodeByHandle(j);
common::NodeAnimation *nodeAnim = firstAnim->NodeAnimationByName(
node->Name());
if (!nodeAnim)
continue;
for (unsigned int k = 0; k < nodeAnim->FrameCount(); ++k)
{
std::pair<double, math::Matrix4d> keyFrame = nodeAnim->KeyFrame(k);
skelAnim->AddKeyFrame(
node->Name(), keyFrame.first, keyFrame.second);
}
}
meshSkel->AddAnimation(skelAnim);
}
mapAnimNameId[animName] = numAnims++;
}
}
this->dataPtr->actorSkeletons[_id] = meshSkel;
std::vector<common::TrajectoryInfo> trajectories;
if (_actor.TrajectoryCount() != 0)
{
// Load all trajectories specified in sdf
for (unsigned i = 0; i < _actor.TrajectoryCount(); i++)
{
const sdf::Trajectory *trajSdf = _actor.TrajectoryByIndex(i);
if (nullptr == trajSdf)
{
ignerr << "Null trajectory SDF for [" << _actor.Name() << "]"
<< std::endl;
continue;
}
common::TrajectoryInfo trajInfo;
trajInfo.SetId(trajSdf->Id());
trajInfo.SetAnimIndex(mapAnimNameId[trajSdf->Type()]);
if (trajSdf->WaypointCount() != 0)
{
std::map<TP, math::Pose3d> waypoints;
for (unsigned j = 0; j < trajSdf->WaypointCount(); j++)
{
auto point = trajSdf->WaypointByIndex(j);
TP pointTp(std::chrono::milliseconds(
static_cast<int>(point->Time()*1000)));
waypoints[pointTp] = point->Pose();
}
trajInfo.SetWaypoints(waypoints);
// Animations are offset by 1 because index 0 is taken by the mesh name
auto animation = _actor.AnimationByIndex(trajInfo.AnimIndex()-1);
if (animation && animation->InterpolateX())
{
// warn if no x displacement can be interpolated
// warn only once per mesh
static std::unordered_set<std::string> animInterpolateCheck;
if (animInterpolateCheck.count(animation->Filename()) == 0)
{
std::string rootNodeName = meshSkel->RootNode()->Name();
common::SkeletonAnimation *skelAnim =
meshSkel->Animation(trajInfo.AnimIndex());
common::NodeAnimation *rootNode = skelAnim->NodeAnimationByName(
rootNodeName);
math::Matrix4d lastPos = rootNode->KeyFrame(
rootNode->FrameCount() - 1).second;
math::Matrix4d firstPos = rootNode->KeyFrame(0).second;
if (!math::equal(firstPos.Translation().X(),
lastPos.Translation().X()))
{
trajInfo.Waypoints()->SetInterpolateX(animation->InterpolateX());
}
else
{
ignwarn << "Animation has no x displacement. "
<< "Ignoring <interpolate_x> for the animation in '"
<< animation->Filename() << "'." << std::endl;
}
animInterpolateCheck.insert(animation->Filename());
}
}
}
else
{
trajInfo.SetTranslated(false);
}
trajectories.push_back(trajInfo);
}
}
// if there are no trajectories, but there are animations, add a trajectory
else
{
auto skel = this->dataPtr->actorSkeletons[_id];
common::TrajectoryInfo trajInfo;
trajInfo.SetId(0);
trajInfo.SetAnimIndex(0);
trajInfo.SetStartTime(TP(0ms));
auto timepoint = std::chrono::milliseconds(
static_cast<int>(skel->Animation(0)->Length() * 1000));
trajInfo.SetEndTime(TP(timepoint));
trajInfo.SetTranslated(false);
trajectories.push_back(trajInfo);
}
// sequencing all trajectories
auto delayStartTime = std::chrono::milliseconds(
static_cast<int>(_actor.ScriptDelayStart() * 1000));
TP time(delayStartTime);
for (auto &trajectory : trajectories)
{
auto dura = trajectory.Duration();
trajectory.SetStartTime(time);
time += dura;
trajectory.SetEndTime(time);
}
// loop flag: add a placeholder trajectory to indicate no loop
if (!_actor.ScriptLoop())
{
common::TrajectoryInfo noLoopTrajInfo;
noLoopTrajInfo.SetId(0);
noLoopTrajInfo.SetAnimIndex(0);
noLoopTrajInfo.SetStartTime(time);
noLoopTrajInfo.SetEndTime(time);
noLoopTrajInfo.SetTranslated(false);
trajectories.push_back(noLoopTrajInfo);
}
this->dataPtr->actorTrajectories[_id] = trajectories;
// create mesh with animations
rendering::MeshPtr actorMesh = this->dataPtr->scene->CreateMesh(
descriptor);
if (nullptr == actorMesh)
{
ignerr << "Actor skin file [" << descriptor.meshName << "] not found."
<< std::endl;
return rendering::VisualPtr();
}
rendering::VisualPtr actorVisual = this->dataPtr->scene->CreateVisual(name);
actorVisual->SetLocalPose(_actor.RawPose());
actorVisual->AddGeometry(actorMesh);
actorVisual->SetUserData("gazebo-entity", static_cast<int>(_id));
actorVisual->SetUserData("pause-update", static_cast<int>(0));
this->dataPtr->visuals[_id] = actorVisual;
this->dataPtr->actors[_id] = actorMesh;
if (parent)
parent->AddChild(actorVisual);
else
this->dataPtr->scene->RootVisual()->AddChild(actorVisual);
return actorVisual;
}
/////////////////////////////////////////////////
rendering::VisualPtr SceneManager::CreateLightVisual(Entity _id,
const sdf::Light &_light, Entity _parentId)
{
if (!this->dataPtr->scene)
return rendering::VisualPtr();
if (this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end())