Skip to content

Commit

Permalink
MaxContacts -> CollisionPairMaxTotalContacts
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <ichen@openrobotics.org>
  • Loading branch information
iche033 committed Jan 8, 2024
1 parent 5490d9b commit ccc4c15
Showing 1 changed file with 12 additions and 9 deletions.
21 changes: 12 additions & 9 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -618,10 +618,12 @@ class gz::sim::systems::PhysicsPrivate
gz::physics::Solver>{};

//////////////////////////////////////////////////
// MaxContacts
/// \brief Feature list for setting and getting the solver
public: struct MaxContactsFeatureList : gz::physics::FeatureList<
gz::physics::MaxContacts>{};
// CollisionPairMaxTotalContacts
/// \brief Feature list for setting and getting the max total contacts for
/// collision pairs
public: struct CollisionPairMaxTotalContactsFeatureList :
gz::physics::FeatureList<
gz::physics::CollisionPairMaxTotalContacts>{};

//////////////////////////////////////////////////
// Nested Models
Expand Down Expand Up @@ -649,7 +651,7 @@ class gz::sim::systems::PhysicsPrivate
CollisionDetectorFeatureList,
SolverFeatureList,
WorldModelFeatureList,
MaxContactsFeatureList
CollisionPairMaxTotalContactsFeatureList
>;

/// \brief A map between world entity ids in the ECM to World Entities in
Expand Down Expand Up @@ -1057,23 +1059,24 @@ void PhysicsPrivate::CreateWorldEntities(const EntityComponentManager &_ecm,
if (physicsComp)
{
auto maxContactsFeature =
this->entityWorldMap.EntityCast<MaxContactsFeatureList>(
_entity);
this->entityWorldMap.EntityCast<
CollisionPairMaxTotalContactsFeatureList>(_entity);
if (!maxContactsFeature)
{
static bool informed{false};
if (!informed)
{
gzdbg << "Attempting to set physics options, but the "
<< "phyiscs engine doesn't support feature "
<< "[MaxContacts]. Options will be ignored."
<< "[CollisionPairMaxTotalContacts]. "
<< "Options will be ignored."
<< std::endl;
informed = true;
}
}
else
{
maxContactsFeature->SetMaxContacts(
maxContactsFeature->SetCollisionPairMaxTotalContacts(
physicsComp->Data().MaxContacts());
}
}
Expand Down

0 comments on commit ccc4c15

Please sign in to comment.