diff options
| author | Crozet Sébastien <developer@crozet.re> | 2021-03-07 11:43:47 +0100 |
|---|---|---|
| committer | Crozet Sébastien <developer@crozet.re> | 2021-03-07 11:44:19 +0100 |
| commit | bed47a82e706a13c22799fcf644753c69fdec6ad (patch) | |
| tree | 51db7ca364983b29ce31ddb6256e6badaad60c06 | |
| parent | e7f805aea45612abb655b3c36a133357fecfcdc4 (diff) | |
| download | rapier-bed47a82e706a13c22799fcf644753c69fdec6ad.tar.gz rapier-bed47a82e706a13c22799fcf644753c69fdec6ad.tar.bz2 rapier-bed47a82e706a13c22799fcf644753c69fdec6ad.zip | |
Projection friction impulses on an implicit cone instead of a pyramidal approximation.
| -rw-r--r-- | build/rapier3d-f64/Cargo.toml | 2 | ||||
| -rw-r--r-- | build/rapier3d/Cargo.toml | 2 | ||||
| -rw-r--r-- | examples2d/one_way_platforms2.rs | 2 | ||||
| -rw-r--r-- | examples3d/all_examples3.rs | 2 | ||||
| -rw-r--r-- | examples3d/debug_friction3.rs | 50 | ||||
| -rw-r--r-- | examples3d/one_way_platforms3.rs | 2 | ||||
| -rw-r--r-- | src/dynamics/coefficient_combine_rule.rs | 2 | ||||
| -rw-r--r-- | src/dynamics/solver/velocity_constraint.rs | 230 | ||||
| -rw-r--r-- | src/dynamics/solver/velocity_constraint_wide.rs | 197 | ||||
| -rw-r--r-- | src/dynamics/solver/velocity_ground_constraint.rs | 158 | ||||
| -rw-r--r-- | src/dynamics/solver/velocity_ground_constraint_wide.rs | 161 | ||||
| -rw-r--r-- | src/geometry/contact_pair.rs | 16 | ||||
| -rw-r--r-- | src/pipeline/physics_hooks.rs | 10 | ||||
| -rw-r--r-- | src/utils.rs | 12 | ||||
| -rw-r--r-- | src_testbed/physx_backend.rs | 4 |
15 files changed, 625 insertions, 225 deletions
diff --git a/build/rapier3d-f64/Cargo.toml b/build/rapier3d-f64/Cargo.toml index 54d4892..e201811 100644 --- a/build/rapier3d-f64/Cargo.toml +++ b/build/rapier3d-f64/Cargo.toml @@ -39,7 +39,7 @@ required-features = [ "dim3", "f64" ] vec_map = { version = "0.8", optional = true } instant = { version = "0.1", features = [ "now" ]} num-traits = "0.2" -nalgebra = "0.25" +nalgebra = "^0.25.3" parry3d-f64 = "0.2" simba = "0.4" approx = "0.4" diff --git a/build/rapier3d/Cargo.toml b/build/rapier3d/Cargo.toml index ccd0d08..0a83872 100644 --- a/build/rapier3d/Cargo.toml +++ b/build/rapier3d/Cargo.toml @@ -39,7 +39,7 @@ required-features = [ "dim3", "f32" ] vec_map = { version = "0.8", optional = true } instant = { version = "0.1", features = [ "now" ]} num-traits = "0.2" -nalgebra = "0.25" +nalgebra = "^0.25.3" parry3d = "0.2" simba = "0.4" approx = "0.4" diff --git a/examples2d/one_way_platforms2.rs b/examples2d/one_way_platforms2.rs index 551eaf1..fc3acb1 100644 --- a/examples2d/one_way_platforms2.rs +++ b/examples2d/one_way_platforms2.rs @@ -40,7 +40,7 @@ impl PhysicsHooks for OneWayPlatformHook { allowed_local_n1 = -Vector2::y(); } else if context.collider_handle2 == self.platform2 { // Flip the allowed direction. - allowed_local_n1 = -Vector2::y(); + allowed_local_n1 = Vector2::y(); } // Call the helper function that simulates one-way platforms. diff --git a/examples3d/all_examples3.rs b/examples3d/all_examples3.rs index 8a71665..724aa45 100644 --- a/examples3d/all_examples3.rs +++ b/examples3d/all_examples3.rs @@ -19,6 +19,7 @@ mod debug_add_remove_collider3; mod debug_boxes3; mod debug_cylinder3; mod debug_dynamic_collider_add3; +mod debug_friction3; mod debug_infinite_fall3; mod debug_rollback3; mod debug_triangle3; @@ -99,6 +100,7 @@ pub fn main() { "(Debug) dyn. coll. add", debug_dynamic_collider_add3::init_world, ), + ("(Debug) friction", debug_friction3::init_world), ("(Debug) triangle", debug_triangle3::init_world), ("(Debug) trimesh", debug_trimesh3::init_world), ("(Debug) cylinder", debug_cylinder3::init_world), diff --git a/examples3d/debug_friction3.rs b/examples3d/debug_friction3.rs new file mode 100644 index 0000000..5cf40b3 --- /dev/null +++ b/examples3d/debug_friction3.rs @@ -0,0 +1,50 @@ +use na::{Point3, Vector3}; +use rapier3d::dynamics::{JointSet, RigidBodyBuilder, RigidBodySet}; +use rapier3d::geometry::{ColliderBuilder, ColliderSet}; +use rapier_testbed3d::Testbed; + +pub fn init_world(testbed: &mut Testbed) { + /* + * World + */ + let mut bodies = RigidBodySet::new(); + let mut colliders = ColliderSet::new(); + let joints = JointSet::new(); + + /* + * Ground + */ + let ground_size = 100.0; + let ground_height = 0.1; + + let rigid_body = RigidBodyBuilder::new_static().build(); + let handle = bodies.insert(rigid_body); + let collider = ColliderBuilder::cuboid(ground_size, ground_height, ground_size) + .friction(1.5) + .build(); + colliders.insert(collider, handle, &mut bodies); + + // Build a dynamic box rigid body. + let rigid_body = RigidBodyBuilder::new_dynamic() + .translation(0.0, 1.1, 0.0) + .rotation(Vector3::y() * 0.3) + .build(); + let handle = bodies.insert(rigid_body); + let collider = ColliderBuilder::cuboid(2.0, 1.0, 3.0).friction(1.5).build(); + colliders.insert(collider, handle, &mut bodies); + + let rigid_body = &mut bodies[handle]; + let force = rigid_body.position() * Vector3::z() * 50.0; + rigid_body.set_linvel(force, true); + + /* + * Set up the testbed. + */ + testbed.set_world(bodies, colliders, joints); + testbed.look_at(Point3::new(10.0, 10.0, 10.0), Point3::origin()); +} + +fn main() { + let testbed = Testbed::from_builders(0, vec![("Boxes", init_world)]); + testbed.run() +} diff --git a/examples3d/one_way_platforms3.rs b/examples3d/one_way_platforms3.rs index 173d03d..d117a5b 100644 --- a/examples3d/one_way_platforms3.rs +++ b/examples3d/one_way_platforms3.rs @@ -40,7 +40,7 @@ impl PhysicsHooks for OneWayPlatformHook { allowed_local_n1 = -Vector3::y(); } else if context.collider_handle2 == self.platform2 { // Flip the allowed direction. - allowed_local_n1 = -Vector3::y(); + allowed_local_n1 = Vector3::y(); } // Call the helper function that simulates one-way platforms. diff --git a/src/dynamics/coefficient_combine_rule.rs b/src/dynamics/coefficient_combine_rule.rs index 5e8b4a0..2c66888 100644 --- a/src/dynamics/coefficient_combine_rule.rs +++ b/src/dynamics/coefficient_combine_rule.rs @@ -25,7 +25,7 @@ impl CoefficientCombineRule { let effective_rule = rule_value1.max(rule_value2); match effective_rule { - 0 => (coeff1 + coeff1) / 2.0, + 0 => (coeff1 + coeff2) / 2.0, 1 => coeff1.min(coeff2), 2 => coeff1 * coeff2, _ => coeff1.max(coeff2), diff --git a/src/dynamics/solver/velocity_constraint.rs b/src/dynamics/solver/velocity_constraint.rs index 243d7d7..8e70fb0 100644 --- a/src/dynamics/solver/velocity_constraint.rs +++ b/src/dynamics/solver/velocity_constraint.rs @@ -6,7 +6,8 @@ use crate::dynamics::{IntegrationParameters, RigidBodySet}; use crate::geometry::{ContactManifold, ContactManifoldIndex}; use crate::math::{AngVector, Real, Vector, DIM, MAX_MANIFOLD_POINTS}; use crate::utils::{WAngularInertia, WBasis, WCross, WDot}; -use simba::simd::SimdPartialOrd; +#[cfg(feature = "dim2")] +use na::SimdPartialOrd; //#[repr(align(64))] #[derive(Copy, Clone, Debug)] @@ -78,7 +79,34 @@ impl AnyVelocityConstraint { } #[derive(Copy, Clone, Debug)] -pub(crate) struct VelocityConstraintElementPart { +pub(crate) struct VelocityConstraintTangentPart { + pub gcross1: [AngVector<Real>; DIM - 1], + pub gcross2: [AngVector<Real>; DIM - 1], + pub rhs: [Real; DIM - 1], + #[cfg(feature = "dim2")] + pub impulse: [Real; DIM - 1], + #[cfg(feature = "dim3")] + pub impulse: na::Vector2<Real>, + pub r: [Real; DIM - 1], +} + +impl VelocityConstraintTangentPart { + fn zero() -> Self { + Self { + gcross1: [na::zero(); DIM - 1], + gcross2: [na::zero(); DIM - 1], + rhs: [0.0; DIM - 1], + #[cfg(feature = "dim2")] + impulse: [0.0; DIM - 1], + #[cfg(feature = "dim3")] + impulse: na::zero(), + r: [0.0; DIM - 1], + } + } +} + +#[derive(Copy, Clone, Debug)] +pub(crate) struct VelocityConstraintNormalPart { pub gcross1: AngVector<Real>, pub gcross2: AngVector<Real>, pub rhs: Real, @@ -87,7 +115,7 @@ pub(crate) struct VelocityConstraintElementPart { } #[cfg(not(target_arch = "wasm32"))] -impl VelocityConstraintElementPart { +impl VelocityConstraintNormalPart { fn zero() -> Self { Self { gcross1: na::zero(), @@ -101,16 +129,16 @@ impl VelocityConstraintElementPart { #[derive(Copy, Clone, Debug)] pub(crate) struct VelocityConstraintElement { - pub normal_part: VelocityConstraintElementPart, - pub tangent_part: [VelocityConstraintElementPart; DIM - 1], + pub normal_part: VelocityConstraintNormalPart, + pub tangent_part: VelocityConstraintTangentPart, } #[cfg(not(target_arch = "wasm32"))] impl VelocityConstraintElement { pub fn zero() -> Self { Self { - normal_part: VelocityConstraintElementPart::zero(), - tangent_part: [VelocityConstraintElementPart::zero(); DIM - 1], + normal_part: VelocityConstraintNormalPart::zero(), + tangent_part: VelocityConstraintTangentPart::zero(), } } } @@ -118,6 +146,10 @@ impl VelocityConstraintElement { #[derive(Copy, Clone, Debug)] pub(crate) struct VelocityConstraint { pub dir1: Vector<Real>, // Non-penetration force direction for the first body. + #[cfg(feature = "dim3")] + pub tangent1: Vector<Real>, // One of the friction force directions. + #[cfg(feature = "dim3")] + pub tangent_rot1: na::UnitComplex<Real>, // Orientation of the tangent basis wrt. the reference basis. pub im1: Real, pub im2: Real, pub limit: Real, @@ -156,6 +188,12 @@ impl VelocityConstraint { let force_dir1 = -manifold.data.normal; let warmstart_coeff = manifold.data.warmstart_multiplier * params.warmstart_coeff; + #[cfg(feature = "dim2")] + let tangents1 = force_dir1.orthonormal_basis(); + #[cfg(feature = "dim3")] + let (tangents1, tangent_rot1) = + super::compute_tangent_contact_directions(&force_dir1, &rb1.linvel, &rb2.linvel); + for (_l, manifold_points) in manifold .data .solver_contacts @@ -165,6 +203,10 @@ impl VelocityConstraint { #[cfg(not(target_arch = "wasm32"))] let mut constraint = VelocityConstraint { dir1: force_dir1, + #[cfg(feature = "dim3")] + tangent1: tangents1[0], + #[cfg(feature = "dim3")] + tangent_rot1, elements: [VelocityConstraintElement::zero(); MAX_MANIFOLD_POINTS], im1: rb1.effective_inv_mass, im2: rb2.effective_inv_mass, @@ -203,7 +245,7 @@ impl VelocityConstraint { .as_nongrouped_mut() .unwrap() } else { - unreachable!(); // We don't have parallelization on WASM yet, so this is unreachable. + unreachable!(); // We don't have parallelization on WASM yet, so this is unreachable. }; #[cfg(target_arch = "wasm32")] @@ -254,7 +296,7 @@ impl VelocityConstraint { rhs *= is_bouncy + is_resting * params.velocity_solve_fraction; rhs += is_resting * velocity_based_erp_inv_dt * manifold_point.dist.min(0.0); - constraint.elements[k].normal_part = VelocityConstraintElementPart { + constraint.elements[k].normal_part = VelocityConstraintNormalPart { gcross1, gcross2, rhs, @@ -265,7 +307,12 @@ impl VelocityConstraint { // Tangent parts. { - let tangents1 = force_dir1.orthonormal_basis(); + #[cfg(feature = "dim3")] + let impulse = + tangent_rot1 * manifold_points[k].data.tangent_impulse * warmstart_coeff; + #[cfg(feature = "dim2")] + let impulse = [manifold_points[k].data.tangent_impulse * warmstart_coeff]; + constraint.elements[k].tangent_part.impulse = impulse; for j in 0..DIM - 1 { let gcross1 = rb1 @@ -281,18 +328,11 @@ impl VelocityConstraint { + gcross2.gdot(gcross2)); let rhs = (vel1 - vel2 + manifold_point.tangent_velocity).dot(&tangents1[j]); - #[cfg(feature = "dim2")] - let impulse = manifold_point.data.tangent_impulse * warmstart_coeff; - #[cfg(feature = "dim3")] - let impulse = manifold_point.data.tangent_impulse[j] * warmstart_coeff; - - constraint.elements[k].tangent_part[j] = VelocityConstraintElementPart { - gcross1, - gcross2, - rhs, - impulse, - r, - }; + + constraint.elements[k].tangent_part.gcross1[j] = gcross1; + constraint.elements[k].tangent_part.gcross2[j] = gcross2; + constraint.elements[k].tangent_part.rhs[j] = rhs; + constraint.elements[k].tangent_part.r[j] = r; } } } @@ -311,6 +351,11 @@ impl VelocityConstraint { let mut mj_lambda1 = DeltaVel::zero(); let mut mj_lambda2 = DeltaVel::zero(); + #[cfg(feature = "dim3")] + let tangents1 = [self.tangent1, self.dir1.cross(&self.tangent1)]; + #[cfg(feature = "dim2")] + let tangents1 = self.dir1.orthonormal_basis(); + for i in 0..self.num_contacts as usize { let elt = &self.elements[i].normal_part; mj_lambda1.linear += self.dir1 * (self.im1 * elt.impulse); @@ -319,16 +364,13 @@ impl VelocityConstraint { mj_lambda2.linear += self.dir1 * (-self.im2 * elt.impulse); mj_lambda2.angular += elt.gcross2 * elt.impulse; - // FIXME: move this out of the for loop? - let tangents1 = self.dir1.orthonormal_basis(); - for j in 0..DIM - 1 { - let elt = &self.elements[i].tangent_part[j]; - mj_lambda1.linear += tangents1[j] * (self.im1 * elt.impulse); - mj_lambda1.angular += elt.gcross1 * elt.impulse; + let elt = &self.elements[i].tangent_part; + mj_lambda1.linear += tangents1[j] * (self.im1 * elt.impulse[j]); + mj_lambda1.angular += elt.gcross1[j] * elt.impulse[j]; - mj_lambda2.linear += tangents1[j] * (-self.im2 * elt.impulse); - mj_lambda2.angular += elt.gcross2 * elt.impulse; + mj_lambda2.linear += tangents1[j] * (-self.im2 * elt.impulse[j]); + mj_lambda2.angular += elt.gcross2[j] * elt.impulse[j]; } } @@ -343,28 +385,63 @@ impl VelocityConstraint { let mut mj_lambda2 = mj_lambdas[self.mj_lambda2 as usize]; // Solve friction. + #[cfg(feature = "dim3")] + let bitangent1 = self.dir1.cross(&self.tangent1); + #[cfg(feature = "dim2")] + let tangents1 = self.dir1.orthonormal_basis(); + + #[cfg(feature = "dim2")] for i in 0..self.num_contacts as usize { - let tangents1 = self.dir1.orthonormal_basis(); + let normal_elt = &self.elements[i].normal_part; + let elt = &mut self.elements[i].tangent_part; + let dimpulse = tangents1[0].dot(&mj_lambda1.linear) + + elt.gcross1[0].gdot(mj_lambda1.angular) + - tangents1[0].dot(&mj_lambda2.linear) + + elt.gcross2[0].gdot(mj_lambda2.angular) + + elt.rhs[0]; + let limit = self.limit * normal_elt.impulse; + let new_impulse = (elt.impulse[0] - elt.r[0] * dimpulse).simd_clamp(-limit, limit); + let dlambda = new_impulse - elt.impulse[0]; + elt.impulse[0] = new_impulse; + + mj_lambda1.linear += tangents1[0] * (self.im1 * dlambda); + mj_lambda1.angular += elt.gcross1[0] * dlambda; + + mj_lambda2.linear += tangents1[0] * (-self.im2 * dlambda); + mj_lambda2.angular += elt.gcross2[0] * dlambda; + } - for j in 0..DIM - 1 { - let normal_elt = &self.elements[i].normal_part; - let elt = &mut self.elements[i].tangent_part[j]; - let dimpulse = tangents1[j].dot(&mj_lambda1.linear) - + elt.gcross1.gdot(mj_lambda1.angular) - - tangents1[j].dot(&mj_lambda2.linear) - + elt.gcross2.gdot(mj_lambda2.angular) - + elt.rhs; - let limit = self.limit * normal_elt.impulse; - let new_impulse = (elt.impulse - elt.r * dimpulse).simd_clamp(-limit, limit); - let dlambda = new_impulse - elt.impulse; - elt.impulse = new_impulse; - - mj_lambda1.linear += tangents1[j] * (self.im1 * dlambda); - mj_lambda1.angular += elt.gcross1 * dlambda; - - mj_lambda2.linear += tangents1[j] * (-self.im2 * dlambda); - mj_lambda2.angular += elt.gcross2 * dlambda; - } + #[cfg(feature = "dim3")] + for i in 0..self.num_contacts as usize { + let limit = self.limit * self.elements[i].normal_part.impulse; + let elt = &mut self.elements[i].tangent_part; + + let dimpulse_0 = self.tangent1.dot(&mj_lambda1.linear) + + elt.gcross1[0].gdot(mj_lambda1.angular) + - self.tangent1.dot(&mj_lambda2.linear) + + elt.gcross2[0].gdot(mj_lambda2.angular) + + elt.rhs[0]; + let dimpulse_1 = bitangent1.dot(&mj_lambda1.linear) + + elt.gcross1[1].gdot(mj_lambda1.angular) + - bitangent1.dot(&mj_lambda2.linear) + + elt.gcross2[1].gdot(mj_lambda2.angular) + + elt.rhs[1]; + + let new_impulse = na::Vector2::new( + elt.impulse[0] - elt.r[0] * dimpulse_0, + elt.impulse[1] - elt.r[1] * dimpulse_1, + ); + let new_impulse = new_impulse.cap_magnitude(limit); + let dlambda = new_impulse - elt.impulse; + elt.impulse = new_impulse; + + mj_lambda1.linear += + self.tangent1 * (self.im1 * dlambda[0]) + bitangent1 * (self.im1 * dlambda[1]); + mj_lambda1.angular += elt.gcross1[0] * dlambda[0] + elt.gcross1[1] * dlambda[1]; + + mj_lambda2.linear += + self.tangent1 * (-self.im2 * dlambda[0]) + bitangent1 * (-self.im2 * dlambda[1]); + mj_lambda2.angular += elt.gcross2[0] * dlambda[0] + elt.gcross2[1] * dlambda[1]; } // Solve non-penetration. @@ -398,15 +475,58 @@ impl VelocityConstraint { active_contact.data.impulse = self.elements[k].normal_part.impulse; #[cfg(feature = "dim2")] { - active_contact.data.tangent_impulse = self.elements[k].tangent_part[0].impulse; + active_contact.data.tangent_impulse = self.elements[k].tangent_part.impulse[0]; } #[cfg(feature = "dim3")] { - active_contact.data.tangent_impulse = [ - self.elements[k].tangent_part[0].impulse, - self.elements[k].tangent_part[1].impulse, - ]; + active_contact.data.tangent_impulse = self + .tangent_rot1 + .inverse_transform_vector(&self.elements[k].tangent_part.impulse); } } } } + +#[inline(always)] +#[cfg(feature = "dim3")] +pub(crate) fn compute_tangent_contact_directions<N>( + force_dir1: &Vector<N>, + linvel1: &Vector<N>, + linvel2: &Vector<N>, +) -> ([Vector<N>; DIM - 1], na::UnitComplex<N>) +where + N: na::SimdRealField, + N::Element: na::RealField, + Vector<N>: WBasis, +{ + use na::SimdValue; + + // Compute the tangent direction. Pick the direction of + // the linear relative velocity, if it is not too small. + // Otherwise use a fallback direction. + let relative_linvel = linvel1 - linvel2; + let mut tangent_relative_linvel = + relative_linvel - force_dir1 * (force_dir1.dot(&relative_linvel)); + let tangent_linvel_norm = tangent_relative_linvel.normalize_mut(); + let threshold: N::Element = na::convert(1.0e-4); + let use_fallback = tangent_linvel_norm.simd_lt(N::splat(threshold)); + let tangent_fallback = force_dir1.orthonormal_vector(); + + let tangent1 = tangent_fallback.select(use_fallback, tangent_relative_linvel); + let bitangent1 = force_dir1.cross(&tangent1); + + // Rotation such that: rot * tangent_fallback = tangent1 + // (when projected in the tangent plane.) This is needed to ensure the + // warmstart impulse has the correct orientation. Indeed, at frame n + 1, + // we need to reapply the same impulse as we did in frame n. However the + // basis on which the tangent impulse is expresses may change at each frame + // (because the the relative linvel may change direction at each frame). + // So we need this rotation to: + // - Project the impulse back to the "reference" basis at after friction is resolved. + // - Project the old impulse on the new basis before the friction is resolved. + let rot = na::UnitComplex::new_unchecked(na::Complex::new( + tangent1.dot(&tangent_fallback), + bitangent1.dot(&tangent_fallback), + )); + ([tangent1, bitangent1], rot) +} diff --git a/src/dynamics/solver/velocity_constraint_wide.rs b/src/dynamics/solver/velocity_constraint_wide.rs index d97602c..ec24e56 100644 --- a/src/dynamics/solver/velocity_constraint_wide.rs +++ b/src/dynamics/solver/velocity_constraint_wide.rs @@ -4,12 +4,41 @@ use crate::geometry::{ContactManifold, ContactManifoldIndex}; use crate::math::{ AngVector, AngularInertia, Point, Real, SimdReal, Vector, DIM, MAX_MANIFOLD_POINTS, SIMD_WIDTH, }; -use crate::utils::{WAngularInertia, WBasis, WCross, WDot}; +#[cfg(feature = "dim2")] +use crate::utils::WBasis; +use crate::utils::{WAngularInertia, WCross, WDot}; use num::Zero; use simba::simd::{SimdPartialOrd, SimdValue}; #[derive(Copy, Clone, Debug)] -pub(crate) struct WVelocityConstraintElementPart { +pub(crate) struct WVelocityConstraintTangentPart { + pub gcross1: [AngVector<SimdReal>; DIM - 1], + pub gcross2: [AngVector<SimdReal>; DIM - 1], + pub rhs: [SimdReal; DIM - 1], + #[cfg(feature = "dim2")] + pub impulse: [SimdReal; DIM - 1], + #[cfg(feature = "dim3")] + pub impulse: na::Vector2<SimdReal>, + pub r: [SimdReal; DIM - 1], +} + +impl WVelocityConstraintTangentPart { + pub fn zero() -> Self { + Self { + gcross1: [AngVector::zero(); DIM - 1], + gcross2: [AngVector::zero(); DIM - 1], + rhs: [SimdReal::zero(); DIM - 1], + #[cfg(feature = "dim2")] + impulse: [SimdReal::zero(); DIM - 1], + #[cfg(feature = "dim3")] + impulse: na::Vector2::zeros(), + r: [SimdReal::zero(); DIM - 1], + } + } +} + +#[derive(Copy, Clone, Debug)] +pub(crate) struct WVelocityConstraintNormalPart { pub gcross1: AngVector<SimdReal>, pub gcross2: AngVector<SimdReal>, pub rhs: SimdReal, @@ -17,7 +46,7 @@ pub(crate) struct WVelocityConstraintElementPart { pub r: SimdReal, } -impl WVelocityConstraintElementPart { +impl WVelocityConstraintNormalPart { pub fn zero() -> Self { Self { gcross1: AngVector::zero(), @@ -31,15 +60,15 @@ impl WVelocityConstraintElementPart { #[derive(Copy, Clone, Debug)] pub(crate) struct WVelocityConstraintElement { - pub normal_part: WVelocityConstraintElementPart, - pub tangent_parts: [WVelocityConstraintElementPart; DIM - 1], + pub normal_part: WVelocityConstraintNormalPart, + pub tangent_part: WVelocityConstraintTangentPart, } impl WVelocityConstraintElement { pub fn zero() -> Self { Self { - normal_part: WVelocityConstraintElementPart::zero(), - tangent_parts: [WVelocityConstraintElementPart::zero(); DIM - 1], + normal_part: WVelocityConstraintNormalPart::zero(), + tangent_part: WVelocityConstraintTangentPart::zero(), } } } @@ -47,6 +76,10 @@ impl WVelocityConstraintElement { #[derive(Copy, Clone, Debug)] pub(crate) struct WVelocityConstraint { pub dir1: Vector<SimdReal>, // Non-penetration force direction for the first body. + #[cfg(feature = "dim3")] + pub tangent1: Vector<SimdReal>, // One of the friction force directions. + #[cfg(feature = "dim3")] + pub tangent_rot1: na::UnitComplex<SimdReal>, // Orientation of the tangent basis wrt. the reference basis. pub elements: [WVelocityConstraintElement; MAX_MANIFOLD_POINTS], pub num_contacts: u8, pub im1: SimdReal, @@ -108,6 +141,12 @@ impl WVelocityConstraint { let warmstart_coeff = warmstart_multiplier * SimdReal::splat(params.warmstart_coeff); let num_active_contacts = manifolds[0].data.num_active_contacts(); + #[cfg(feature = "dim2")] + let tangents1 = force_dir1.orthonormal_basis(); + #[cfg(feature = "dim3")] + let (tangents1, tangent_rot1) = + super::compute_tangent_contact_directions(&force_dir1, &linvel1, &linvel2); + for l in (0..num_active_contacts).step_by(MAX_MANIFOLD_POINTS) { let manifold_points = array![|ii| &manifolds[ii].data.solver_contacts[l..num_active_contacts]; SIMD_WIDTH @@ -116,6 +155,10 @@ impl WVelocityConstraint { let mut constraint = WVelocityConstraint { dir1: force_dir1, + #[cfg(feature = "dim3")] + tangent1: tangents1[0], + #[cfg(feature = "dim3")] + tangent_rot1, elements: [WVelocityConstraintElement::zero(); MAX_MANIFOLD_POINTS], im1, im2, @@ -169,7 +212,7 @@ impl WVelocityConstraint { rhs += dist.simd_min(SimdReal::zero()) * (velocity_based_erp_inv_dt * is_resting); - constraint.elements[k].normal_part = WVelocityConstraintElementPart { + constraint.elements[k].normal_part = WVelocityConstraintNormalPart { gcross1, gcross2, rhs, @@ -179,31 +222,30 @@ impl WVelocityConstraint { } // tangent parts. - let tangents1 = force_dir1.orthonormal_basis(); + #[cfg(feature = "dim2")] + let impulse = [SimdReal::from( + array![|ii| manifold_points[ii][k].data.tangent_impulse; SIMD_WIDTH], + )]; - for j in 0..DIM - 1 { - #[cfg(feature = "dim2")] - let impulse = SimdReal::from( + #[cfg(feature = "dim3")] + let impulse = tangent_rot1 + * na::Vector2::from( array![|ii| manifold_points[ii][k].data.tangent_impulse; SIMD_WIDTH], ); - #[cfg(feature = "dim3")] - let impulse = SimdReal::from( - array![|ii| manifold_points[ii][k].data.tangent_impulse[j]; SIMD_WIDTH], - ); + constraint.elements[k].tangent_part.impulse = impulse; + + for j in 0..DIM - 1 { let gcross1 = ii1.transform_vector(dp1.gcross(tangents1[j])); let gcross2 = ii2.transform_vector(dp2.gcross(-tangents1[j])); let r = SimdReal::splat(1.0) / (im1 + im2 + gcross1.gdot(gcross1) + gcross2.gdot(gcross2)); let rhs = (vel1 - vel2 + tangent_velocity).dot(&tangents1[j]); - constraint.elements[k].tangent_parts[j] = WVelocityConstraintElementPart { - gcross1, - gcross2, - rhs, - impulse: impulse * warmstart_coeff, - r, - }; + constraint.elements[k].tangent_part.gcross1[j] = gcross1; + constraint.elements[k].tangent_part.gcross2[j] = gcross2; + constraint.elements[k].tangent_part.rhs[j] = rhs; + constraint.elements[k].tangent_part.r[j] = r; } } @@ -235,6 +277,11 @@ impl WVelocityConstraint { ), }; + #[cfg(feature = "dim3")] + let tangents1 = [self.tangent1, self.dir1.cross(&self.tangent1)]; + #[cfg(feature = "dim2")] + let tangents1 = self.dir1.orthonormal_basis(); + for i in 0..self.num_contacts as usize { let elt = &self.elements[i].normal_part; mj_lambda1.linear += self.dir1 * (self.im1 * elt.impulse); @@ -243,16 +290,13 @@ impl WVelocityConstraint { mj_lambda2.linear += self.dir1 * (-self.im2 * elt.impulse); mj_lambda2.angular += elt.gcross2 * elt.impulse; - // FIXME: move this out of the for loop? - let tangents1 = self.dir1.orthonormal_basis(); - for j in 0..DIM - 1 { - let elt = &self.elements[i].tangent_parts[j]; - mj_lambda1.linear += tangents1[j] * (self.im1 * elt.impulse); - mj_lambda1.angular += elt.gcross1 * elt.impulse; + let elt = &self.elements[i].tangent_part; + mj_lambda1.linear += tangents1[j] * (self.im1 * elt.impulse[j]); + mj_lambda1.angular += elt.gcross1[j] * elt.impulse[j]; - mj_lambda2.linear += tangents1[j] * (-self.im2 * elt.impulse); - mj_lambda2.angular += elt.gcross2 * elt.impulse; + mj_lambda2.linear += tangents1[j] * (-self.im2 * elt.impulse[j]); + mj_lambda2.angular += elt.gcross2[j] * elt.impulse[j]; } } @@ -278,36 +322,71 @@ impl WVelocityConstraint { let mut mj_lambda2 = DeltaVel { linear: Vector::from( - array![ |ii| mj_lambdas[ self.mj_lambda2[ii] as usize].linear; SIMD_WIDTH], + array![|ii| mj_lambdas[ self.mj_lambda2[ii] as usize].linear; SIMD_WIDTH], ), angular: AngVector::from( - array![ |ii| mj_lambdas[ self.mj_lambda2[ii] as usize].angular; SIMD_WIDTH], + array![|ii| mj_lambdas[ self.mj_lambda2[ii] as usize].angular; SIMD_WIDTH], ), }; - // Solve friction first. + // Solve friction. + #[cfg(feature = "dim3")] + let bitangent1 = self.dir1.cross(&self.tangent1); + #[cfg(feature = "dim2")] + let tangents1 = self.dir1.orthonormal_basis(); + + #[cfg(feature = "dim2")] for i in 0..self.num_contacts as usize { - // FIXME: move this out of the for loop? - let tangents1 = self.dir1.orthonormal_basis(); let normal_elt = &self.elements[i].normal_part; - for j in 0..DIM - 1 { - let elt = &mut self.elements[i].tangent_parts[j]; - let dimpulse = tangents1[j].dot(&mj_lambda1.linear) - + elt.gcross1.gdot(mj_lambda1.angular) - - tangents1[j].dot(&mj_lambda2.linear) - + elt.gcross2.gdot(mj_lambda2.angular) - + elt.rhs; - let limit = self.limit * normal_elt.impulse; - let new_impulse = (elt.impulse - elt.r * dimpulse).simd_clamp(-limit, limit); - let dlambda = new_impulse - elt.impulse; - elt.impulse = new_impulse; - - mj_lambda1.linear += tangents1[j] * (self.im1 * dlambda); - mj_lambda1.angular += elt.gcross1 * dlambda; - mj_lambda2.linear += tangents1[j] * (-self.im2 * dlambda); - mj_lambda2.angular += elt.gcross2 * dlambda; - } + let elt = &mut self.elements[i].tangent_part; + let dimpulse = tangents1[0].dot(&mj_lambda1.linear) + + elt.gcross1[0].gdot(mj_lambda1.angular) + - tangents1[0].dot(&mj_lambda2.linear) + + elt.gcross2[0].gdot(mj_lambda2.angular) + + elt.rhs[0]; + let limit = self.limit * normal_elt.impulse; + let new_impulse = (elt.impulse[0] - elt.r[0] * dimpulse).simd_clamp(-limit, limit); + let dlambda = new_impulse - elt.impulse[0]; + elt.impulse[0] = new_impulse; + + mj_lambda1.linear += tangents1[0] * (self.im1 * dlambda); + mj_lambda1.angular += elt.gcross1[0] * dlambda; + mj_lambda2.linear += tangents1[0] * (-self.im2 * dlambda); + mj_lambda2.angular += elt.gcross2[0] * dlambda; + } + + #[cfg(feature = "dim3")] + for i in 0..self.num_contacts as usize { + let limit = self.limit * self.elements[i].normal_part.impulse; + let elts = &mut self.elements[i].tangent_part; + + let dimpulse_0 = self.tangent1.dot(&mj_lambda1.linear) + + elts.gcross1[0].gdot(mj_lambda1.angular) + - self.tangent1.dot(&mj_lambda2.linear) + + elts.gcross2[0].gdot(mj_lambda2.angular) + + elts.rhs[0]; |
