-
Notifications
You must be signed in to change notification settings - Fork 269
/
Physics.cc
1965 lines (1712 loc) · 73 KB
/
Physics.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Copyright (C) 2018 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include <ignition/msgs/contact.pb.h>
#include <ignition/msgs/contacts.pb.h>
#include <ignition/msgs/entity.pb.h>
#include <ignition/msgs/Utility.hh>
#include <iostream>
#include <deque>
#include <unordered_map>
#include <ignition/common/MeshManager.hh>
#include <ignition/common/Profiler.hh>
#include <ignition/common/SystemPaths.hh>
#include <ignition/math/AxisAlignedBox.hh>
#include <ignition/math/eigen3/Conversions.hh>
#include <ignition/physics/config.hh>
#include <ignition/physics/FeatureList.hh>
#include <ignition/physics/FeaturePolicy.hh>
#include <ignition/physics/FindFeatures.hh>
#include <ignition/physics/RelativeQuantity.hh>
#include <ignition/physics/RequestEngine.hh>
#include <ignition/plugin/Loader.hh>
#include <ignition/plugin/PluginPtr.hh>
#include <ignition/plugin/Register.hh>
// Features
#include <ignition/physics/BoxShape.hh>
#include <ignition/physics/CylinderShape.hh>
#include <ignition/physics/ForwardStep.hh>
#include <ignition/physics/FrameSemantics.hh>
#include <ignition/physics/FreeGroup.hh>
#include <ignition/physics/FixedJoint.hh>
#include <ignition/physics/GetContacts.hh>
#include <ignition/physics/GetBoundingBox.hh>
#include <ignition/physics/Joint.hh>
#include <ignition/physics/Link.hh>
#include <ignition/physics/RemoveEntities.hh>
#include <ignition/physics/Shape.hh>
#include <ignition/physics/SphereShape.hh>
#include <ignition/physics/mesh/MeshShape.hh>
#include <ignition/physics/sdf/ConstructCollision.hh>
#include <ignition/physics/sdf/ConstructJoint.hh>
#include <ignition/physics/sdf/ConstructLink.hh>
#include <ignition/physics/sdf/ConstructModel.hh>
#include <ignition/physics/sdf/ConstructWorld.hh>
// SDF
#include <sdf/Collision.hh>
#include <sdf/Joint.hh>
#include <sdf/Link.hh>
#include <sdf/Mesh.hh>
#include <sdf/Model.hh>
#include <sdf/Surface.hh>
#include <sdf/World.hh>
#include "ignition/gazebo/EntityComponentManager.hh"
#include "ignition/gazebo/Util.hh"
// Components
#include "ignition/gazebo/components/AngularAcceleration.hh"
#include "ignition/gazebo/components/AngularVelocity.hh"
#include "ignition/gazebo/components/AxisAlignedBox.hh"
#include "ignition/gazebo/components/BatterySoC.hh"
#include "ignition/gazebo/components/CanonicalLink.hh"
#include "ignition/gazebo/components/ChildLinkName.hh"
#include "ignition/gazebo/components/Collision.hh"
#include "ignition/gazebo/components/ContactSensorData.hh"
#include "ignition/gazebo/components/Geometry.hh"
#include "ignition/gazebo/components/Gravity.hh"
#include "ignition/gazebo/components/Inertial.hh"
#include "ignition/gazebo/components/DetachableJoint.hh"
#include "ignition/gazebo/components/Joint.hh"
#include "ignition/gazebo/components/JointAxis.hh"
#include "ignition/gazebo/components/JointPosition.hh"
#include "ignition/gazebo/components/JointPositionReset.hh"
#include "ignition/gazebo/components/JointType.hh"
#include "ignition/gazebo/components/JointVelocity.hh"
#include "ignition/gazebo/components/JointVelocityCmd.hh"
#include "ignition/gazebo/components/JointVelocityReset.hh"
#include "ignition/gazebo/components/LinearAcceleration.hh"
#include "ignition/gazebo/components/LinearVelocity.hh"
#include "ignition/gazebo/components/Link.hh"
#include "ignition/gazebo/components/Model.hh"
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/ParentEntity.hh"
#include "ignition/gazebo/components/ParentLinkName.hh"
#include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh"
#include "ignition/gazebo/components/JointForceCmd.hh"
#include "ignition/gazebo/components/PhysicsEnginePlugin.hh"
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/PoseCmd.hh"
#include "ignition/gazebo/components/SelfCollide.hh"
#include "ignition/gazebo/components/Static.hh"
#include "ignition/gazebo/components/ThreadPitch.hh"
#include "ignition/gazebo/components/World.hh"
#include "Physics.hh"
using namespace ignition;
using namespace ignition::gazebo::systems;
namespace components = ignition::gazebo::components;
// Private data class.
class ignition::gazebo::systems::PhysicsPrivate
{
/// \brief This is the minimum set of features that any physics engine must
/// implement to be supported by this system.
/// New features can't be added to this list in minor / patch releases, in
/// order to maintain backwards compatibility with downstream physics plugins.
public: struct MinimumFeatureList : ignition::physics::FeatureList<
ignition::physics::FindFreeGroupFeature,
ignition::physics::SetFreeGroupWorldPose,
ignition::physics::FreeGroupFrameSemantics,
ignition::physics::LinkFrameSemantics,
ignition::physics::ForwardStep,
ignition::physics::RemoveEntities,
ignition::physics::sdf::ConstructSdfLink,
ignition::physics::sdf::ConstructSdfModel,
ignition::physics::sdf::ConstructSdfWorld
>{};
/// \brief Engine type with just the minimum features.
public: using EnginePtrType = ignition::physics::EnginePtr<
ignition::physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief World type with just the minimum features.
public: using WorldPtrType = ignition::physics::WorldPtr<
ignition::physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief Model type with just the minimum features.
public: using ModelPtrType = ignition::physics::ModelPtr<
ignition::physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief Link type with just the minimum features.
public: using LinkPtrType = ignition::physics::LinkPtr<
ignition::physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief Free group type with just the minimum features.
public: using FreeGroupPtrType = ignition::physics::FreeGroupPtr<
ignition::physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief Create physics entities
/// \param[in] _ecm Constant reference to ECM.
public: void CreatePhysicsEntities(const EntityComponentManager &_ecm);
/// \brief Remove physics entities if they are removed from the ECM
/// \param[in] _ecm Constant reference to ECM.
public: void RemovePhysicsEntities(const EntityComponentManager &_ecm);
/// \brief Update physics from components
/// \param[in] _ecm Constant reference to ECM.
public: void UpdatePhysics(EntityComponentManager &_ecm);
/// \brief Step the simulationrfor each world
/// \param[in] _dt Duration
public: void Step(const std::chrono::steady_clock::duration &_dt);
/// \brief Update components from physics simulation
/// \param[in] _ecm Mutable reference to ECM.
public: void UpdateSim(EntityComponentManager &_ecm);
/// \brief Update collision components from physics simulation
/// \param[in] _ecm Mutable reference to ECM.
public: void UpdateCollisions(EntityComponentManager &_ecm);
/// \brief FrameData relative to world at a given offset pose
/// \param[in] _link ign-physics link
/// \param[in] _pose Offset pose in which to compute the frame data
/// \returns FrameData at the given offset pose
public: physics::FrameData3d LinkFrameDataAtOffset(
const LinkPtrType &_link, const math::Pose3d &_pose) const;
/// \brief A map between world entity ids in the ECM to World Entities in
/// ign-physics.
public: std::unordered_map<Entity, WorldPtrType> entityWorldMap;
/// \brief A map between model entity ids in the ECM to Model Entities in
/// ign-physics.
public: std::unordered_map<Entity, ModelPtrType> entityModelMap;
/// \brief A map between link entity ids in the ECM to Link Entities in
/// ign-physics.
public: std::unordered_map<Entity, LinkPtrType> entityLinkMap;
/// \brief Reverse of entityLinkMap. This is used for finding the Entity
/// associated with a physics Link
public: std::unordered_map<LinkPtrType, Entity> linkEntityMap;
/// \brief A map between model entity ids in the ECM to whether its battery
/// has drained.
public: std::unordered_map<Entity, bool> entityOffMap;
/// \brief used to store whether physics objects have been created.
public: bool initialized = false;
/// \brief Pointer to the underlying ign-physics Engine entity.
public: EnginePtrType engine = nullptr;
/// \brief Vector3d equality comparison function.
public: std::function<bool(const math::Vector3d &, const math::Vector3d &)>
vec3Eql { [](const math::Vector3d &_a, const math::Vector3d &_b)
{
return _a.Equal(_b, 1e-6);
}};
/// \brief Pose3d equality comparison function.
public: std::function<bool(const math::Pose3d &, const math::Pose3d &)>
pose3Eql { [](const math::Pose3d &_a, const math::Pose3d &_b)
{
return _a.Pos().Equal(_b.Pos(), 1e-6) &&
math::equal(_a.Rot().X(), _b.Rot().X(), 1e-6) &&
math::equal(_a.Rot().Y(), _b.Rot().Y(), 1e-6) &&
math::equal(_a.Rot().Z(), _b.Rot().Z(), 1e-6) &&
math::equal(_a.Rot().W(), _b.Rot().W(), 1e-6);
}};
/// \brief AxisAlignedBox equality comparison function.
public: std::function<bool(const math::AxisAlignedBox &,
const math::AxisAlignedBox&)>
axisAlignedBoxEql { [](const math::AxisAlignedBox &_a,
const math::AxisAlignedBox &_b)
{
return _a == _b;
}};
/// \brief Environment variable which holds paths to look for engine plugins
public: std::string pluginPathEnv = "IGN_GAZEBO_PHYSICS_ENGINE_PATH";
//////////////////////////////////////////////////
// Joints
/// \brief Feature list to handle joints.
public: using JointFeatureList = ignition::physics::FeatureList<
MinimumFeatureList,
ignition::physics::GetBasicJointProperties,
ignition::physics::GetBasicJointState,
ignition::physics::SetBasicJointState,
ignition::physics::sdf::ConstructSdfJoint>;
/// \brief Joint type with joint features.
public: using JointPtrType = ignition::physics::JointPtr<
ignition::physics::FeaturePolicy3d, JointFeatureList>;
/// \brief Model type with joint features (models to attach to).
public: using ModelJointPtrType = ignition::physics::ModelPtr<
ignition::physics::FeaturePolicy3d, JointFeatureList>;
/// \brief A map between joint entity ids in the ECM to Joint Entities in
/// ign-physics
public: std::unordered_map<Entity, JointPtrType> entityJointMap;
/// \brief A map between model entity ids in the ECM to Model Entities in
/// ign-physics, with attach feature.
/// All models on this map are also in `entityModelMap`. The difference is
/// that here they've been casted for `JointFeatureList`.
public: std::unordered_map<Entity, ModelJointPtrType> entityModelJointMap;
//////////////////////////////////////////////////
// Detachable joints
/// \brief Feature list to process `DetachableJoint` components.
public: using DetachableJointFeatureList = physics::FeatureList<
JointFeatureList,
physics::AttachFixedJointFeature,
physics::DetachJointFeature,
physics::SetJointTransformFromParentFeature>;
/// \brief Joint type with detachable joint features.
public: using JointDetachableJointPtrType = physics::JointPtr<
physics::FeaturePolicy3d, DetachableJointFeatureList>;
/// \brief Link type with detachable joint features (links to attach to).
public: using LinkDetachableJointPtrType = physics::LinkPtr<
physics::FeaturePolicy3d, DetachableJointFeatureList>;
/// \brief A map between joint entity ids in the ECM to Joint Entities in
/// ign-physics, with detach feature.
/// All joints on this map are also in `entityJointMap`. The difference is
/// that here they've been casted for `physics::DetachJointFeature`.
public: std::unordered_map<Entity, JointDetachableJointPtrType>
entityJointDetachableJointMap;
/// \brief A map between link entity ids in the ECM to Link Entities in
/// ign-physics, with attach feature.
/// All links on this map are also in `entityLinkMap`. The difference is
/// that here they've been casted for `DetachableJointFeatureList`.
public: std::unordered_map<Entity, LinkDetachableJointPtrType>
entityLinkDetachableJointMap;
//////////////////////////////////////////////////
// Collisions
/// \brief Feature list to handle collisions.
public: using CollisionFeatureList = ignition::physics::FeatureList<
MinimumFeatureList,
ignition::physics::GetContactsFromLastStepFeature,
ignition::physics::sdf::ConstructSdfCollision>;
/// \brief Collision type with collision features.
public: using ShapePtrType = ignition::physics::ShapePtr<
ignition::physics::FeaturePolicy3d, CollisionFeatureList>;
/// \brief Link type with collision features.
public: using LinkShapePtrType = ignition::physics::LinkPtr<
ignition::physics::FeaturePolicy3d, CollisionFeatureList>;
/// \brief World type with collision features.
public: using WorldShapePtrType = ignition::physics::WorldPtr<
ignition::physics::FeaturePolicy3d, CollisionFeatureList>;
/// \brief World type with just the minimum features. Non-pointer.
public: using WorldShapeType = ignition::physics::World<
ignition::physics::FeaturePolicy3d, CollisionFeatureList>;
/// \brief A map between collision entity ids in the ECM to Shape Entities in
/// ign-physics.
public: std::unordered_map<Entity, ShapePtrType> entityCollisionMap;
/// \brief A map between shape entities in ign-physics to collision entities
/// in the ECM. This is the reverse map of entityCollisionMap.
public: std::unordered_map<ShapePtrType, Entity> collisionEntityMap;
/// \brief A map between link entity ids in the ECM to Link Entities in
/// ign-physics, with attach feature.
/// All links on this map are also in `entityLinkMap`. The difference is
/// that here they've been casted for `CollisionFeatureList`.
public: std::unordered_map<Entity, LinkShapePtrType> entityLinkCollisionMap;
/// \brief A map between world entity ids in the ECM to World Entities in
/// ign-physics, with attach feature.
/// All worlds on this map are also in `entityWorldMap`. The difference is
/// that here they've been casted for `CollisionFeatureList`.
public: std::unordered_map<Entity, WorldShapePtrType> entityWorldCollisionMap;
//////////////////////////////////////////////////
// Collision filtering with bitmasks
/// \brief Feature list to filter collisions with bitmasks.
public: using CollisionMaskFeatureList = ignition::physics::FeatureList<
CollisionFeatureList,
ignition::physics::CollisionFilterMaskFeature>;
/// \brief Collision type with collision filtering features.
public: using ShapeFilterMaskPtrType = ignition::physics::ShapePtr<
ignition::physics::FeaturePolicy3d, CollisionMaskFeatureList>;
/// \brief A map between collision entity ids in the ECM to Shape Entities in
/// ign-physics, with collision filtering feature.
/// All links on this map are also in `entityCollisionMap`. The difference is
/// that here they've been casted for `CollisionMaskFeatureList`.
public: std::unordered_map<Entity, ShapeFilterMaskPtrType> entityShapeMaskMap;
//////////////////////////////////////////////////
// Link force
/// \brief Feature list for applying forces to links.
public: using LinkForceFeatureList = ignition::physics::FeatureList<
ignition::physics::AddLinkExternalForceTorque>;
/// \brief Link type with bounding box feature.
public: using LinkForcePtrType = ignition::physics::LinkPtr<
ignition::physics::FeaturePolicy3d, LinkForceFeatureList>;
/// \brief A map between link entity ids in the ECM to Link Entities in
/// ign-physics, with force feature.
/// All links on this map are also in `entityLinkMap`. The difference is
/// that here they've been casted for `LinkForceFeatureList`.
public: std::unordered_map<Entity, LinkForcePtrType> entityLinkForceMap;
//////////////////////////////////////////////////
// Bounding box
/// \brief Feature list for model bounding box.
public: using BoundingBoxFeatureList = ignition::physics::FeatureList<
MinimumFeatureList,
ignition::physics::GetModelBoundingBox>;
/// \brief Model type with bounding box feature.
public: using ModelBoundingBoxPtrType = ignition::physics::ModelPtr<
ignition::physics::FeaturePolicy3d, BoundingBoxFeatureList>;
/// \brief A map between model entity ids in the ECM to Model Entities in
/// ign-physics, with bounding box feature.
/// All models on this map are also in `entityModelMap`. The difference is
/// that here they've been casted for `BoundingBoxFeatureList`.
public: std::unordered_map<Entity, ModelBoundingBoxPtrType>
entityModelBoundingBoxMap;
//////////////////////////////////////////////////
// Joint velocity command
/// \brief Feature list for set joint velocity command.
public: using JointVelocityCommandFeatureList = physics::FeatureList<
physics::SetJointVelocityCommandFeature>;
/// \brief Joint type with set joint velocity command.
public: using JointVelocityCommandPtrType = physics::JointPtr<
physics::FeaturePolicy3d, JointVelocityCommandFeatureList>;
/// \brief A map between joint entity ids in the ECM to Joint Entities in
/// ign-physics, with velocity command feature.
/// All joints on this map are also in `entityJointMap`. The difference is
/// that here they've been casted for `JointVelocityCommandFeatureList`.
public: std::unordered_map<Entity, JointVelocityCommandPtrType>
entityJointVelocityCommandMap;
//////////////////////////////////////////////////
// Meshes
/// \brief Feature list for meshes.
/// Include MinimumFeatureList so created collision can be automatically
/// up-cast.
public: using MeshFeatureList = physics::FeatureList<
CollisionFeatureList,
physics::mesh::AttachMeshShapeFeature>;
/// \brief Link type with meshes.
public: using LinkMeshPtrType = physics::LinkPtr<
physics::FeaturePolicy3d, MeshFeatureList>;
/// \brief A map between link entity ids in the ECM to Link Entities in
/// ign-physics, with mesh feature.
/// All links on this map are also in `entityLinkMap`. The difference is
/// that here they've been casted for `MeshFeatureList`.
public: std::unordered_map<Entity, LinkMeshPtrType>
entityLinkMeshMap;
};
//////////////////////////////////////////////////
Physics::Physics() : System(), dataPtr(std::make_unique<PhysicsPrivate>())
{
}
//////////////////////////////////////////////////
void Physics::Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &_ecm,
EventManager &/*_eventMgr*/)
{
std::string pluginLib;
// 1. Engine from component (from command line / ServerConfig)
auto engineComp = _ecm.Component<components::PhysicsEnginePlugin>(_entity);
if (engineComp && !engineComp->Data().empty())
{
pluginLib = engineComp->Data();
}
// 2. Engine from SDF
else if (_sdf->HasElement("engine"))
{
auto sdfClone = _sdf->Clone();
auto engineElem = sdfClone->GetElement("engine");
pluginLib = engineElem->Get<std::string>("filename", pluginLib).first;
}
// 3. Use DART by default
if (pluginLib.empty())
{
pluginLib = "libignition-physics-dartsim-plugin.so";
}
// Update component
if (!engineComp)
{
_ecm.CreateComponent(_entity, components::PhysicsEnginePlugin(pluginLib));
}
else
{
engineComp->SetData(pluginLib,
[](const std::string &_a, const std::string &_b){return _a == _b;});
}
// Find engine shared library
// Look in:
// * Paths from environment variable
// * Engines installed with ign-physics
common::SystemPaths systemPaths;
systemPaths.SetPluginPathEnv(this->dataPtr->pluginPathEnv);
systemPaths.AddPluginPaths({IGNITION_PHYSICS_ENGINE_INSTALL_DIR});
auto pathToLib = systemPaths.FindSharedLibrary(pluginLib);
if (pathToLib.empty())
{
ignerr << "Failed to find plugin [" << pluginLib
<< "]. Have you checked the " << this->dataPtr->pluginPathEnv
<< " environment variable?" << std::endl;
return;
}
// Load engine plugin
ignition::plugin::Loader pluginLoader;
auto plugins = pluginLoader.LoadLib(pathToLib);
if (plugins.empty())
{
ignerr << "Unable to load the [" << pathToLib << "] library.\n";
return;
}
auto classNames = pluginLoader.AllPlugins();
if (classNames.empty())
{
ignerr << "No plugins found in library [" << pathToLib << "]." << std::endl;
return;
}
// Get the first plugin that works
for (auto className : classNames)
{
auto plugin = pluginLoader.Instantiate(className);
if (!plugin)
continue;
this->dataPtr->engine = ignition::physics::RequestEngine<
ignition::physics::FeaturePolicy3d,
PhysicsPrivate::MinimumFeatureList>::From(plugin);
if (nullptr != this->dataPtr->engine)
{
igndbg << "Loaded [" << className << "] from library ["
<< pathToLib << "]" << std::endl;
break;
}
auto missingFeatures = ignition::physics::RequestEngine<
ignition::physics::FeaturePolicy3d,
PhysicsPrivate::MinimumFeatureList>::MissingFeatureNames(plugin);
std::stringstream msg;
msg << "Plugin [" << className << "] misses required features:"
<< std::endl;
for (auto feature : missingFeatures)
{
msg << "- " << feature << std::endl;
}
ignwarn << msg.str();
}
if (nullptr == this->dataPtr->engine)
{
ignerr << "Failed to load a valid physics engine from [" << pathToLib
<< "]."
<< std::endl;
}
}
//////////////////////////////////////////////////
Physics::~Physics() = default;
//////////////////////////////////////////////////
void Physics::Update(const UpdateInfo &_info, EntityComponentManager &_ecm)
{
IGN_PROFILE("Physics::Update");
// \TODO(anyone) Support rewind
if (_info.dt < std::chrono::steady_clock::duration::zero())
{
ignwarn << "Detected jump back in time ["
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
}
if (this->dataPtr->engine)
{
this->dataPtr->CreatePhysicsEntities(_ecm);
this->dataPtr->UpdatePhysics(_ecm);
// Only step if not paused.
if (!_info.paused)
{
this->dataPtr->Step(_info.dt);
}
this->dataPtr->UpdateSim(_ecm);
// Entities scheduled to be removed should be removed from physics after the
// simulation step. Otherwise, since the to-be-removed entity still shows up
// in the ECM::Each the UpdatePhysics and UpdateSim calls will have an error
this->dataPtr->RemovePhysicsEntities(_ecm);
}
}
//////////////////////////////////////////////////
void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm)
{
// Get all the new worlds
_ecm.EachNew<components::World, components::Name, components::Gravity>(
[&](const Entity &_entity,
const components::World * /* _world */,
const components::Name *_name,
const components::Gravity *_gravity)->bool
{
// Check if world already exists
if (this->entityWorldMap.find(_entity) != this->entityWorldMap.end())
{
ignwarn << "World entity [" << _entity
<< "] marked as new, but it's already on the map."
<< std::endl;
return true;
}
sdf::World world;
world.SetName(_name->Data());
world.SetGravity(_gravity->Data());
auto worldPtrPhys = this->engine->ConstructWorld(world);
this->entityWorldMap.insert(std::make_pair(_entity, worldPtrPhys));
return true;
});
_ecm.EachNew<components::Model, components::Name, components::Pose,
components::ParentEntity>(
[&](const Entity &_entity,
const components::Model *,
const components::Name *_name,
const components::Pose *_pose,
const components::ParentEntity *_parent)->bool
{
// Check if model already exists
if (this->entityModelMap.find(_entity) != this->entityModelMap.end())
{
ignwarn << "Model entity [" << _entity
<< "] marked as new, but it's already on the map."
<< std::endl;
return true;
}
// TODO(anyone) Don't load models unless they have collisions
// Check if parent world exists
// TODO(louise): Support nested models, see
// https://github.com/ignitionrobotics/ign-physics/issues/10
if (this->entityWorldMap.find(_parent->Data())
== this->entityWorldMap.end())
{
ignwarn << "Model's parent entity [" << _parent->Data()
<< "] not found on world map." << std::endl;
return true;
}
auto worldPtrPhys = this->entityWorldMap.at(_parent->Data());
sdf::Model model;
model.SetName(_name->Data());
model.SetRawPose(_pose->Data());
auto staticComp = _ecm.Component<components::Static>(_entity);
if (staticComp && staticComp->Data())
{
model.SetStatic(staticComp->Data());
}
auto selfCollideComp = _ecm.Component<components::SelfCollide>(_entity);
if (selfCollideComp && selfCollideComp ->Data())
{
model.SetSelfCollide(selfCollideComp->Data());
}
auto modelPtrPhys = worldPtrPhys->ConstructModel(model);
this->entityModelMap.insert(std::make_pair(_entity, modelPtrPhys));
return true;
});
_ecm.EachNew<components::Link, components::Name, components::Pose,
components::ParentEntity>(
[&](const Entity &_entity,
const components::Link * /* _link */,
const components::Name *_name,
const components::Pose *_pose,
const components::ParentEntity *_parent)->bool
{
// Check if link already exists
if (this->entityLinkMap.find(_entity) != this->entityLinkMap.end())
{
ignwarn << "Link entity [" << _entity
<< "] marked as new, but it's already on the map."
<< std::endl;
return true;
}
// TODO(anyone) Don't load links unless they have collisions
// Check if parent model exists
if (this->entityModelMap.find(_parent->Data())
== this->entityModelMap.end())
{
ignwarn << "Link's parent entity [" << _parent->Data()
<< "] not found on model map." << std::endl;
return true;
}
auto modelPtrPhys = this->entityModelMap.at(_parent->Data());
sdf::Link link;
link.SetName(_name->Data());
link.SetRawPose(_pose->Data());
// get link inertial
auto inertial = _ecm.Component<components::Inertial>(_entity);
if (inertial)
{
link.SetInertial(inertial->Data());
}
auto linkPtrPhys = modelPtrPhys->ConstructLink(link);
this->entityLinkMap.insert(std::make_pair(_entity, linkPtrPhys));
this->linkEntityMap.insert(std::make_pair(linkPtrPhys, _entity));
return true;
});
// We don't need to add visuals to the physics engine.
// collisions
_ecm.EachNew<components::Collision, components::Name, components::Pose,
components::Geometry, components::CollisionElement,
components::ParentEntity>(
[&](const Entity & _entity,
const components::Collision *,
const components::Name *_name,
const components::Pose *_pose,
const components::Geometry *_geom,
const components::CollisionElement *_collElement,
const components::ParentEntity *_parent) -> bool
{
if (this->entityCollisionMap.find(_entity) !=
this->entityCollisionMap.end())
{
ignwarn << "Collision entity [" << _entity
<< "] marked as new, but it's already on the map."
<< std::endl;
return true;
}
// Check if parent link exists
if (this->entityLinkMap.find(_parent->Data())
== this->entityLinkMap.end())
{
ignwarn << "Collision's parent entity [" << _parent->Data()
<< "] not found on link map." << std::endl;
return true;
}
auto linkPtrPhys = this->entityLinkMap.at(_parent->Data());
// Make a copy of the collision DOM so we can set its pose which has
// been resolved and is now expressed w.r.t the parent link of the
// collision.
sdf::Collision collision = _collElement->Data();
collision.SetRawPose(_pose->Data());
collision.SetPoseRelativeTo("");
auto collideBitmask = collision.Surface()->Contact()->CollideBitmask();
ShapePtrType collisionPtrPhys;
if (_geom->Data().Type() == sdf::GeometryType::MESH)
{
const sdf::Mesh *meshSdf = _geom->Data().MeshShape();
if (nullptr == meshSdf)
{
ignwarn << "Mesh geometry for collision [" << _name->Data()
<< "] missing mesh shape." << std::endl;
return true;
}
auto &meshManager = *ignition::common::MeshManager::Instance();
auto fullPath = asFullPath(meshSdf->Uri(), meshSdf->FilePath());
auto *mesh = meshManager.Load(fullPath);
if (nullptr == mesh)
{
ignwarn << "Failed to load mesh from [" << fullPath
<< "]." << std::endl;
return true;
}
auto linkMeshFeature = entityCast(_parent->Data(), linkPtrPhys,
this->entityLinkMeshMap);
if (!linkMeshFeature)
{
static bool informed{false};
if (!informed)
{
igndbg << "Attempting to process mesh geometries, but the physics"
<< " engine doesn't support feature "
<< "[AttachMeshShapeFeature]. Meshes will be ignored."
<< std::endl;
informed = true;
}
return true;
}
collisionPtrPhys = linkMeshFeature->AttachMeshShape(_name->Data(),
*mesh,
math::eigen3::convert(_pose->Data()),
math::eigen3::convert(meshSdf->Scale()));
}
else
{
auto linkCollisionFeature = entityCast(_parent->Data(), linkPtrPhys,
this->entityLinkCollisionMap);
if (!linkCollisionFeature)
{
static bool informed{false};
if (!informed)
{
igndbg << "Attempting to process collisions, but the physics "
<< "engine doesn't support feature "
<< "[ConstructSdfCollision]. Collisions will be ignored."
<< std::endl;
informed = true;
}
return true;
}
collisionPtrPhys =
linkCollisionFeature->ConstructCollision(collision);
}
// Check that the physics engine has a filter mask feature
// Set the collide_bitmask if it does
auto filterMaskFeature = entityCast(_parent->Data(), collisionPtrPhys,
entityShapeMaskMap);
if (filterMaskFeature)
{
filterMaskFeature->SetCollisionFilterMask(collideBitmask);
}
else
{
static bool informed{false};
if (!informed)
{
igndbg << "Attempting to set collision bitmasks, but the physics "
<< "engine doesn't support feature [CollisionFilterMask]. "
<< "Collision bitmasks will be ignored." << std::endl;
informed = true;
}
}
this->entityCollisionMap.insert(
std::make_pair(_entity, collisionPtrPhys));
this->collisionEntityMap.insert(
std::make_pair(collisionPtrPhys, _entity));
return true;
});
// joints
_ecm.EachNew<components::Joint, components::Name, components::JointType,
components::Pose, components::ThreadPitch,
components::ParentEntity, components::ParentLinkName,
components::ChildLinkName>(
[&](const Entity &_entity,
const components::Joint * /* _joint */,
const components::Name *_name,
const components::JointType *_jointType,
const components::Pose *_pose,
const components::ThreadPitch *_threadPitch,
const components::ParentEntity *_parentModel,
const components::ParentLinkName *_parentLinkName,
const components::ChildLinkName *_childLinkName) -> bool
{
// Check if joint already exists
if (this->entityJointMap.find(_entity) != this->entityJointMap.end())
{
ignwarn << "Joint entity [" << _entity
<< "] marked as new, but it's already on the map."
<< std::endl;
return true;
}
// Check if parent model exists
if (this->entityModelMap.find(_parentModel->Data())
== this->entityModelMap.end())
{
ignwarn << "Joint's parent entity [" << _parentModel->Data()
<< "] not found on model map." << std::endl;
return true;
}
auto modelPtrPhys = this->entityModelMap.at(_parentModel->Data());
auto modelJointFeature = entityCast(_parentModel->Data(), modelPtrPhys,
this->entityModelJointMap);
if (!modelJointFeature)
{
static bool informed{false};
if (!informed)
{
igndbg << "Attempting to process joints, but the physics "
<< "engine doesn't support joint features. "
<< "Joints will be ignored." << std::endl;
informed = true;
}
// Break Each call since no joints can be processed
return false;
}
sdf::Joint joint;
joint.SetName(_name->Data());
joint.SetType(_jointType->Data());
joint.SetRawPose(_pose->Data());
joint.SetThreadPitch(_threadPitch->Data());
joint.SetParentLinkName(_parentLinkName->Data());
joint.SetChildLinkName(_childLinkName->Data());
auto jointAxis = _ecm.Component<components::JointAxis>(_entity);
auto jointAxis2 = _ecm.Component<components::JointAxis2>(_entity);
// Since we're making copies of the joint axes that were created using
// `Model::Load`, frame semantics should work for resolving their xyz
// axis
if (jointAxis)
joint.SetAxis(0, jointAxis->Data());
if (jointAxis2)
joint.SetAxis(1, jointAxis2->Data());
// Use the parent link's parent model as the model of this joint
auto jointPtrPhys = modelJointFeature->ConstructJoint(joint);
if (jointPtrPhys.Valid())
{
// Some joints may not be supported, so only add them to the map if
// the physics entity is valid
this->entityJointMap.insert(std::make_pair(_entity, jointPtrPhys));
}
return true;
});
_ecm.EachNew<components::BatterySoC>(
[&](const Entity & _entity, const components::BatterySoC *)->bool
{
// Parent entity of battery is model entity
this->entityOffMap.insert(std::make_pair(
_ecm.ParentEntity(_entity), false));
return true;
});
// Detachable joints
_ecm.EachNew<components::DetachableJoint>(
[&](const Entity &_entity,
const components::DetachableJoint *_jointInfo) -> bool
{
if (_jointInfo->Data().jointType != "fixed")
{
ignerr << "Detachable joint type [" << _jointInfo->Data().jointType
<< "] is currently not supported" << std::endl;
return true;
}
// Check if joint already exists
if (this->entityJointMap.find(_entity) != this->entityJointMap.end())
{
ignwarn << "Joint entity [" << _entity
<< "] marked as new, but it's already on the map."
<< std::endl;
return true;
}
// Check if the link entities exist in the physics engine
auto parentLinkPhysIt =
this->entityLinkMap.find(_jointInfo->Data().parentLink);
if (parentLinkPhysIt == this->entityLinkMap.end())
{
ignwarn << "DetachableJoint's parent link entity ["
<< _jointInfo->Data().parentLink << "] not found in link map."
<< std::endl;
return true;
}
auto childLinkEntity = _jointInfo->Data().childLink;
// Get child link
auto childLinkIt = this->entityLinkMap.find(childLinkEntity);
if (childLinkIt == this->entityLinkMap.end())
{
ignwarn << "Failed to find joint's child link [" << childLinkEntity
<< "]." << std::endl;
return true;
}
auto childLinkDetachableJointFeature = entityCast(childLinkEntity,
childLinkIt->second, this->entityLinkDetachableJointMap);
if (!childLinkDetachableJointFeature)
{
static bool informed{false};
if (!informed)
{
igndbg << "Attempting to create a detachable joint, but the physics"
<< " engine doesn't support feature "
<< "[AttachFixedJointFeature]. Detachable joints will be "