Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Set max contacts for collision pairs #2270

Merged
merged 4 commits into from
Jun 26, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 37 additions & 1 deletion src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -617,6 +617,14 @@ class gz::sim::systems::PhysicsPrivate
public: struct SolverFeatureList : gz::physics::FeatureList<
gz::physics::Solver>{};

//////////////////////////////////////////////////
// CollisionPairMaxContacts
/// \brief Feature list for setting and getting the max total contacts for
/// collision pairs
public: struct CollisionPairMaxContactsFeatureList :
gz::physics::FeatureList<
gz::physics::CollisionPairMaxContacts>{};

//////////////////////////////////////////////////
// Nested Models

Expand All @@ -642,7 +650,8 @@ class gz::sim::systems::PhysicsPrivate
NestedModelFeatureList,
CollisionDetectorFeatureList,
SolverFeatureList,
WorldModelFeatureList
WorldModelFeatureList,
CollisionPairMaxContactsFeatureList
>;

/// \brief A map between world entity ids in the ECM to World Entities in
Expand Down Expand Up @@ -1045,6 +1054,33 @@ void PhysicsPrivate::CreateWorldEntities(const EntityComponentManager &_ecm,
}
}

auto physicsComp =
_ecm.Component<components::Physics>(_entity);
if (physicsComp)
{
auto maxContactsFeature =
this->entityWorldMap.EntityCast<
CollisionPairMaxContactsFeatureList>(_entity);
if (!maxContactsFeature)
{
static bool informed{false};
if (!informed)
{
gzdbg << "Attempting to set physics options, but the "
<< "phyiscs engine doesn't support feature "
<< "[CollisionPairMaxContacts]. "
<< "Options will be ignored."
<< std::endl;
informed = true;
}
}
else
{
maxContactsFeature->SetCollisionPairMaxContacts(
physicsComp->Data().MaxContacts());
}
}

// World Model proxy (used for joints directly under <world> in SDF)
auto worldModelFeature =
this->entityWorldMap.EntityCast<WorldModelFeatureList>(_entity);
Expand Down
Loading