Conversation
- The broad phase now emits new collision pairs and stores all pairs in a HashSet - Contact status and kind is now tracked with `ContactPairFlags` instead of booleans - The narrow phase adds new collision pairs, updates existing pairs, and responds to state changes separately instead of overwriting and doing extra work for persistent contact - State changes are tracked with bit vectors (bit sets), which are fast to iterate serially - The narrow phase is responsible for collision events instead of the `ContactReportingPlugin`
- Renamed `BroadCollisionPairs` to `BroadPhasePairSet` - Added `BroadPhasePairSet` for fast pair lookup with new `PairKey` - Improve broad phase docs
…pt-in - Removed `BroadPhaseAddedPairs` - Renamed `BroadPhasePairSet` to `BroadPhasePairs` - Moved contact creation to broad phase to improve persistence - Removed some graph querying overhead from contact pair removal by using the `EdgeIndex` directly - Made collision events opt-in with `CollisionEventsEnabled` component - Improved a lot of docs
Also moved contact types to `contact_types` module and improved some docs.
Jondolf
added a commit
that referenced
this pull request
Mar 31, 2025
# Objective Especially after #683, we use the term "contact pair" a lot. However, the contact pair type is called `Contacts`. This name is very ambiguous: does it represent all contacts in the world, all contacts between two entities, contacts belonging to a specific contact surface, or something else? ## Solution Rename `Contacts` to `ContactPair`. It much more accurately describes what the type represents: contact data for a pair of entities that may be in contact. This is also the name used by Rapier. --- ## Migration Guide `Contacts` has been renamed to `ContactPair`.
Jondolf
added a commit
that referenced
this pull request
Apr 17, 2025
# Objective Currently, contact constraints are generated serially after the narrow phase. This requires iterating over all contact pairs and redoing various queries and computations, which can add meaningful overhead. (Note: The commit history also includes most commits from #683, sorry about that 😅) ## Solution Optimize contact constraint generation by generating constraints directly in the parallel contact update loop of the narrow phase. This way, we get "free" parallelism while getting rid of the extra iteration, and we don't need to query for the rigid bodies or colliders a second time. We can even reuse some values computed for the contact update, like `effective_speculative_margin`. Constraint generation is multi-threaded by storing constraints in thread-local `Vec`s and draining them serially into `ContactConstraints`. This preserves determinism. ## Performance For physics diagnostics, the "Generate Constraints" step has been removed, and the cost is now included in the "Narrow Phase" step. This means that the narrow phase is seemingly more expensive, but the total cost is reduced quite drastically. Improvements can be seen in both single-threaded and multi-threaded performance, with the latter having a larger difference. Note that the "Store Impulses" step is now slightly more expensive. This is because the contact pair lookup can no longer be performed with the edge index directly, as constraints are generated before contact pair removal, and pair removal can invalidate indices. ### Single-threaded Before:  After:  ### Multi-threaded Before:  After:  --- ## Migration Guide `NarrowPhaseSet::GenerateConstraints` has been removed. Contact constraints are now generated as part of `NarrowPhaseSet::Update`.
Jondolf
added a commit
that referenced
this pull request
Apr 18, 2025
# Objective Closes #361. Closes #481. A common user request is to allow listening to collision events for specific entities, with an API where you don't need to check e.g. which entity is the player and which entity is an enemy like you might need to do when using `CollisionStarted` and `CollisionEnded`. The typical Bevy API for per-entity events like this is observers. On the surface, this is a straightforward addition. However, there have historically been some challenges and open questions: 1. We don't want to trigger collision events for *every* contact. Doing so would mean that we get one buffered event and two observable events (one for each entity) per started/ended contact pair, which could add up to a decent amount of overhead. 2. Observable events shouldn't store two entities like `CollisionStarted` and `CollisionEnded` do. The `Trigger` already stores the observed entity. 3. Should we trigger the observers immediately in the narrow phase, which could be slightly more efficient, or should we defer events until after the solver so that contact impulses have been computed? Now that #683 made collision events opt-in via the `CollisionEventsEnabled` component, I consider (1) to be solved. We can only trigger the event for entities with that component. The other two are more just a matter of how we want to design this, but I would assert that (2) we should just have separate types for buffered and observable events, and (3) we should trigger the events after the solver, because having access to contact impulses is valuable, even if it has a small extra cost. ## Solution Add `OnCollisionStart` and `OnCollisionEnd` events that are triggered when an entity starts or stops colliding with another entity. The naming was chosen to be distinct enough from `CollisionStarted` and `CollisionEnded`, while reflecting Bevy's observer event names such as `OnAdd` or `Pointer<Move>` (present tense verb). The events are triggered after the solver by iterating through the buffered events and checking which entities have `CollisionEventsEnabled`. System-local buffers and exclusive world access are used to try and minimize overhead and unnecessary allocations. Usage of the events might look like this: ```rust use avian3d::prelude::*; use bevy::prelude::*; #[derive(Component)] struct Player; #[derive(Component)] struct PressurePlate; fn setup_pressure_plates(mut commands: Commands) { commands.spawn(( PressurePlate, Collider::cuboid(1.0, 0.1, 1.0), Sensor, // Enable collision events for this entity. CollisionEventsEnabled, )) .observe(|trigger: Trigger<OnCollisionStart>, player_query: Query<&Player>| { let pressure_plate = trigger.entity(); if player_query.contains(trigger.0) { println!("Player {trigger.0} stepped on pressure plate {pressure_plate}"); } }); } ``` The system that triggers the events runs in a `CollisionEventSystems` system set in a new `PhysicsStepSet::Finalize` system set right before `PhysicsStepSet::Last`.
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Add this suggestion to a batch that can be applied as a single commit.This suggestion is invalid because no changes were made to the code.Suggestions cannot be applied while the pull request is closed.Suggestions cannot be applied while viewing a subset of changes.Only one suggestion per line can be applied in a batch.Add this suggestion to a batch that can be applied as a single commit.Applying suggestions on deleted lines is not supported.You must change the existing code in this line in order to create a valid suggestion.Outdated suggestions cannot be applied.This suggestion has been applied or marked resolved.Suggestions cannot be applied from pending reviews.Suggestions cannot be applied on multi-line comments.Suggestions cannot be applied while the pull request is queued to merge.Suggestion cannot be applied right now. Please check back later.
Objective
Currently, contact pair management works as follows:
BroadCollisionPairsresource.during_previous_frameandduring_current_frameof each existing contact totrueandfalserespectively.BroadCollisionPairsin parallel. For each pair:Collisions, if they exist, and setduring_previous_frameaccordingly.Collisions.CollidingEntities).during_current_frameisfalse.There are a lot of inefficiencies here.
Vecevery frame.BroadCollisionPairscollects collisions into new vectors every time.Overall, there is an excessive amount of iteration and allocations, and the logic for managing contact statuses is very confusing.
In addition, the
Collisionsresource itself is not efficient for our purposes. There are many cases where you may need to iterate over contacts associated with a specific entity, but this currently requires iterating through all collisions because collisions are just stored in anIndexMap. To resolve this, we need a more graph-like structure.Solution
Change
Collisionsto aContactGraph, and rework contact pair management to look like the following:ContactGraphdirectly. Duplicate pairs are avoided with fast lookups into aHashSet<PairKey>.ContactGraphin parallel, maintaining thread-local bit vectors to track contact status changes. For each contact pair:ContactPairFlags::DISJOINT_AABBand the status change bit for this contact pair. Continue to the next pair.CollisionEndedevent (if events are enabled), updateCollidingEntities, and remove the pair fromCollisions.CollisionStaredevent (if events are enabled) and updateCollidingEntities.CollisionEndedevent (if events are enabled) and updateCollidingEntities.The use of bit vectors to track status changes was inspired by Box2D v3.
Contact removal for removed or disabled colliders is now also handled with observers.
This improves several aspects:
ContactGraphdirectly.ContactGraphdirectly, and don't need to do separate lookups for previous contacts or do any extra allocations.As you may have noticed, a contact pair now exists between two colliders if their AABBs are touching, even if the actual shapes aren't. This is important for the pair management logic, though it does mean that the
ContactGraphcan now have a lot more contact pairs in some cases.Contact Graph
Previously,
Collisionsused anIndexMapto store collisions, keyed by(Entity, Entity). The motivation was that we get vec-like iteration speed, with preserved insertion order and fast lookups by entity pairs.However, there are scenarios where you may need to iterate over the entities colliding with a given entity, such as for simulation islands or even gameplay logic. With just an
IndexMap, this requires iterating over all pairs.This PR adds an undirected graph data structure called
UnGraph, based on petgraph, simplified and tailored for our use cases.This is used for the new
ContactGraphto provide faster and more powerful queries over contact pairs. The following methods are available:get(&self, entity1: Entity, entity2: Entity)get_mut(&mut self, entity1: Entity, entity2: Entity)contains(&self, entity1: Entity, entity2: Entity)contains_key(&self, pair_key: &PairKey)iter(&self)iter_touching(&self)iter_mut(&mut self)iter_touching_mut(&mut self)collisions_with(&self, entity: Entity)collisions_with_mut(&mut self, entity: Entity)entities_colliding_with(&self, entity: Entity)and a few ones primarily for internals:
add_pair(&mut self, contacts: Contacts)add_pair_with_key(&mut self, contacts: Contacts, pair_key: PairKey)insert_pair(&mut self, contacts: Contacts)insert_pair_with_key(&mut self, contacts: Contacts, pair_key: PairKey)remove_pair(&mut self, entity1: Entity, entity2: Entity)remove_collider_with(&mut self, entity: Entity, pair_callback: F)The graph doesn't let us directly get nodes or edges by
EntityID. However, a newEntityDataIndexis used to mapEntityIDs to graph nodes.This is modeled after Rapier's
Coarena.CollisionsSystem ParameterThe
ContactGraphresource contains both touching and non-touching contacts. This may be inconvenient and confusing for new users.To provide a simpler, more user-friendly API, a
CollisionsSystemParamhas been added. It is similar to the oldCollisionsresource, and only provides access to touching contacts. It doesn't allow mutation, as contact modification and filtering should typically be handled viaCollisionHooks.Contact Reporting
Previously, the
ContactReportingPluginsent theCollisionStarted,CollisionEnded, andCollisionevents and updatedCollidingEntitiesfor all contact pairs after the solver. This required iterating through all contacts and performing lots of queries, which had meaningful overhead, even for apps that don't need collision events, or only need them for a few entities.Very few applications actually need collision events for all entities. In most engines, contact reporting/monitoring is entirely optional, and typically opt-in. Thus, a new
CollisionEventsEnabledcomponent has been added. Collision events are only sent if either entity in a collision has the component.The
ContactReportingPluginhas also been entirely removed, and contact reporting is now handled directly by the narrow phase when processing contact status changes. This removes the need for extra iteration or queries.Finally, the
Collisionevent has been removed. It was largely unnecessary, as the collision data can be accessed throughCollisionsdirectly. And semantically, it didn't feel like an "event" as it was sent every frame during continuous contact.Performance
In the new
pyramid_2dexample, with a pyramid that has a base of 50 boxes, 1276 total colliders, and 6 substeps, the old timings with theparallelfeature looked like the following after 500 steps:Now, they look like this:
Notably:
wake_on_collision_endedbeing removed in favor of much more efficient logic integrated into the narrow phaseThe total step time in this scene is reduced by 1.76 ms. The difference should be larger the more collisions there are.
Single-threaded performance is also improved, though not quite as much. In the same test scene, the old timings looked like this:
Now, they look like this:
reducing the total step time in this scene by 0.7 ms.
The changes in this PR also unlock many future optimizations:
It is worth noting that we are currently using Bevy's built-in
ComputeTaskPoolfor parallelism, which limits the number of available threads. Using it, we are still slightly behind Rapier's narrow phase performance. However, I have measured that if we manually increase the size of the thread pool, or use rayon, we now match or even slightly outperform Rapier's narrow phase.Future Work
ContactstoContactPairContactManifoldtypes)Migration Guide
PostProcessCollisionsThe
PostProcessCollisionsschedule andNarrowPhaseSet::PostProcesssystem set have been removed, as it is incompatible with new optimizations to narrow phase collision detection. Instead, useCollisionHooksfor contact modification.Contact Reporting
The
ContactReportingPluginandPhysicsStepSet::ReportContactssystem set have been removed. Contact reporting is now handled by theNarrowPhasePlugindirectly.The
Collisionevent no longer exists. Instead, useCollisionsdirectly, or get colliding entities using theCollidingEntitiescomponent.The
CollisionStartedandCollisionEndedevents are now only sent if either entity in the collision has theCollisionEventsEnabledcomponent. If you'd like to revert to the old behavior of having collision events for all entities, consider makingCollisionEventsEnableda required component forCollider:CollisionsThe
Collisionsresource is now aSystemParam.Internally,
Collisionsnow stores aContactGraphthat stores both touching and non-touching contact pairs. TheCollisionssystem parameter is just a wrapper that provides a simpler API and only returns touching contacts.The
collisions_with_entitymethod has also been renamed tocollisions_with, and all methods that mutatate, add, or remove contact pairs have been removed fromCollisions. However, the following mutating methods are available onContactGraph:get_mutiter_mutiter_touching_mutcollisions_with_mutadd_pair/add_pair_with_keyinsert_pair/insert_pair_with_keyremove_pairremove_collider_withFor most scenarios, contact modification and removal are intended to be handled with
CollisionHooks.ContactsThe
is_sensor,during_current_frame, andduring_previous_frameproperties ofContactshave been removed in favor of aflagsproperty storing information in a more compact bitflag format. Theis_sensor,is_touching,collision_started, andcollision_endedhelper methods can be used instead.ContactManifoldMethods such as
AnyCollider::contact_manifolds_with_contextnow take&mut Vec<ContactManifold>instead of returning a new vector every time. This allows manifolds to be persisted more effectively, and reduces unnecessary allocations.BroadCollisionPairsThe
BroadCollisionPairsresource has been removed. Use theContactGraphresource instead.AabbIntersectionsThe
AabbIntersectionscomponent has been removed. UseContactGraph::entities_colliding_withinstead.