-
Notifications
You must be signed in to change notification settings - Fork 276
/
Physics.cc
3924 lines (3450 loc) · 140 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 "Physics.hh"
#include <gz/msgs/contact.pb.h>
#include <gz/msgs/contacts.pb.h>
#include <gz/msgs/entity.pb.h>
#include <gz/msgs/Utility.hh>
#include <algorithm>
#include <iostream>
#include <deque>
#include <map>
#include <set>
#include <string>
#include <unordered_map>
#include <unordered_set>
#include <vector>
#include <gz/common/geospatial/Dem.hh>
#include <gz/common/geospatial/HeightmapData.hh>
#include <gz/common/geospatial/ImageHeightmap.hh>
#include <gz/common/MeshManager.hh>
#include <gz/common/Profiler.hh>
#include <gz/common/StringUtils.hh>
#include <gz/common/SystemPaths.hh>
#include <gz/common/Uuid.hh>
#include <gz/math/AxisAlignedBox.hh>
#include <gz/math/eigen3/Conversions.hh>
#include <gz/math/Vector3.hh>
#include <gz/physics/config.hh>
#include <gz/physics/FeatureList.hh>
#include <gz/physics/FeaturePolicy.hh>
#include <gz/physics/heightmap/HeightmapShape.hh>
#include <gz/physics/RelativeQuantity.hh>
#include <gz/physics/RequestEngine.hh>
#include <gz/physics/BoxShape.hh>
#include <gz/physics/ContactProperties.hh>
#include <gz/physics/CylinderShape.hh>
#include <gz/physics/ForwardStep.hh>
#include <gz/physics/FrameSemantics.hh>
#include <gz/physics/FreeGroup.hh>
#include <gz/physics/FixedJoint.hh>
#include <gz/physics/GetContacts.hh>
#include <gz/physics/GetBoundingBox.hh>
#include <gz/physics/GetEntities.hh>
#include <gz/physics/Joint.hh>
#include <gz/physics/Link.hh>
#include <gz/physics/RemoveEntities.hh>
#include <gz/physics/Shape.hh>
#include <gz/physics/SphereShape.hh>
#include <gz/physics/World.hh>
#include <gz/physics/mesh/MeshShape.hh>
#include <gz/physics/sdf/ConstructCollision.hh>
#include <gz/physics/sdf/ConstructJoint.hh>
#include <gz/physics/sdf/ConstructLink.hh>
#include <gz/physics/sdf/ConstructModel.hh>
#include <gz/physics/sdf/ConstructNestedModel.hh>
#include <gz/physics/sdf/ConstructWorld.hh>
#include <gz/plugin/Loader.hh>
#include <gz/plugin/PluginPtr.hh>
#include <gz/plugin/Register.hh>
// SDF
#include <sdf/Collision.hh>
#include <sdf/Heightmap.hh>
#include <sdf/Joint.hh>
#include <sdf/Link.hh>
#include <sdf/Mesh.hh>
#include <sdf/Model.hh>
#include <sdf/Polyline.hh>
#include <sdf/Surface.hh>
#include <sdf/World.hh>
#include "gz/sim/EntityComponentManager.hh"
#include "gz/sim/Model.hh"
#include "gz/sim/Util.hh"
// Components
#include "gz/sim/components/AngularAcceleration.hh"
#include "gz/sim/components/AngularVelocity.hh"
#include "gz/sim/components/AngularVelocityCmd.hh"
#include "gz/sim/components/AxisAlignedBox.hh"
#include "gz/sim/components/BatterySoC.hh"
#include "gz/sim/components/CanonicalLink.hh"
#include "gz/sim/components/ChildLinkName.hh"
#include "gz/sim/components/Collision.hh"
#include "gz/sim/components/ContactSensorData.hh"
#include "gz/sim/components/Geometry.hh"
#include "gz/sim/components/Gravity.hh"
#include "gz/sim/components/Inertial.hh"
#include "gz/sim/components/DetachableJoint.hh"
#include "gz/sim/components/Joint.hh"
#include "gz/sim/components/JointAxis.hh"
#include "gz/sim/components/JointEffortLimitsCmd.hh"
#include "gz/sim/components/JointPosition.hh"
#include "gz/sim/components/JointPositionLimitsCmd.hh"
#include "gz/sim/components/JointPositionReset.hh"
#include "gz/sim/components/JointType.hh"
#include "gz/sim/components/JointVelocity.hh"
#include "gz/sim/components/JointVelocityCmd.hh"
#include "gz/sim/components/JointVelocityLimitsCmd.hh"
#include "gz/sim/components/JointVelocityReset.hh"
#include "gz/sim/components/LinearAcceleration.hh"
#include "gz/sim/components/LinearVelocity.hh"
#include "gz/sim/components/LinearVelocityCmd.hh"
#include "gz/sim/components/Link.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/ExternalWorldWrenchCmd.hh"
#include "gz/sim/components/JointTransmittedWrench.hh"
#include "gz/sim/components/JointForceCmd.hh"
#include "gz/sim/components/Physics.hh"
#include "gz/sim/components/PhysicsEnginePlugin.hh"
#include "gz/sim/components/Pose.hh"
#include "gz/sim/components/PoseCmd.hh"
#include "gz/sim/components/Recreate.hh"
#include "gz/sim/components/SelfCollide.hh"
#include "gz/sim/components/SlipComplianceCmd.hh"
#include "gz/sim/components/SphericalCoordinates.hh"
#include "gz/sim/components/Static.hh"
#include "gz/sim/components/ThreadPitch.hh"
#include "gz/sim/components/World.hh"
#include "gz/sim/components/HaltMotion.hh"
#include "CanonicalLinkModelTracker.hh"
// Events
#include "gz/sim/physics/Events.hh"
#include "EntityFeatureMap.hh"
using namespace gz;
using namespace gz::sim;
using namespace gz::sim::systems;
using namespace gz::sim::systems::physics_system;
namespace components = gz::sim::components;
// Private data class.
class gz::sim::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 : physics::FeatureList<
physics::FindFreeGroupFeature,
physics::SetFreeGroupWorldPose,
physics::FreeGroupFrameSemantics,
physics::LinkFrameSemantics,
physics::ForwardStep,
physics::RemoveModelFromWorld,
physics::sdf::ConstructSdfModel,
physics::sdf::ConstructSdfWorld,
physics::GetLinkFromModel,
physics::GetShapeFromLink
>{};
/// \brief Engine type with just the minimum features.
public: using EnginePtrType = physics::EnginePtr<
physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief World type with just the minimum features.
public: using WorldPtrType = physics::WorldPtr<
physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief Model type with just the minimum features.
public: using ModelPtrType = physics::ModelPtr<
physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief Link type with just the minimum features.
public: using LinkPtrType = physics::LinkPtr<
physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief Free group type with just the minimum features.
public: using FreeGroupPtrType = physics::FreeGroupPtr<
physics::FeaturePolicy3d, MinimumFeatureList>;
/// \brief Create physics entities
/// \param[in] _ecm Constant reference to ECM.
/// \param[in] _warnIfEntityExists True to emit warnings if the same entity
/// already exists in the physics system
public: void CreatePhysicsEntities(const EntityComponentManager &_ecm,
bool _warnIfEntityExists = true);
/// \brief Create world entities
/// \param[in] _ecm Constant reference to ECM.
/// \param[in] _warnIfEntityExists True to emit warnings if the same entity
/// already exists in the physics system
public: void CreateWorldEntities(const EntityComponentManager &_ecm,
bool _warnIfEntityExists = true);
/// \brief Create model entities
/// \param[in] _ecm Constant reference to ECM.
/// \param[in] _warnIfEntityExists True to emit warnings if the same entity
/// already exists in the physics system
public: void CreateModelEntities(const EntityComponentManager &_ecm,
bool _warnIfEntityExists = true);
/// \brief Create link entities
/// \param[in] _ecm Constant reference to ECM.
/// \param[in] _warnIfEntityExists True to emit warnings if the same entity
/// already exists in the physics system
public: void CreateLinkEntities(const EntityComponentManager &_ecm,
bool _warnIfEntityExists = true);
/// \brief Create collision entities
/// \param[in] _ecm Constant reference to ECM.
/// \param[in] _warnIfEntityExists True to emit warnings if the same entity
/// already exists in the physics system
public: void CreateCollisionEntities(const EntityComponentManager &_ecm,
bool _warnIfEntityExists = true);
/// \brief Create joint entities
/// \param[in] _ecm Constant reference to ECM.
/// \param[in] _warnIfEntityExists True to emit warnings if the same entity
/// already exists in the physics system
public: void CreateJointEntities(const EntityComponentManager &_ecm,
bool _warnIfEntityExists = true);
/// \brief Create Battery entities
/// \param[in] _ecm Constant reference to ECM.
public: void CreateBatteryEntities(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 Mutable reference to ECM.
public: void UpdatePhysics(EntityComponentManager &_ecm);
/// \brief Reset physics from components
/// \param[in] _ecm Constant reference to ECM.
public: void ResetPhysics(EntityComponentManager &_ecm);
/// \brief Step the simulation for each world
/// \param[in] _dt Duration
/// \returns Output data from the physics engine (this currently contains
/// data for links that experienced a pose change in the physics step)
public: gz::physics::ForwardStep::Output Step(
const std::chrono::steady_clock::duration &_dt);
/// \brief Get data of links that were updated in the latest physics step.
/// \param[in] _ecm Mutable reference to ECM.
/// \param[in] _updatedLinks Updated link poses from the latest physics step
/// that were written to by the physics engine (some physics engines may
/// not write this data to ForwardStep::Output. If not, _ecm is used to get
/// this updated link pose data).
/// \return A map of gazebo link entities to their updated pose data.
/// std::map is used because canonical links must be in topological order
/// to ensure that nested models with multiple canonical links are updated
/// properly (models must be updated in topological order).
public: std::map<Entity, physics::FrameData3d> ChangedLinks(
EntityComponentManager &_ecm,
const gz::physics::ForwardStep::Output &_updatedLinks);
/// \brief Helper function to update the pose of a model.
/// \param[in] _model The model to update.
/// \param[in] _canonicalLink The canonical link of _model.
/// \param[in] _ecm The entity component manager.
/// \param[in, out] _linkFrameData Links that experienced a pose change in the
/// most recent physics step. The key is the entity of the link, and the
/// value is the updated frame data corresponding to that entity. The
/// canonical links of _model's nested models are added to _linkFrameData to
/// ensure that all of _model's nested models are marked as models to be
/// updated (if a parent model's pose changes, all nested model poses must be
/// updated since nested model poses are saved w.r.t. the parent model).
public: void UpdateModelPose(const Entity _model,
const Entity _canonicalLink, EntityComponentManager &_ecm,
std::map<Entity, physics::FrameData3d> &_linkFrameData);
/// \brief Get an entity's frame data relative to world from physics.
/// \param[in] _entity The entity.
/// \param[in, out] _data The frame data to populate.
/// \return True if _data was populated with frame data for _entity, false
/// otherwise.
public: bool GetFrameDataRelativeToWorld(const Entity _entity,
physics::FrameData3d &_data);
/// \brief Update components from physics simulation
/// \param[in] _ecm Mutable reference to ECM.
/// \param[in, out] _linkFrameData Links that experienced a pose change in the
/// most recent physics step. The key is the entity of the link, and the
/// value is the updated frame data corresponding to that entity.
public: void UpdateSim(EntityComponentManager &_ecm,
std::map<Entity, physics::FrameData3d> &_linkFrameData);
/// \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 gz-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 Get transform from one ancestor entity to a descendant entity
/// that are in the same model.
/// \param[in] _from An ancestor of the _to entity.
/// \param[in] _to A descendant of the _from entity.
/// \return Pose transform between the two entities
public: math::Pose3d RelativePose(const Entity &_from,
const Entity &_to, const EntityComponentManager &_ecm) const;
/// \brief Enable contact surface customization for the given world.
/// \param[in] _world The world to enable it for.
public: void EnableContactSurfaceCustomization(const Entity &_world);
/// \brief Disable contact surface customization for the given world.
/// \param[in] _world The world to disable it for.
public: void DisableContactSurfaceCustomization(const Entity &_world);
/// \brief Cache the top-level model for each entity.
/// The key is an entity and the value is its top level model.
public: std::unordered_map<Entity, Entity> topLevelModelMap;
/// \brief Keep track of what entities are static (models and links).
public: std::unordered_set<Entity> staticEntities;
/// \brief Keep track of poses for links attached to non-static models.
/// This allows for skipping pose updates if a link's pose didn't change
/// after a physics step.
public: std::unordered_map<Entity, gz::math::Pose3d> linkWorldPoses;
/// \brief Keep a mapping of canonical links to models that have this
/// canonical link. Useful for updating model poses efficiently after a
/// physics step
public: CanonicalLinkModelTracker canonicalLinkModelTracker;
/// \brief Keep track of non-static model world poses. Since non-static
/// models may not move on a given iteration, we want to keep track of the
/// most recent model world pose change that took place.
public: std::unordered_map<Entity, math::Pose3d> modelWorldPoses;
/// \brief A map between model entity ids in the ECM to whether its battery
/// has drained.
public: std::unordered_map<Entity, bool> entityOffMap;
/// \brief Entities whose pose commands have been processed and should be
/// deleted the following iteration.
public: std::unordered_set<Entity> worldPoseCmdsToRemove;
/// \brief IDs of the ContactSurfaceHandler callbacks registered for worlds
public: std::unordered_map<Entity, std::string> worldContactCallbackIDs;
/// \brief used to store whether physics objects have been created.
public: bool initialized = false;
/// \brief Pointer to the underlying gz-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) &&
_a.Rot().Equal(_b.Rot(), 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 msgs::Contacts equality comparison function.
public: std::function<bool(const msgs::Contacts &,
const msgs::Contacts &)>
contactsEql { [](const msgs::Contacts &_a,
const msgs::Contacts &_b)
{
if (_a.contact_size() != _b.contact_size())
{
return false;
}
for (int i = 0; i < _a.contact_size(); ++i)
{
if (_a.contact(i).position_size() !=
_b.contact(i).position_size())
{
return false;
}
for (int j = 0; j < _a.contact(i).position_size();
++j)
{
auto pos1 = _a.contact(i).position(j);
auto pos2 = _b.contact(i).position(j);
if (!math::equal(pos1.x(), pos2.x(), 1e-6) ||
!math::equal(pos1.y(), pos2.y(), 1e-6) ||
!math::equal(pos1.z(), pos2.z(), 1e-6))
{
return false;
}
}
}
return true;
}};
/// \brief msgs::Contacts equality comparison function.
public: std::function<bool(const msgs::Wrench &, const msgs::Wrench &)>
wrenchEql{
[](const msgs::Wrench &_a, const msgs::Wrench &_b)
{
return math::equal(_a.torque().x(), _b.torque().x(), 1e-6) &&
math::equal(_a.torque().y(), _b.torque().y(), 1e-6) &&
math::equal(_a.torque().z(), _b.torque().z(), 1e-6) &&
math::equal(_a.force().x(), _b.force().x(), 1e-6) &&
math::equal(_a.force().y(), _b.force().y(), 1e-6) &&
math::equal(_a.force().z(), _b.force().z(), 1e-6);
}};
/// \brief Environment variable which holds paths to look for engine plugins
public: std::string pluginPathEnv = "GZ_SIM_PHYSICS_ENGINE_PATH";
public: std::string pluginPathEnvDeprecated = \
"IGN_GAZEBO_PHYSICS_ENGINE_PATH";
//////////////////////////////////////////////////
////////////// Optional Features /////////////////
//////////////////////////////////////////////////
//////////////////////////////////////////////////
// Slip Compliance
/// \brief Feature list to process `FrictionPyramidSlipCompliance` components.
public: struct FrictionPyramidSlipComplianceFeatureList
: physics::FeatureList<
MinimumFeatureList,
physics::GetShapeFrictionPyramidSlipCompliance,
physics::SetShapeFrictionPyramidSlipCompliance>{};
//////////////////////////////////////////////////
// Joints
/// \brief Feature list to handle joints.
public: struct JointFeatureList : physics::FeatureList<
MinimumFeatureList,
physics::GetJointFromModel,
physics::GetBasicJointProperties,
physics::GetBasicJointState,
physics::SetBasicJointState>{};
/// \brief Feature list to construct joints
public: struct ConstructSdfJointFeatureList : gz::physics::FeatureList<
JointFeatureList,
gz::physics::sdf::ConstructSdfJoint>{};
//////////////////////////////////////////////////
// Detachable joints
/// \brief Feature list to process `DetachableJoint` components.
public: struct DetachableJointFeatureList : physics::FeatureList<
JointFeatureList,
physics::AttachFixedJointFeature,
physics::DetachJointFeature,
physics::SetJointTransformFromParentFeature>{};
//////////////////////////////////////////////////
// Joint transmitted wrench
/// \brief Feature list for getting joint transmitted wrenches.
public: struct JointGetTransmittedWrenchFeatureList : physics::FeatureList<
physics::GetJointTransmittedWrench>{};
//////////////////////////////////////////////////
// Collisions
/// \brief Feature list to handle collisions.
public: struct CollisionFeatureList : physics::FeatureList<
MinimumFeatureList,
physics::sdf::ConstructSdfCollision>{};
/// \brief Feature list to handle contacts information.
public: struct ContactFeatureList : physics::FeatureList<
CollisionFeatureList,
physics::GetContactsFromLastStepFeature>{};
/// \brief Feature list to change contacts before they are applied to physics.
public: struct SetContactPropertiesCallbackFeatureList :
physics::FeatureList<
ContactFeatureList,
physics::SetContactPropertiesCallbackFeature>{};
/// \brief Collision type with collision features.
public: using ShapePtrType = physics::ShapePtr<
physics::FeaturePolicy3d, CollisionFeatureList>;
/// \brief World type with just the minimum features. Non-pointer.
public: using WorldShapeType = physics::World<
physics::FeaturePolicy3d, ContactFeatureList>;
//////////////////////////////////////////////////
// Collision filtering with bitmasks
/// \brief Feature list to filter collisions with bitmasks.
public: struct CollisionMaskFeatureList : physics::FeatureList<
CollisionFeatureList,
physics::CollisionFilterMaskFeature>{};
//////////////////////////////////////////////////
// Link force
/// \brief Feature list for applying forces to links.
public: struct LinkForceFeatureList : physics::FeatureList<
physics::AddLinkExternalForceTorque>{};
//////////////////////////////////////////////////
// Bounding box
/// \brief Feature list for model bounding box.
public: struct BoundingBoxFeatureList : physics::FeatureList<
MinimumFeatureList,
physics::GetModelBoundingBox>{};
//////////////////////////////////////////////////
// Joint velocity command
/// \brief Feature list for set joint velocity command.
public: struct JointVelocityCommandFeatureList : physics::FeatureList<
physics::SetJointVelocityCommandFeature>{};
//////////////////////////////////////////////////
// Joint position limits command
/// \brief Feature list for setting joint position limits.
public: struct JointPositionLimitsCommandFeatureList : physics::FeatureList<
physics::SetJointPositionLimitsFeature>{};
//////////////////////////////////////////////////
// Joint velocity limits command
/// \brief Feature list for setting joint velocity limits.
public: struct JointVelocityLimitsCommandFeatureList : physics::FeatureList<
physics::SetJointVelocityLimitsFeature>{};
//////////////////////////////////////////////////
// Joint effort limits command
/// \brief Feature list for setting joint effort limits.
public: struct JointEffortLimitsCommandFeatureList : physics::FeatureList<
physics::SetJointEffortLimitsFeature>{};
//////////////////////////////////////////////////
// World velocity command
public: struct WorldVelocityCommandFeatureList :
physics::FeatureList<
physics::SetFreeGroupWorldVelocity>{};
//////////////////////////////////////////////////
// Meshes
/// \brief Feature list for meshes.
/// Include MinimumFeatureList so created collision can be automatically
/// up-cast.
public: struct MeshFeatureList : physics::FeatureList<
CollisionFeatureList,
physics::mesh::AttachMeshShapeFeature>{};
//////////////////////////////////////////////////
// Construct Links
/// \brief Feature list for constructing links
public: struct ConstructSdfLinkFeatureList : gz::physics::FeatureList<
MinimumFeatureList,
gz::physics::sdf::ConstructSdfLink>{};
//////////////////////////////////////////////////
// Heightmap
/// \brief Feature list for heightmaps.
/// Include MinimumFeatureList so created collision can be automatically
/// up-cast.
public: struct HeightmapFeatureList : gz::physics::FeatureList<
CollisionFeatureList,
physics::heightmap::AttachHeightmapShapeFeature>{};
//////////////////////////////////////////////////
// Collision detector
/// \brief Feature list for setting and getting the collision detector
public: struct CollisionDetectorFeatureList : gz::physics::FeatureList<
gz::physics::CollisionDetector>{};
//////////////////////////////////////////////////
// Solver
/// \brief Feature list for setting and getting the solver
public: struct SolverFeatureList : gz::physics::FeatureList<
gz::physics::Solver>{};
//////////////////////////////////////////////////
// Nested Models
/// \brief Feature list to construct nested models
public: struct NestedModelFeatureList : physics::FeatureList<
MinimumFeatureList,
physics::sdf::ConstructSdfNestedModel>{};
//////////////////////////////////////////////////
/// \brief World EntityFeatureMap
public: using WorldEntityMap = EntityFeatureMap3d<
physics::World,
MinimumFeatureList,
CollisionFeatureList,
ContactFeatureList,
SetContactPropertiesCallbackFeatureList,
NestedModelFeatureList,
CollisionDetectorFeatureList,
SolverFeatureList>;
/// \brief A map between world entity ids in the ECM to World Entities in
/// gz-physics.
public: WorldEntityMap entityWorldMap;
/// \brief Model EntityFeatureMap
public: using ModelEntityMap = EntityFeatureMap3d<
physics::Model,
MinimumFeatureList,
JointFeatureList,
BoundingBoxFeatureList,
NestedModelFeatureList,
ConstructSdfLinkFeatureList,
ConstructSdfJointFeatureList>;
/// \brief A map between model entity ids in the ECM to Model Entities in
/// gz-physics.
public: ModelEntityMap entityModelMap;
/// \brief Link EntityFeatureMap
public: using EntityLinkMap = EntityFeatureMap3d<
physics::Link,
MinimumFeatureList,
DetachableJointFeatureList,
CollisionFeatureList,
HeightmapFeatureList,
LinkForceFeatureList,
MeshFeatureList>;
/// \brief A map between link entity ids in the ECM to Link Entities in
/// gz-physics.
public: EntityLinkMap entityLinkMap;
/// \brief Joint EntityFeatureMap
public: using EntityJointMap = EntityFeatureMap3d<
physics::Joint,
JointFeatureList,
DetachableJointFeatureList,
JointVelocityCommandFeatureList,
JointGetTransmittedWrenchFeatureList,
JointPositionLimitsCommandFeatureList,
JointVelocityLimitsCommandFeatureList,
JointEffortLimitsCommandFeatureList
>;
/// \brief A map between joint entity ids in the ECM to Joint Entities in
/// gz-physics
public: EntityJointMap entityJointMap;
/// \brief Collision EntityFeatureMap
public: using EntityCollisionMap = EntityFeatureMap3d<
physics::Shape,
CollisionFeatureList,
ContactFeatureList,
CollisionMaskFeatureList,
FrictionPyramidSlipComplianceFeatureList
>;
/// \brief A map between collision entity ids in the ECM to Shape Entities in
/// gz-physics.
public: EntityCollisionMap entityCollisionMap;
/// \brief FreeGroup EntityFeatureMap
public: using EntityFreeGroupMap = EntityFeatureMap3d<
physics::FreeGroup,
MinimumFeatureList,
WorldVelocityCommandFeatureList
>;
/// \brief A map between collision entity ids in the ECM to FreeGroup Entities
/// in gz-physics.
public: EntityFreeGroupMap entityFreeGroupMap;
/// \brief Event manager from simulation runner.
public: EventManager *eventManager = nullptr;
/// \brief Keep track of what entities use customized contact surfaces.
/// Map keys are expected to be world entities so that we keep a set of
/// entities with customizations per world.
public: std::unordered_map<Entity, std::unordered_set<Entity>>
customContactSurfaceEntities;
/// \brief Set of links that were added to an existing model. This set
/// is used to track links that were added to an existing model, such as
/// through the GUI model editor, so that we can avoid premature creation
/// of links and collision elements. This also lets us suppress some
/// invalid error messages.
public: std::set<Entity> linkAddedToModel;
/// \brief Set of joints that were added to an existing model. This set
/// is used to track joints that were added to an existing model, such as
/// through the GUI model editor, so that we can avoid premature creation
/// of joints. This also lets us suppress some invalid error messages.
public: std::set<Entity> jointAddedToModel;
/// \brief Flag to store whether the names of colliding entities should
/// be populated in the contact points.
public: bool contactsEntityNames = true;
};
//////////////////////////////////////////////////
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 = "gz-physics-dartsim-plugin";
}
// Deprecated: accept ignition-prefixed engines
std::string deprecatedPrefix{"ignition"};
auto pos = pluginLib.find(deprecatedPrefix);
if (pos != std::string::npos)
{
auto msg = "Trying to load deprecated plugin [" + pluginLib + "]. Use [";
pluginLib.replace(pos, deprecatedPrefix.size(), "gz");
gzwarn << msg << pluginLib << "] instead." << std::endl;
}
// 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;});
}
// Check if entity names should be populated in contact points.
auto contactsElement = _sdf->FindElement("contacts");
if (contactsElement)
{
this->dataPtr->contactsEntityNames = contactsElement->Get<bool>(
"include_entity_names", true).first;
}
// Find engine shared library
// Look in:
// * Paths from environment variable
// * Engines installed with gz-physics
common::SystemPaths systemPaths;
systemPaths.SetPluginPathEnv(this->dataPtr->pluginPathEnv);
systemPaths.AddPluginPaths({GZ_PHYSICS_ENGINE_INSTALL_DIR});
auto pathToLib = systemPaths.FindSharedLibrary(pluginLib);
if (pathToLib.empty())
{
// Try deprecated environment variable
// TODO(CH3): Deprecated. Remove on tock.
common::SystemPaths systemPathsDep;
systemPathsDep.SetPluginPathEnv(this->dataPtr->pluginPathEnvDeprecated);
pathToLib = systemPathsDep.FindSharedLibrary(pluginLib);
if (pathToLib.empty())
{
gzerr << "Failed to find plugin [" << pluginLib
<< "]. Have you checked the " << this->dataPtr->pluginPathEnv
<< " environment variable?" << std::endl;
return;
}
else
{
gzwarn << "Found plugin [" << pluginLib
<< "] using deprecated environment variable ["
<< this->dataPtr->pluginPathEnvDeprecated << "]. Please use ["
<< this->dataPtr->pluginPathEnv << "] instead." << std::endl;
}
}
// Load engine plugin
plugin::Loader pluginLoader;
auto plugins = pluginLoader.LoadLib(pathToLib);
if (plugins.empty())
{
gzerr << "Unable to load the [" << pathToLib << "] library.\n";
return;
}
auto classNames = pluginLoader.PluginsImplementing<
physics::ForwardStep::Implementation<
physics::FeaturePolicy3d>>();
if (classNames.empty())
{
gzerr << "No physics 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)
{
gzwarn << "Failed to instantiate [" << className << "] from ["
<< pathToLib << "]" << std::endl;
continue;
}
this->dataPtr->engine = physics::RequestEngine<
physics::FeaturePolicy3d,
PhysicsPrivate::MinimumFeatureList>::From(plugin);
if (nullptr != this->dataPtr->engine)
{
gzdbg << "Loaded [" << className << "] from library ["
<< pathToLib << "]" << std::endl;
break;
}
auto missingFeatures = physics::RequestEngine<
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;
}
gzwarn << msg.str();
}
if (nullptr == this->dataPtr->engine)
{
gzerr << "Failed to load a valid physics engine from [" << pathToLib
<< "]."
<< std::endl;
return;
}
this->dataPtr->eventManager = &_eventMgr;
}
//////////////////////////////////////////////////
Physics::~Physics() = default;
//////////////////////////////////////////////////
void Physics::Update(const UpdateInfo &_info, EntityComponentManager &_ecm)
{
GZ_PROFILE("Physics::Update");
if (this->dataPtr->engine)
{
this->dataPtr->CreatePhysicsEntities(_ecm);
this->dataPtr->UpdatePhysics(_ecm);
gz::physics::ForwardStep::Output stepOutput;
// Only step if not paused.
if (!_info.paused)
{
stepOutput = this->dataPtr->Step(_info.dt);
}
auto changedLinks = this->dataPtr->ChangedLinks(_ecm, stepOutput);
this->dataPtr->UpdateSim(_ecm, changedLinks);
// 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 Physics::Reset(const UpdateInfo &, EntityComponentManager &_ecm)
{
GZ_PROFILE("Physics::Reset");
if (this->dataPtr->engine)
{
gzdbg << "Resetting Physics\n";
this->dataPtr->ResetPhysics(_ecm);
}
}
//////////////////////////////////////////////////
void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm,
bool _warnIfEntityExists)
{
// Clear the set of links that were added to a model.
this->linkAddedToModel.clear();
this->jointAddedToModel.clear();
this->CreateWorldEntities(_ecm, _warnIfEntityExists);
this->CreateModelEntities(_ecm, _warnIfEntityExists);
this->CreateLinkEntities(_ecm, _warnIfEntityExists);
// We don't need to add visuals to the physics engine.
this->CreateCollisionEntities(_ecm, _warnIfEntityExists);
this->CreateJointEntities(_ecm, _warnIfEntityExists);
this->CreateBatteryEntities(_ecm);
}
//////////////////////////////////////////////////
void PhysicsPrivate::CreateWorldEntities(const EntityComponentManager &_ecm,
bool _warnIfEntityExists)
{
// 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.HasEntity(_entity))
{
if (_warnIfEntityExists)
{
gzwarn << "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.AddEntity(_entity, worldPtrPhys);
// Optional world features
auto collisionDetectorComp =
_ecm.Component<components::PhysicsCollisionDetector>(_entity);
if (collisionDetectorComp)
{
auto collisionDetectorFeature =
this->entityWorldMap.EntityCast<CollisionDetectorFeatureList>(
_entity);
if (!collisionDetectorFeature)
{
static bool informed{false};
if (!informed)
{
gzdbg << "Attempting to set physics options, but the "
<< "phyiscs engine doesn't support feature "
<< "[CollisionDetectorFeature]. Options will be ignored."