aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--examples2d/all_examples2.rs2
-rw-r--r--examples2d/damping2.rs2
-rw-r--r--examples3d/all_examples3.rs2
-rw-r--r--examples3d/damping3.rs2
-rw-r--r--src/geometry/collider.rs17
-rw-r--r--src/geometry/contact_pair.rs11
-rw-r--r--src/geometry/mod.rs2
-rw-r--r--src/geometry/narrow_phase.rs16
-rw-r--r--src/pipeline/collision_pipeline.rs6
-rw-r--r--src/pipeline/mod.rs4
-rw-r--r--src_testbed/harness/mod.rs14
-rw-r--r--src_testbed/physics/mod.rs4
-rw-r--r--src_testbed/testbed.rs10
13 files changed, 61 insertions, 31 deletions
diff --git a/examples2d/all_examples2.rs b/examples2d/all_examples2.rs
index 5040c8a..f4430aa 100644
--- a/examples2d/all_examples2.rs
+++ b/examples2d/all_examples2.rs
@@ -18,6 +18,7 @@ mod debug_box_ball2;
mod heightfield2;
mod joints2;
mod locked_rotations2;
+mod one_way_platforms2;
mod platform2;
mod polyline2;
mod pyramid2;
@@ -65,6 +66,7 @@ pub fn main() {
("Heightfield", heightfield2::init_world),
("Joints", joints2::init_world),
("Locked rotations", locked_rotations2::init_world),
+ ("One-way platforms", one_way_platforms2::init_world),
("Platform", platform2::init_world),
("Polyline", polyline2::init_world),
("Pyramid", pyramid2::init_world),
diff --git a/examples2d/damping2.rs b/examples2d/damping2.rs
index 43ca2b6..68fd77d 100644
--- a/examples2d/damping2.rs
+++ b/examples2d/damping2.rs
@@ -40,6 +40,6 @@ pub fn init_world(testbed: &mut Testbed) {
/*
* Set up the testbed.
*/
- testbed.set_world_with_gravity(bodies, colliders, joints, Vector2::zeros());
+ testbed.set_world_with_params(bodies, colliders, joints, Vector2::zeros(), ());
testbed.look_at(Point2::new(3.0, 2.0), 50.0);
}
diff --git a/examples3d/all_examples3.rs b/examples3d/all_examples3.rs
index 9cbf4c3..8a71665 100644
--- a/examples3d/all_examples3.rs
+++ b/examples3d/all_examples3.rs
@@ -29,6 +29,7 @@ mod heightfield3;
mod joints3;
mod keva3;
mod locked_rotations3;
+mod one_way_platforms3;
mod platform3;
mod primitives3;
mod restitution3;
@@ -83,6 +84,7 @@ pub fn main() {
("Heightfield", heightfield3::init_world),
("Joints", joints3::init_world),
("Locked rotations", locked_rotations3::init_world),
+ ("One-way platforms", one_way_platforms3::init_world),
("Platform", platform3::init_world),
("Restitution", restitution3::init_world),
("Sensor", sensor3::init_world),
diff --git a/examples3d/damping3.rs b/examples3d/damping3.rs
index 8c68d3b..3847ceb 100644
--- a/examples3d/damping3.rs
+++ b/examples3d/damping3.rs
@@ -40,6 +40,6 @@ pub fn init_world(testbed: &mut Testbed) {
/*
* Set up the testbed.
*/
- testbed.set_world_with_gravity(bodies, colliders, joints, Vector3::zeros());
+ testbed.set_world_with_params(bodies, colliders, joints, Vector3::zeros(), ());
testbed.look_at(Point3::new(2.0, 2.5, 20.0), Point3::new(2.0, 2.5, 0.0));
}
diff --git a/src/geometry/collider.rs b/src/geometry/collider.rs
index ce263f8..4be6d29 100644
--- a/src/geometry/collider.rs
+++ b/src/geometry/collider.rs
@@ -1,5 +1,5 @@
use crate::dynamics::{CoefficientCombineRule, MassProperties, RigidBodyHandle};
-use crate::geometry::{InteractionGroups, SharedShape};
+use crate::geometry::{InteractionGroups, SharedShape, SolverFlags};
use crate::math::{AngVector, Isometry, Point, Real, Rotation, Vector, DIM};
use crate::parry::transformation::vhacd::VHACDParameters;
use parry::bounding_volume::AABB;
@@ -50,6 +50,7 @@ pub struct Collider {
shape: SharedShape,
density: Real,
pub(crate) flags: ColliderFlags,
+ pub(crate) solver_flags: SolverFlags,
pub(crate) parent: RigidBodyHandle,
pub(crate) delta: Isometry<Real>,
pub(crate) position: Isometry<Real>,
@@ -159,6 +160,9 @@ pub struct ColliderBuilder {
pub delta: Isometry<Real>,
/// Is this collider a sensor?
pub is_sensor: bool,
+ /// Do we have to always call the contact modifier
+ /// on this collider?
+ pub modify_contacts: bool,
/// The user-data of the collider being built.
pub user_data: u128,
/// The collision groups for the collider being built.
@@ -182,6 +186,7 @@ impl ColliderBuilder {
solver_groups: InteractionGroups::all(),
friction_combine_rule: CoefficientCombineRule::Average,
restitution_combine_rule: CoefficientCombineRule::Average,
+ modify_contacts: false,
}
}
@@ -456,6 +461,13 @@ impl ColliderBuilder {
self
}
+ /// If set to `true` then the physics hooks will always run to modify
+ /// contacts involving this collider.
+ pub fn modify_contacts(mut self, modify_contacts: bool) -> Self {
+ self.modify_contacts = modify_contacts;
+ self
+ }
+
/// Sets the friction coefficient of the collider this builder will build.
pub fn friction(mut self, friction: Real) -> Self {
self.friction = friction;
@@ -534,6 +546,8 @@ impl ColliderBuilder {
flags = flags
.with_friction_combine_rule(self.friction_combine_rule)
.with_restitution_combine_rule(self.restitution_combine_rule);
+ let mut solver_flags = SolverFlags::default();
+ solver_flags.set(SolverFlags::MODIFY_SOLVER_CONTACTS, self.modify_contacts);
Collider {
shape: self.shape.clone(),
@@ -542,6 +556,7 @@ impl ColliderBuilder {
restitution: self.restitution,
delta: self.delta,
flags,
+ solver_flags,
parent: RigidBodyHandle::invalid(),
position: Isometry::identity(),
predicted_position: Isometry::identity(),
diff --git a/src/geometry/contact_pair.rs b/src/geometry/contact_pair.rs
index 11e0188..50094ca 100644
--- a/src/geometry/contact_pair.rs
+++ b/src/geometry/contact_pair.rs
@@ -16,6 +16,12 @@ bitflags::bitflags! {
}
}
+impl Default for SolverFlags {
+ fn default() -> Self {
+ SolverFlags::COMPUTE_IMPULSES
+ }
+}
+
#[derive(Copy, Clone, Debug)]
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
/// A single contact between two collider.
@@ -126,10 +132,11 @@ pub struct SolverContact {
pub friction: Real,
/// The effective restitution coefficient at this contact point.
pub restitution: Real,
- /// The artificially add relative velocity at the contact point.
+ /// The desired tangent relative velocity at the contact point.
+ ///
/// This is set to zero by default. Set to a non-zero value to
/// simulate, e.g., conveyor belts.
- pub surface_velocity: Vector<Real>,
+ pub tangent_velocity: Vector<Real>,
/// Associated contact data used to warm-start the constraints
/// solver.
pub data: ContactData,
diff --git a/src/geometry/mod.rs b/src/geometry/mod.rs
index 2997e24..ab04b25 100644
--- a/src/geometry/mod.rs
+++ b/src/geometry/mod.rs
@@ -10,7 +10,6 @@ pub use self::interaction_graph::{
};
pub use self::interaction_groups::InteractionGroups;
pub use self::narrow_phase::NarrowPhase;
-pub use self::pair_filter::{PairFilterContext, PhysicsHooks};
pub use parry::query::TrackedContact;
@@ -109,4 +108,3 @@ mod contact_pair;
mod interaction_graph;
mod interaction_groups;
mod narrow_phase;
-mod pair_filter;
diff --git a/src/geometry/narrow_phase.rs b/src/geometry/narrow_phase.rs
index e929e0f..d05b19a 100644
--- a/src/geometry/narrow_phase.rs
+++ b/src/geometry/narrow_phase.rs
@@ -4,15 +4,15 @@ use rayon::prelude::*;
use crate::data::pubsub::Subscription;
use crate::data::Coarena;
use crate::dynamics::{BodyPair, CoefficientCombineRule, RigidBodySet};
-use crate::geometry::pair_filter::{ContactModificationContext, PhysicsHooksFlags};
use crate::geometry::{
- BroadPhasePairEvent, ColliderGraphIndex, ColliderHandle, ContactData, ContactEvent,
- ContactManifoldData, IntersectionEvent, PairFilterContext, PhysicsHooks, RemovedCollider,
- SolverContact, SolverFlags,
+ BroadPhasePairEvent, ColliderGraphIndex, ColliderHandle, ColliderSet, ContactData,
+ ContactEvent, ContactManifold, ContactManifoldData, ContactPair, InteractionGraph,
+ IntersectionEvent, RemovedCollider, SolverContact, SolverFlags,
};
-use crate::geometry::{ColliderSet, ContactManifold, ContactPair, InteractionGraph};
use crate::math::{Real, Vector};
-use crate::pipeline::EventHandler;
+use crate::pipeline::{
+ ContactModificationContext, EventHandler, PairFilterContext, PhysicsHooks, PhysicsHooksFlags,
+};
use parry::query::{DefaultQueryDispatcher, PersistentQueryDispatcher};
use parry::utils::IsometryOpt;
use std::collections::HashMap;
@@ -518,7 +518,7 @@ impl NarrowPhase {
return;
}
} else {
- SolverFlags::COMPUTE_IMPULSES
+ co1.solver_flags | co2.solver_flags
};
if !co1.solver_groups.test(co2.solver_groups) {
@@ -573,7 +573,7 @@ impl NarrowPhase {
dist: contact.dist,
friction,
restitution,
- surface_velocity: Vector::zeros(),
+ tangent_velocity: Vector::zeros(),
data: contact.data,
};
diff --git a/src/pipeline/collision_pipeline.rs b/src/pipeline/collision_pipeline.rs
index 6f02d98..a74a6e5 100644
--- a/src/pipeline/collision_pipeline.rs
+++ b/src/pipeline/collision_pipeline.rs
@@ -1,11 +1,9 @@
//! Physics pipeline structures.
use crate::dynamics::{JointSet, RigidBodySet};
-use crate::geometry::{
- BroadPhase, BroadPhasePairEvent, ColliderPair, ColliderSet, NarrowPhase, PhysicsHooks,
-};
+use crate::geometry::{BroadPhase, BroadPhasePairEvent, ColliderPair, ColliderSet, NarrowPhase};
use crate::math::Real;
-use crate::pipeline::EventHandler;
+use crate::pipeline::{EventHandler, PhysicsHooks};
/// The collision pipeline, responsible for performing collision detection between colliders.
///
diff --git a/src/pipeline/mod.rs b/src/pipeline/mod.rs
index 287de9d..fd85cfa 100644
--- a/src/pipeline/mod.rs
+++ b/src/pipeline/mod.rs
@@ -2,10 +2,14 @@
pub use collision_pipeline::CollisionPipeline;
pub use event_handler::{ChannelEventCollector, EventHandler};
+pub use physics_hooks::{
+ ContactModificationContext, PairFilterContext, PhysicsHooks, PhysicsHooksFlags,
+};
pub use physics_pipeline::PhysicsPipeline;
pub use query_pipeline::QueryPipeline;
mod collision_pipeline;
mod event_handler;
+mod physics_hooks;
mod physics_pipeline;
mod query_pipeline;
diff --git a/src_testbed/harness/mod.rs b/src_testbed/harness/mod.rs
index 53aa893..5e75d85 100644
--- a/src_testbed/harness/mod.rs
+++ b/src_testbed/harness/mod.rs
@@ -7,7 +7,7 @@ use plugin::HarnessPlugin;
use rapier::dynamics::{IntegrationParameters, JointSet, RigidBodySet};
use rapier::geometry::{BroadPhase, ColliderSet, NarrowPhase};
use rapier::math::Vector;
-use rapier::pipeline::{ChannelEventCollector, PhysicsPipeline, QueryPipeline};
+use rapier::pipeline::{ChannelEventCollector, PhysicsHooks, PhysicsPipeline, QueryPipeline};
pub mod plugin;
@@ -111,15 +111,16 @@ impl Harness {
}
pub fn set_world(&mut self, bodies: RigidBodySet, colliders: ColliderSet, joints: JointSet) {
- self.set_world_with_gravity(bodies, colliders, joints, Vector::y() * -9.81)
+ self.set_world_with_params(bodies, colliders, joints, Vector::y() * -9.81, ())
}
- pub fn set_world_with_gravity(
+ pub fn set_world_with_params(
&mut self,
bodies: RigidBodySet,
colliders: ColliderSet,
joints: JointSet,
gravity: Vector<f32>,
+ hooks: impl PhysicsHooks + 'static,
) {
// println!("Num bodies: {}", bodies.len());
// println!("Num joints: {}", joints.len());
@@ -127,6 +128,8 @@ impl Harness {
self.physics.bodies = bodies;
self.physics.colliders = colliders;
self.physics.joints = joints;
+ self.physics.hooks = Box::new(hooks);
+
self.physics.broad_phase = BroadPhase::new();
self.physics.narrow_phase = NarrowPhase::new();
self.state.timestep_id = 0;
@@ -176,8 +179,7 @@ impl Harness {
&mut physics.bodies,
&mut physics.colliders,
&mut physics.joints,
- None,
- None,
+ &*physics.hooks,
event_handler,
);
});
@@ -192,7 +194,7 @@ impl Harness {
&mut self.physics.bodies,
&mut self.physics.colliders,
&mut self.physics.joints,
- &(),
+ &*self.physics.hooks,
&self.event_handler,
);
diff --git a/src_testbed/physics/mod.rs b/src_testbed/physics/mod.rs
index 808e9bd..0987e32 100644
--- a/src_testbed/physics/mod.rs
+++ b/src_testbed/physics/mod.rs
@@ -2,7 +2,7 @@ use crossbeam::channel::Receiver;
use rapier::dynamics::{IntegrationParameters, JointSet, RigidBodySet};
use rapier::geometry::{BroadPhase, ColliderSet, ContactEvent, IntersectionEvent, NarrowPhase};
use rapier::math::Vector;
-use rapier::pipeline::{PhysicsPipeline, QueryPipeline};
+use rapier::pipeline::{PhysicsHooks, PhysicsPipeline, QueryPipeline};
pub struct PhysicsSnapshot {
timestep_id: usize,
@@ -77,6 +77,7 @@ pub struct PhysicsState {
pub query_pipeline: QueryPipeline,
pub integration_parameters: IntegrationParameters,
pub gravity: Vector<f32>,
+ pub hooks: Box<dyn PhysicsHooks>,
}
impl PhysicsState {
@@ -91,6 +92,7 @@ impl PhysicsState {
query_pipeline: QueryPipeline::new(),
integration_parameters: IntegrationParameters::default(),
gravity: Vector::y() * -9.81,
+ hooks: Box::new(()),
}
}
}
diff --git a/src_testbed/testbed.rs b/src_testbed/testbed.rs
index b8ef324..bc5cd6c 100644
--- a/src_testbed/testbed.rs
+++ b/src_testbed/testbed.rs
@@ -25,6 +25,7 @@ use rapier::geometry::{ColliderHandle, ColliderSet, NarrowPhase};
#[cfg(feature = "dim3")]
use rapier::geometry::{InteractionGroups, Ray};
use rapier::math::{Isometry, Vector};
+use rapier::pipeline::PhysicsHooks;
#[cfg(all(feature = "dim2", feature = "other-backends"))]
use crate::box2d_backend::Box2dWorld;
@@ -245,20 +246,19 @@ impl Testbed {
}
pub fn set_world(&mut self, bodies: RigidBodySet, colliders: ColliderSet, joints: JointSet) {
- self.set_world_with_gravity(bodies, colliders, joints, Vector::y() * -9.81)
+ self.set_world_with_params(bodies, colliders, joints, Vector::y() * -9.81, ())
}
- pub fn set_world_with_gravity(
+ pub fn set_world_with_params(
&mut self,
bodies: RigidBodySet,
colliders: ColliderSet,
joints: JointSet,
gravity: Vector<f32>,
+ hooks: impl PhysicsHooks + 'static,
) {
- println!("Num bodies: {}", bodies.len());
- println!("Num joints: {}", joints.len());
self.harness
- .set_world_with_gravity(bodies, colliders, joints, gravity);
+ .set_world_with_params(bodies, colliders, joints, gravity, hooks);
self.state
.action_flags