diff --git a/scenario/src/plugins/Physics/Physics.cc b/scenario/src/plugins/Physics/Physics.cc index b260add6e..011b44fb4 100644 --- a/scenario/src/plugins/Physics/Physics.cc +++ b/scenario/src/plugins/Physics/Physics.cc @@ -424,20 +424,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 @@ -521,7 +517,6 @@ class ignition::gazebo::systems::PhysicsPrivate physics::World, MinimumFeatureList, CollisionFeatureList, - ContactFeatureList, NestedModelFeatureList, CollisionDetectorFeatureList, SolverFeatureList>; @@ -572,7 +567,6 @@ class ignition::gazebo::systems::PhysicsPrivate public: using EntityCollisionMap = EntityFeatureMap3d< physics::Shape, CollisionFeatureList, - ContactFeatureList, CollisionMaskFeatureList, FrictionPyramidSlipComplianceFeatureList >; @@ -2800,7 +2794,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) } auto worldCollisionFeature = - this->entityWorldMap.EntityCast(worldEntity); + this->entityWorldMap.EntityCast(worldEntity); if (!worldCollisionFeature) { static bool informed{false};