Skip to content

Commit

Permalink
Revert upstream PR 690
Browse files Browse the repository at this point in the history
  • Loading branch information
diegoferigo committed Jul 27, 2021
1 parent 41ad594 commit 17fca92
Showing 1 changed file with 3 additions and 9 deletions.
12 changes: 3 additions & 9 deletions scenario/src/plugins/Physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -521,7 +517,6 @@ class ignition::gazebo::systems::PhysicsPrivate
physics::World,
MinimumFeatureList,
CollisionFeatureList,
ContactFeatureList,
NestedModelFeatureList,
CollisionDetectorFeatureList,
SolverFeatureList>;
Expand Down Expand Up @@ -572,7 +567,6 @@ class ignition::gazebo::systems::PhysicsPrivate
public: using EntityCollisionMap = EntityFeatureMap3d<
physics::Shape,
CollisionFeatureList,
ContactFeatureList,
CollisionMaskFeatureList,
FrictionPyramidSlipComplianceFeatureList
>;
Expand Down Expand Up @@ -2800,7 +2794,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm)
}

auto worldCollisionFeature =
this->entityWorldMap.EntityCast<ContactFeatureList>(worldEntity);
this->entityWorldMap.EntityCast<CollisionFeatureList>(worldEntity);
if (!worldCollisionFeature)
{
static bool informed{false};
Expand Down

0 comments on commit 17fca92

Please sign in to comment.