diff options
| author | Sébastien Crozet <sebcrozet@dimforge.com> | 2024-03-17 21:20:18 +0100 |
|---|---|---|
| committer | Sébastien Crozet <sebcrozet@dimforge.com> | 2024-03-17 21:24:28 +0100 |
| commit | ecd308338b189ab569816a38a03e3f8b89669dde (patch) | |
| tree | fa612abff2f23ea6a5ff04c64c07296d9fb065c8 /src/dynamics | |
| parent | da92e5c2837b27433286cf0dd9d887fd44dda254 (diff) | |
| download | rapier-bevy-glam.tar.gz rapier-bevy-glam.tar.bz2 rapier-bevy-glam.zip | |
feat: start experimenting with a glam/bevy versionbevy-glam
Diffstat (limited to 'src/dynamics')
53 files changed, 2351 insertions, 2210 deletions
diff --git a/src/dynamics/ccd/ccd_solver.rs b/src/dynamics/ccd/ccd_solver.rs index 79c4495..064c044 100644 --- a/src/dynamics/ccd/ccd_solver.rs +++ b/src/dynamics/ccd/ccd_solver.rs @@ -1,7 +1,7 @@ use super::TOIEntry; use crate::dynamics::{IslandManager, RigidBodyHandle, RigidBodySet}; use crate::geometry::{ColliderParent, ColliderSet, CollisionEvent, NarrowPhase}; -use crate::math::Real; +use crate::math::*; use crate::parry::utils::SortedPair; use crate::pipeline::{EventHandler, QueryPipeline, QueryPipelineMode}; use crate::prelude::{ActiveEvents, CollisionEventFlags}; @@ -92,14 +92,14 @@ impl CCDSolver { for handle in islands.active_dynamic_bodies() { let rb = bodies.index_mut_internal(*handle); - if rb.ccd.ccd_enabled { + if rb.ccd.enabled { let forces = if include_forces { Some(&rb.forces) } else { None }; let moving_fast = rb.ccd.is_moving_fast(dt, &rb.integrated_vels, forces); - rb.ccd.ccd_active = moving_fast; + rb.ccd.active = moving_fast; ccd_active = ccd_active || moving_fast; } } @@ -129,7 +129,7 @@ impl CCDSolver { for handle in islands.active_dynamic_bodies() { let rb1 = &bodies[*handle]; - if rb1.ccd.ccd_active { + if rb1.ccd.active { let predicted_body_pos1 = rb1.pos.integrate_forces_and_velocities( dt, &rb1.forces, @@ -161,10 +161,7 @@ impl CCDSolver { } if pairs_seen - .insert( - SortedPair::new(ch1.into_raw_parts().0, ch2.into_raw_parts().0), - (), - ) + .insert(SortedPair::new(ch1.index(), ch2.index()), ()) .is_none() { let co1 = &colliders[*ch1]; @@ -253,7 +250,7 @@ impl CCDSolver { for handle in islands.active_dynamic_bodies() { let rb1 = &bodies[*handle]; - if rb1.ccd.ccd_active { + if rb1.ccd.active { let predicted_body_pos1 = rb1.pos.integrate_forces_and_velocities( dt, &rb1.forces, @@ -261,8 +258,8 @@ impl CCDSolver { &rb1.mprops, ); - for ch1 in &rb1.colliders.0 { - let co1 = &colliders[*ch1]; + for ch1 in rb1.colliders.0.iter().copied() { + let co1 = &colliders[ch1]; let co_parent1 = co1 .parent .as_ref() @@ -275,19 +272,16 @@ impl CCDSolver { self.query_pipeline .colliders_with_aabb_intersecting_aabb(&aabb1, |ch2| { - if *ch1 == *ch2 { + if ch1 == *ch2 { // Ignore self-intersection. return true; } if pairs_seen - .insert( - SortedPair::new(ch1.into_raw_parts().0, ch2.into_raw_parts().0), - (), - ) + .insert(SortedPair::new(ch1.index(), ch2.index()), ()) .is_none() { - let co1 = &colliders[*ch1]; + let co1 = &colliders[ch1]; let co2 = &colliders[*ch2]; let bh1 = co1.parent.map(|p| p.handle); @@ -301,7 +295,7 @@ impl CCDSolver { } let smallest_dist = narrow_phase - .contact_pair(*ch1, *ch2) + .contact_pair(ch1, *ch2) .and_then(|p| p.find_deepest_contact()) .map(|c| c.1.dist) .unwrap_or(0.0); @@ -311,7 +305,7 @@ impl CCDSolver { if let Some(toi) = TOIEntry::try_from_colliders( self.query_pipeline.query_dispatcher(), - *ch1, + ch1, *ch2, co1, co2, @@ -362,12 +356,10 @@ impl CCDSolver { let rb2 = toi.b2.and_then(|b| bodies.get(b)); let mut colliders_to_check = Vec::new(); - let should_freeze1 = rb1.is_some() - && rb1.unwrap().ccd.ccd_active - && !frozen.contains_key(&toi.b1.unwrap()); - let should_freeze2 = rb2.is_some() - && rb2.unwrap().ccd.ccd_active - && !frozen.contains_key(&toi.b2.unwrap()); + let should_freeze1 = + rb1.is_some() && rb1.unwrap().ccd.active && !frozen.contains_key(&toi.b1.unwrap()); + let should_freeze2 = + rb2.is_some() && rb2.unwrap().ccd.active && !frozen.contains_key(&toi.b2.unwrap()); if !should_freeze1 && !should_freeze2 { continue; @@ -400,8 +392,8 @@ impl CCDSolver { // NOTE: the 1 and 2 indices (e.g., `ch1`, `ch2`) bellow are unrelated to the // ones we used above. - for ch1 in &colliders_to_check { - let co1 = &colliders[*ch1]; + for ch1 in colliders_to_check.iter().copied() { + let co1 = &colliders[ch1]; let co1_parent = co1.parent.as_ref().unwrap(); let rb1 = &bodies[co1_parent.handle]; @@ -428,23 +420,22 @@ impl CCDSolver { let rb1 = bh1.and_then(|h| bodies.get(h)); let rb2 = bh2.and_then(|h| bodies.get(h)); - if (frozen1.is_some() || !rb1.map(|b| b.ccd.ccd_active).unwrap_or(false)) - && (frozen2.is_some() - || !rb2.map(|b| b.ccd.ccd_active).unwrap_or(false)) + if (frozen1.is_some() || !rb1.map(|b| b.ccd.active).unwrap_or(false)) + && (frozen2.is_some() || !rb2.map(|b| b.ccd.active).unwrap_or(false)) { // We already did a resweep. return true; } let smallest_dist = narrow_phase - .contact_pair(*ch1, *ch2) + .contact_pair(ch1, *ch2) .and_then(|p| p.find_deepest_contact()) .map(|c| c.1.dist) .unwrap_or(0.0); if let Some(toi) = TOIEntry::try_from_colliders( self.query_pipeline.query_dispatcher(), - *ch1, + ch1, *ch2, co1, co2, diff --git a/src/dynamics/ccd/toi_entry.rs b/src/dynamics/ccd/toi_entry.rs index 719f3c5..3f4f5f2 100644 --- a/src/dynamics/ccd/toi_entry.rs +++ b/src/dynamics/ccd/toi_entry.rs @@ -1,6 +1,6 @@ use crate::dynamics::{RigidBody, RigidBodyHandle}; use crate::geometry::{Collider, ColliderHandle}; -use crate::math::Real; +use crate::math::*; use parry::query::{NonlinearRigidMotion, QueryDispatcher}; #[derive(Copy, Clone, Debug)] @@ -57,13 +57,13 @@ impl TOIEntry { } let linvel1 = frozen1.is_none() as u32 as Real - * rb1.map(|b| b.integrated_vels.linvel).unwrap_or(na::zero()); + * rb1.map(|b| b.integrated_vels.linvel).unwrap_or_default(); let linvel2 = frozen2.is_none() as u32 as Real - * rb2.map(|b| b.integrated_vels.linvel).unwrap_or(na::zero()); + * rb2.map(|b| b.integrated_vels.linvel).unwrap_or_default(); let angvel1 = frozen1.is_none() as u32 as Real - * rb1.map(|b| b.integrated_vels.angvel).unwrap_or(na::zero()); + * rb1.map(|b| b.integrated_vels.angvel).unwrap_or_default(); let angvel2 = frozen2.is_none() as u32 as Real - * rb2.map(|b| b.integrated_vels.angvel).unwrap_or(na::zero()); + * rb2.map(|b| b.integrated_vels.angvel).unwrap_or_default(); #[cfg(feature = "dim2")] let vel12 = (linvel2 - linvel1).norm() @@ -154,7 +154,7 @@ impl TOIEntry { } fn body_motion(rb: &RigidBody) -> NonlinearRigidMotion { - if rb.ccd.ccd_active { + if rb.ccd.active { NonlinearRigidMotion::new( rb.pos.position, rb.mprops.local_mprops.local_com, diff --git a/src/dynamics/coefficient_combine_rule.rs b/src/dynamics/coefficient_combine_rule.rs index 9f99b7d..84094bf 100644 --- a/src/dynamics/coefficient_combine_rule.rs +++ b/src/dynamics/coefficient_combine_rule.rs @@ -1,4 +1,7 @@ -use crate::math::Real; +use crate::math::*; + +#[cfg(feature = "bevy")] +use bevy::prelude::{Component, Reflect, ReflectComponent}; /// Rules used to combine two coefficients. /// @@ -9,6 +12,11 @@ use crate::math::Real; /// actually used is given by `max(first_combine_rule as usize, second_combine_rule as usize)`. #[derive(Default, Copy, Clone, Debug, PartialEq, Eq)] #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] +#[cfg_attr( + feature = "bevy", + derive(Component, Reflect), + reflect(Component, PartialEq) +)] pub enum CoefficientCombineRule { /// The two coefficients are averaged. #[default] diff --git a/src/dynamics/integration_parameters.rs b/src/dynamics/integration_parameters.rs index 13b3fde..ea290fc 100644 --- a/src/dynamics/integration_parameters.rs +++ b/src/dynamics/integration_parameters.rs @@ -1,4 +1,4 @@ -use crate::math::Real; +use crate::math::*; use std::num::NonZeroUsize; /// Parameters for a time-step of the physics engine. diff --git a/src/dynamics/island_manager.rs b/src/dynamics/island_manager.rs index 8f18941..1e720fc 100644 --- a/src/dynamics/island_manager.rs +++ b/src/dynamics/island_manager.rs @@ -1,9 +1,9 @@ use crate::dynamics::{ - ImpulseJointSet, MultibodyJointSet, RigidBodyActivation, RigidBodyChanges, RigidBodyColliders, - RigidBodyHandle, RigidBodyIds, RigidBodySet, RigidBodyType, RigidBodyVelocity, + ImpulseJointSet, MultibodyJointSet, RigidBodyChanges, RigidBodyColliders, RigidBodyHandle, + RigidBodyIds, RigidBodySet, RigidBodyType, SleepState, Velocity, }; use crate::geometry::{ColliderSet, NarrowPhase}; -use crate::math::Real; +use crate::math::*; use crate::utils::SimdDot; /// Structure responsible for maintaining the set of active rigid-bodies, and @@ -317,14 +317,14 @@ impl IslandManager { for handle in &self.can_sleep { let rb = bodies.index_mut_internal(*handle); if rb.activation.sleeping { - rb.vels = RigidBodyVelocity::zero(); + rb.vels = Velocity::zero(); rb.activation.sleep(); } } } } -fn update_energy(activation: &mut RigidBodyActivation, sq_linvel: Real, sq_angvel: Real, dt: Real) { +fn update_energy(activation: &mut SleepState, sq_linvel: Real, sq_angvel: Real, dt: Real) { if sq_linvel < activation.linear_threshold * activation.linear_threshold.abs() && sq_angvel < activation.angular_threshold * activation.angular_threshold.abs() { diff --git a/src/dynamics/joint/fixed_joint.rs b/src/dynamics/joint/fixed_joint.rs index 2bb2f64..f5a0250 100644 --- a/src/dynamics/joint/fixed_joint.rs +++ b/src/dynamics/joint/fixed_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder, JointAxesMask}; -use crate::math::{Isometry, Point, Real}; +use crate::math::*; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] #[derive(Copy, Clone, Debug, PartialEq)] @@ -37,48 +37,48 @@ impl FixedJoint { /// The joint’s frame, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_frame1(&self) -> &Isometry<Real> { + pub fn local_frame1(&self) -> &Isometry { &self.data.local_frame1 } /// Sets the joint’s frame, expressed in the first rigid-body’s local-space. - pub fn set_local_frame1(&mut self, local_frame: Isometry<Real>) -> &mut Self { + pub fn set_local_frame1(&mut self, local_frame: Isometry) -> &mut Self { self.data.set_local_frame1(local_frame); self } /// The joint’s frame, expressed in the second rigid-body’s local-space. #[must_use] - pub fn local_frame2(&self) -> &Isometry<Real> { + pub fn local_frame2(&self) -> &Isometry { &self.data.local_frame2 } /// Sets joint’s frame, expressed in the second rigid-body’s local-space. - pub fn set_local_frame2(&mut self, local_frame: Isometry<Real>) -> &mut Self { + pub fn set_local_frame2(&mut self, local_frame: Isometry) -> &mut Self { self.data.set_local_frame2(local_frame); self } /// The joint’s anchor, expressed in the local-space of the first rigid-body. #[must_use] - pub fn local_anchor1(&self) -> Point<Real> { + pub fn local_anchor1(&self) -> Point { self.data.local_anchor1() } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. - pub fn set_local_anchor1(&mut self, anchor1: Point<Real>) -> &mut Self { + pub fn set_local_anchor1(&mut self, anchor1: Point) -> &mut Self { self.data.set_local_anchor1(anchor1); self } /// The joint’s anchor, expressed in the local-space of the second rigid-body. #[must_use] - pub fn local_anchor2(&self) -> Point<Real> { + pub fn local_anchor2(&self) -> Point { self.data.local_anchor2() } /// Sets the joint’s anchor, expressed in the local-space of the second rigid-body. - pub fn set_local_anchor2(&mut self, anchor2: Point<Real>) -> &mut Self { + pub fn set_local_anchor2(&mut self, anchor2: Point) -> &mut Self { self.data.set_local_anchor2(anchor2); self } @@ -110,28 +110,28 @@ impl FixedJointBuilder { /// Sets the joint’s frame, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_frame1(mut self, local_frame: Isometry<Real>) -> Self { + pub fn local_frame1(mut self, local_frame: Isometry) -> Self { self.0.set_local_frame1(local_frame); self } /// Sets joint’s frame, expressed in the second rigid-body’s local-space. #[must_use] - pub fn local_frame2(mut self, local_frame: Isometry<Real>) -> Self { + pub fn local_frame2(mut self, local_frame: Isometry) -> Self { self.0.set_local_frame2(local_frame); self } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. #[must_use] - pub fn local_anchor1(mut self, anchor1: Point<Real>) -> Self { + pub fn local_anchor1(mut self, anchor1: Point) -> Self { self.0.set_local_anchor1(anchor1); self } /// Sets the joint’s anchor, expressed in the local-space of the second rigid-body. #[must_use] - pub fn local_anchor2(mut self, anchor2: Point<Real>) -> Self { + pub fn local_anchor2(mut self, anchor2: Point) -> Self { self.0.set_local_anchor2(anchor2); self } diff --git a/src/dynamics/joint/generic_joint.rs b/src/dynamics/joint/generic_joint.rs index 76a7fe1..8773b2c 100644 --- a/src/dynamics/joint/generic_joint.rs +++ b/src/dynamics/joint/generic_joint.rs @@ -2,7 +2,7 @@ use crate::dynamics::solver::MotorParameters; use crate::dynamics::{FixedJoint, MotorModel, PrismaticJoint, RevoluteJoint, RopeJoint}; -use crate::math::{Isometry, Point, Real, Rotation, UnitVector, Vector, SPATIAL_DIM}; +use crate::math::*; use crate::utils::{SimdBasis, SimdRealCopy}; #[cfg(feature = "dim3")] @@ -212,9 +212,9 @@ pub enum JointEnabled { /// A generic joint. pub struct GenericJoint { /// The joint’s frame, expressed in the first rigid-body’s local-space. - pub local_frame1: Isometry<Real>, + pub local_frame1: Isometry, /// The joint’s frame, expressed in the second rigid-body’s local-space. - pub local_frame2: Isometry<Real>, + pub local_frame2: Isometry, /// The degrees-of-freedoms locked by this joint. pub locked_axes: JointAxesMask, /// The degrees-of-freedoms limited by this joint. @@ -280,23 +280,20 @@ impl GenericJoint { } #[doc(hidden)] - pub fn complete_ang_frame(axis: UnitVector<Real>) -> Rotation<Real> { + pub fn complete_ang_frame(axis: UnitVector) -> Rotation { let basis = axis.orthonormal_basis(); #[cfg(feature = "dim2")] { - use na::{Matrix2, Rotation2, UnitComplex}; - let mat = Matrix2::from_columns(&[axis.into_inner(), basis[0]]); - let rotmat = Rotation2::from_matrix_unchecked(mat); - UnitComplex::from_rotation_matrix(&rotmat) + let mat = Matrix::from_columns(&[axis.into_inner(), basis[0]]); + Rotation::from_matrix_unchecked(mat) } #[cfg(feature = "dim3")] { - use na::{Matrix3, Rotation3, UnitQuaternion}; - let mat = Matrix3::from_columns(&[axis.into_inner(), basis[0], basis[1]]); - let rotmat = Rotation3::from_matrix_unchecked(mat); - UnitQuaternion::from_rotation_matrix(&rotmat) + let mat = Matrix::from_columns(&[axis.into_inner(), basis[0], basis[1]]); + let rotmat = RotationMatrix::from_matrix_unchecked(mat); + Rotation::from_rotation_matrix(&rotmat) } } @@ -328,62 +325,62 @@ impl GenericJoint { } /// Sets the joint’s frame, expressed in the first rigid-body’s local-space. - pub fn set_local_frame1(&mut self, local_frame: Isometry<Real>) -> &mut Self { + pub fn set_local_frame1(&mut self, local_frame: Isometry) -> &mut Self { self.local_frame1 = local_frame; self } /// Sets the joint’s frame, expressed in the second rigid-body’s local-space. - pub fn set_local_frame2(&mut self, local_frame: Isometry<Real>) -> &mut Self { + pub fn set_local_frame2(&mut self, local_frame: Isometry) -> &mut Self { self.local_frame2 = local_frame; self } /// The principal (local X) axis of this joint, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_axis1(&self) -> UnitVector<Real> { - self.local_frame1 * Vector::x_axis() + pub fn local_axis1(&self) -> UnitVector { + self.local_frame1.rotation * Vector::x_axis() } /// Sets the principal (local X) axis of this joint, expressed in the first rigid-body’s local-space. - pub fn set_local_axis1(&mut self, local_axis: UnitVector<Real>) -> &mut Self { + pub fn set_local_axis1(&mut self, local_axis: UnitVector) -> &mut Self { self.local_frame1.rotation = Self::complete_ang_frame(local_axis); self } /// The principal (local X) axis of this joint, expressed in the second rigid-body’s local-space. #[must_use] - pub fn local_axis2(&self) -> UnitVector<Real> { - self.local_frame2 * Vector::x_axis() + pub fn local_axis2(&self) -> UnitVector { + self.local_frame2.rotation * Vector::x_axis() } /// Sets the principal (local X) axis of this joint, expressed in the second rigid-body’s local-space. - pub fn set_local_axis2(&mut self, local_axis: UnitVector<Real>) -> &mut Self { + pub fn set_local_axis2(&mut self, local_axis: UnitVector) -> &mut Self { self.local_frame2.rotation = Self::complete_ang_frame(local_axis); self } /// The anchor of this joint, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_anchor1(&self) -> Point<Real> { - self.local_frame1.translation.vector.into() + pub fn local_anchor1(&self) -> Point { + self.local_frame1.translation.into_vector().into() } /// Sets anchor of this joint, expressed in the first rigid-body’s local-space. - pub fn set_local_anchor1(&mut self, anchor1: Point<Real>) -> &mut Self { - self.local_frame1.translation.vector = anchor1.coords; + pub fn set_local_anchor1(&mut self, anchor1: Point) -> &mut Self { + *self.local_frame1.translation.as_vector_mut() = anchor1.into_vector(); self } /// The anchor of this joint, expressed in the second rigid-body’s local-space. #[must_use] - pub fn local_anchor2(&self) -> Point<Real> { - self.local_frame2.translation.vector.into() + pub fn local_anchor2(&self) -> Point { + self.local_frame2.translation.into_vector().into() } /// Sets anchor of this joint, expressed in the second rigid-body’s local-space. - pub fn set_local_anchor2(&mut self, anchor2: Point<Real>) -> &mut Self { - self.local_frame2.translation.vector = anchor2.coords; + pub fn set_local_anchor2(&mut self, anchor2: Point) -> &mut Self { + *self.local_frame2.translation.as_vector_mut() = anchor2.into_vector(); self } @@ -589,42 +586,42 @@ impl GenericJointBuilder { /// Sets the joint’s frame, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_frame1(mut self, local_frame: Isometry<Real>) -> Self { + pub fn local_frame1(mut |
