From 2a57f5e8192b59a39ad70dbe7c05077ae2f5d6f6 Mon Sep 17 00:00:00 2001 From: Diego Ferigo Date: Wed, 30 Jun 2021 13:40:36 +0200 Subject: [PATCH] Revert upstream PR 690 It causes a performance regression when contacts are involved --- scenario/src/plugins/Physics/Physics.cc | 12 +++--------- 1 file changed, 3 insertions(+), 9 deletions(-) diff --git a/scenario/src/plugins/Physics/Physics.cc b/scenario/src/plugins/Physics/Physics.cc index aad84fe3f..e800d2cd1 100644 --- a/scenario/src/plugins/Physics/Physics.cc +++ b/scenario/src/plugins/Physics/Physics.cc @@ -454,20 +454,16 @@ class ignition::gazebo::systems::PhysicsPrivate /// \brief Feature list to handle collisions. public: struct CollisionFeatureList : ignition::physics::FeatureList< MinimumFeatureList, + ignition::physics::GetContactsFromLastStepFeature, ignition::physics::sdf::ConstructSdfCollision>{}; - /// \brief Feature list to handle contacts information. - public: struct ContactFeatureList : ignition::physics::FeatureList< - CollisionFeatureList, - ignition::physics::GetContactsFromLastStepFeature>{}; - /// \brief Collision type with collision features. public: using ShapePtrType = ignition::physics::ShapePtr< ignition::physics::FeaturePolicy3d, CollisionFeatureList>; /// \brief World type with just the minimum features. Non-pointer. public: using WorldShapeType = ignition::physics::World< - ignition::physics::FeaturePolicy3d, ContactFeatureList>; + ignition::physics::FeaturePolicy3d, CollisionFeatureList>; ////////////////////////////////////////////////// // Collision filtering with bitmasks @@ -551,7 +547,6 @@ class ignition::gazebo::systems::PhysicsPrivate physics::World, MinimumFeatureList, CollisionFeatureList, - ContactFeatureList, NestedModelFeatureList, CollisionDetectorFeatureList, SolverFeatureList>; @@ -603,7 +598,6 @@ class ignition::gazebo::systems::PhysicsPrivate public: using EntityCollisionMap = EntityFeatureMap3d< physics::Shape, CollisionFeatureList, - ContactFeatureList, CollisionMaskFeatureList, FrictionPyramidSlipComplianceFeatureList >; @@ -3130,7 +3124,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) } auto worldCollisionFeature = - this->entityWorldMap.EntityCast(worldEntity); + this->entityWorldMap.EntityCast(worldEntity); if (!worldCollisionFeature) { static bool informed{false};