diff options
| author | Sébastien Crozet <sebcrozet@dimforge.com> | 2024-04-28 18:23:30 +0200 |
|---|---|---|
| committer | Sébastien Crozet <sebastien@crozet.re> | 2024-04-30 23:10:46 +0200 |
| commit | 0a9153e273dc0bdd4ba6443bd7f4dcfc671faac3 (patch) | |
| tree | 08433a2e846051726d577cbf67e3fb932e446bc5 | |
| parent | 929aa6b9259b95d48cf6a84df40486132b21f088 (diff) | |
| download | rapier-0a9153e273dc0bdd4ba6443bd7f4dcfc671faac3.tar.gz rapier-0a9153e273dc0bdd4ba6443bd7f4dcfc671faac3.tar.bz2 rapier-0a9153e273dc0bdd4ba6443bd7f4dcfc671faac3.zip | |
chore: clippy fixes
29 files changed, 38 insertions, 52 deletions
diff --git a/benchmarks2d/vertical_stacks2.rs b/benchmarks2d/vertical_stacks2.rs index aaf7933..15552ba 100644 --- a/benchmarks2d/vertical_stacks2.rs +++ b/benchmarks2d/vertical_stacks2.rs @@ -10,15 +10,14 @@ pub fn init_world(testbed: &mut Testbed) { let impulse_joints = ImpulseJointSet::new(); let multibody_joints = MultibodyJointSet::new(); - - let rad = 0.5; // 50.0 / 2.0; // 0.5; - let rad = 50.0 / 2.0; // 0.5; + let num = 80; + let rad = 0.5; /* * Ground */ let ground_size = num as f32 * rad * 10.0; - let ground_thickness = 25.0; + let ground_thickness = 1.0; let rigid_body = RigidBodyBuilder::fixed(); let ground_handle = bodies.insert(rigid_body); @@ -31,7 +30,7 @@ pub fn init_world(testbed: &mut Testbed) { let shiftx_centerx = [ (rad * 2.0 + 0.0002, -(num as f32) * rad * 2.0 * 1.5), - (rad * 2.0 + rad, num as f32 * rad * 2.0 * 1.5), + (rad * 2.0 + rad, num as f32 * rad * 2.0 * 1.5), ]; for (shiftx, centerx) in shiftx_centerx { diff --git a/crates/rapier2d-f64/Cargo.toml b/crates/rapier2d-f64/Cargo.toml index fc0d7f4..cb7baec 100644 --- a/crates/rapier2d-f64/Cargo.toml +++ b/crates/rapier2d-f64/Cargo.toml @@ -52,7 +52,7 @@ vec_map = { version = "0.8", optional = true } instant = { version = "0.1", features = ["now"], optional = true } num-traits = "0.2" nalgebra = "0.32" -parry2d-f64 = "0.13.1" +parry2d-f64 = "0.14.0" simba = "0.8" approx = "0.5" rayon = { version = "1", optional = true } diff --git a/crates/rapier2d/Cargo.toml b/crates/rapier2d/Cargo.toml index 891cbb5..5c86692 100644 --- a/crates/rapier2d/Cargo.toml +++ b/crates/rapier2d/Cargo.toml @@ -52,7 +52,7 @@ vec_map = { version = "0.8", optional = true } instant = { version = "0.1", features = ["now"], optional = true } num-traits = "0.2" nalgebra = "0.32" -parry2d = "0.13.1" +parry2d = "0.14.0" simba = "0.8" approx = "0.5" rayon = { version = "1", optional = true } diff --git a/crates/rapier3d-f64/Cargo.toml b/crates/rapier3d-f64/Cargo.toml index a1279fd..c2ed4b6 100644 --- a/crates/rapier3d-f64/Cargo.toml +++ b/crates/rapier3d-f64/Cargo.toml @@ -52,7 +52,7 @@ vec_map = { version = "0.8", optional = true } instant = { version = "0.1", features = ["now"], optional = true } num-traits = "0.2" nalgebra = "0.32" -parry3d-f64 = "0.13.1" +parry3d-f64 = "0.14.0" simba = "0.8" approx = "0.5" rayon = { version = "1", optional = true } diff --git a/crates/rapier3d/Cargo.toml b/crates/rapier3d/Cargo.toml index ee33214..b5276e8 100644 --- a/crates/rapier3d/Cargo.toml +++ b/crates/rapier3d/Cargo.toml @@ -52,7 +52,7 @@ vec_map = { version = "0.8", optional = true } instant = { version = "0.1", features = ["now"], optional = true } num-traits = "0.2" nalgebra = "0.32" -parry3d = "0.13.1" +parry3d = "0.14.0" simba = "0.8" approx = "0.5" rayon = { version = "1", optional = true } diff --git a/examples2d/s2d_arch.rs b/examples2d/s2d_arch.rs index ea92e66..5b935e9 100644 --- a/examples2d/s2d_arch.rs +++ b/examples2d/s2d_arch.rs @@ -10,6 +10,7 @@ pub fn init_world(testbed: &mut Testbed) { let impulse_joints = ImpulseJointSet::new(); let multibody_joints = MultibodyJointSet::new(); + #[allow(clippy::excessive_precision)] let mut ps1 = [ Point::new(16.0, 0.0), Point::new(14.93803712795643, 5.133601056842984), @@ -22,6 +23,7 @@ pub fn init_world(testbed: &mut Testbed) { Point::new(2.405937953536585, 39.09554102558315), ]; + #[allow(clippy::excessive_precision)] let mut ps2 = [ Point::new(24.0, 0.0), Point::new(22.33619528222415, 6.02299846205841), diff --git a/examples2d/s2d_ball_and_chain.rs b/examples2d/s2d_ball_and_chain.rs index cbc1a1f..29e0d87 100644 --- a/examples2d/s2d_ball_and_chain.rs +++ b/examples2d/s2d_ball_and_chain.rs @@ -24,7 +24,7 @@ pub fn init_world(testbed: &mut Testbed) { let friction = 0.6; let capsule = ColliderBuilder::capsule_x(hx, 0.125) .friction(friction) - .density(20.0); + .density(density); let mut prev = ground; for i in 0..count { @@ -55,7 +55,7 @@ pub fn init_world(testbed: &mut Testbed) { let handle = bodies.insert(rigid_body); let collider = ColliderBuilder::ball(radius) .friction(friction) - .density(20.0); + .density(density); colliders.insert_with_parent(collider, handle, &mut bodies); let pivot = point![(2.0 * count as f32) * hx, count as f32 * hx]; @@ -64,7 +64,6 @@ pub fn init_world(testbed: &mut Testbed) { .local_anchor2(bodies[handle].position().inverse_transform_point(&pivot)) .contacts_enabled(false); impulse_joints.insert(prev, handle, joint, true); - prev = handle; /* * Set up the testbed. diff --git a/examples2d/s2d_bridge.rs b/examples2d/s2d_bridge.rs index 712997e..ab9c96f 100644 --- a/examples2d/s2d_bridge.rs +++ b/examples2d/s2d_bridge.rs @@ -29,7 +29,7 @@ pub fn init_world(testbed: &mut Testbed) { .angular_damping(0.1) .translation(vector![x_base + 0.5 + 1.0 * i as f32, 20.0]); let handle = bodies.insert(rigid_body); - let collider = ColliderBuilder::cuboid(0.5, 0.125).density(20.0); + let collider = ColliderBuilder::cuboid(0.5, 0.125).density(density); colliders.insert_with_parent(collider, handle, &mut bodies); let pivot = point![x_base + 1.0 * i as f32, 20.0]; diff --git a/examples2d/s2d_card_house.rs b/examples2d/s2d_card_house.rs index 0862062..5e2c5dc 100644 --- a/examples2d/s2d_card_house.rs +++ b/examples2d/s2d_card_house.rs @@ -10,7 +10,6 @@ pub fn init_world(testbed: &mut Testbed) { let impulse_joints = ImpulseJointSet::new(); let multibody_joints = MultibodyJointSet::new(); - let extent = 1.0; let friction = 0.7; /* diff --git a/examples2d/s2d_confined.rs b/examples2d/s2d_confined.rs index 8b75a3d..ee54408 100644 --- a/examples2d/s2d_confined.rs +++ b/examples2d/s2d_confined.rs @@ -38,13 +38,13 @@ pub fn init_world(testbed: &mut Testbed) { /* * Create the spheres */ - let mut row = 0; + let mut row; let mut count = 0; let mut column = 0; while count < max_count { row = 0; - for i in 0..grid_count { + for _ in 0..grid_count { let x = -8.75 + column as f32 * 18.0 / (grid_count as f32); let y = 1.5 + row as f32 * 18.0 / (grid_count as f32); let body = RigidBodyBuilder::dynamic() diff --git a/examples2d/s2d_far_pyramid.rs b/examples2d/s2d_far_pyramid.rs index f5e34c0..7948731 100644 --- a/examples2d/s2d_far_pyramid.rs +++ b/examples2d/s2d_far_pyramid.rs @@ -11,7 +11,6 @@ pub fn init_world(testbed: &mut Testbed) { let multibody_joints = MultibodyJointSet::new(); let origin = vector![100_000.0, -80_000.0]; - let extent = 1.0; let friction = 0.6; /* diff --git a/examples2d/s2d_high_mass_ratio_3.rs b/examples2d/s2d_high_mass_ratio_3.rs index f8dd3ee..b1f6340 100644 --- a/examples2d/s2d_high_mass_ratio_3.rs +++ b/examples2d/s2d_high_mass_ratio_3.rs @@ -16,8 +16,6 @@ pub fn init_world(testbed: &mut Testbed) { /* * Ground */ - let ground_width = 66.0 * extent; - let rigid_body = RigidBodyBuilder::fixed().translation(vector![0.0, -2.0]); let ground_handle = bodies.insert(rigid_body); let collider = ColliderBuilder::cuboid(40.0, 2.0).friction(friction); diff --git a/examples2d/s2d_joint_grid.rs b/examples2d/s2d_joint_grid.rs index 97cea07..0033c70 100644 --- a/examples2d/s2d_joint_grid.rs +++ b/examples2d/s2d_joint_grid.rs @@ -11,12 +11,7 @@ pub fn init_world(testbed: &mut Testbed) { let multibody_joints = MultibodyJointSet::new(); /* - * Ground - */ - let ground = bodies.insert(RigidBodyBuilder::fixed()); - - /* - * Create the bridge. + * Create the joint grid. */ let rad = 0.4; let numi = 100; diff --git a/examples2d/s2d_pyramid.rs b/examples2d/s2d_pyramid.rs index 45e6310..c35fe63 100644 --- a/examples2d/s2d_pyramid.rs +++ b/examples2d/s2d_pyramid.rs @@ -10,8 +10,6 @@ pub fn init_world(testbed: &mut Testbed) { let impulse_joints = ImpulseJointSet::new(); let multibody_joints = MultibodyJointSet::new(); - let extent = 1.0; - /* * Ground */ diff --git a/examples3d/debug_thin_cube_on_mesh3.rs b/examples3d/debug_thin_cube_on_mesh3.rs index edf6664..4ad557a 100644 --- a/examples3d/debug_thin_cube_on_mesh3.rs +++ b/examples3d/debug_thin_cube_on_mesh3.rs @@ -16,9 +16,6 @@ pub fn init_world(testbed: &mut Testbed) { /* * Ground */ - let ground_size = 100.1; - let ground_height = 0.1; - // let vertices = vec![ // point![-50.0, 0.0, -50.0], // point![-50.0, 0.0, 50.0], diff --git a/examples3d/dynamic_trimesh3.rs b/examples3d/dynamic_trimesh3.rs index 8d71899..0a82476 100644 --- a/examples3d/dynamic_trimesh3.rs +++ b/examples3d/dynamic_trimesh3.rs @@ -21,10 +21,9 @@ pub fn do_init_world(testbed: &mut Testbed, use_convex_decomposition: bool) { /* * Ground */ - let ground_size = 50.0; - let ground_height = 0.1; - //// OPTION 1: floor made of a single big box. + // let ground_size = 50.0; + // let ground_height = 0.1; // let rigid_body = RigidBodyBuilder::fixed().translation(vector![0.0, -ground_height, 0.0]); // let handle = bodies.insert(rigid_body); // let collider = ColliderBuilder::cuboid(ground_size, ground_height, ground_size); @@ -38,7 +37,7 @@ pub fn do_init_world(testbed: &mut Testbed, use_convex_decomposition: bool) { }); let heightfield = HeightField::new(heights, vector![100.0, 2.0, 100.0]); let mut trimesh = TriMesh::from(heightfield); - trimesh.set_flags(TriMeshFlags::FIX_INTERNAL_EDGES); + let _ = trimesh.set_flags(TriMeshFlags::FIX_INTERNAL_EDGES); colliders.insert(ColliderBuilder::new(SharedShape::new(trimesh.clone()))); /* diff --git a/src/dynamics/integration_parameters.rs b/src/dynamics/integration_parameters.rs index b883b0e..8b2ba3b 100644 --- a/src/dynamics/integration_parameters.rs +++ b/src/dynamics/integration_parameters.rs @@ -178,10 +178,16 @@ impl IntegrationParameters { * self.joint_damping_ratio) } + /// Amount of penetration the engine won’t attempt to correct (default: `0.001` multiplied by + /// [`Self::length_unit`]). pub fn allowed_linear_error(&self) -> Real { self.normalized_allowed_linear_error * self.length_unit } + /// Maximum amount of penetration the solver will attempt to resolve in one timestep. + /// + /// This is equal to [`Self::normalized_max_penetration_correction`] multiplied by + /// [`Self::length_unit`]. pub fn max_penetration_correction(&self) -> Real { if self.normalized_max_penetration_correction != Real::MAX { self.normalized_max_penetration_correction * self.length_unit @@ -190,11 +196,13 @@ impl IntegrationParameters { } } + /// The maximal distance separating two objects that will generate predictive contacts + /// (default: `0.002m` multiped by [`Self::length_unit`]). pub fn prediction_distance(&self) -> Real { self.normalized_prediction_distance * self.length_unit } - /// Initialize the simulation paramaters with settings matching the TGS-soft solver + /// Initialize the simulation parameters with settings matching the TGS-soft solver /// with warmstarting. /// /// This is the default configuration, equivalent to [`IntegrationParameters::default()`]. diff --git a/src/dynamics/solver/contact_constraint/one_body_constraint.rs b/src/dynamics/solver/contact_constraint/one_body_constraint.rs index 2392493..1243d11 100644 --- a/src/dynamics/solver/contact_constraint/one_body_constraint.rs +++ b/src/dynamics/solver/contact_constraint/one_body_constraint.rs @@ -128,7 +128,7 @@ impl OneBodyConstraintBuilder { // Normal part. let normal_rhs_wo_bias; { - let mut gcross2 = mprops2 + let gcross2 = mprops2 .effective_world_inv_inertia_sqrt .transform_vector(dp2.gcross(-force_dir1)); diff --git a/src/dynamics/solver/contact_constraint/two_body_constraint.rs b/src/dynamics/solver/contact_constraint/two_body_constraint.rs index 39f4931..1511d4f 100644 --- a/src/dynamics/solver/contact_constraint/two_body_constraint.rs +++ b/src/dynamics/solver/contact_constraint/two_body_constraint.rs @@ -8,7 +8,6 @@ use crate::geometry::{ContactManifold, ContactManifoldIndex}; use crate::math::{Isometry, Real, Vector, DIM, MAX_MANIFOLD_POINTS}; use crate::utils::{self, SimdAngularInertia, SimdBasis, SimdCross, SimdDot}; use na::{DVector, Matrix2}; -use num::Pow; use super::{TwoBodyConstraintElement, TwoBodyConstraintNormalPart}; diff --git a/src/dynamics/solver/contact_constraint/two_body_constraint_element.rs b/src/dynamics/solver/contact_constraint/two_body_constraint_element.rs index 7e17e73..b794833 100644 --- a/src/dynamics/solver/contact_constraint/two_body_constraint_element.rs +++ b/src/dynamics/solver/contact_constraint/two_body_constraint_element.rs @@ -1,11 +1,9 @@ use crate::dynamics::integration_parameters::BLOCK_SOLVER_ENABLED; -use crate::dynamics::solver::contact_constraint::OneBodyConstraintNormalPart; use crate::dynamics::solver::SolverVel; use crate::math::{AngVector, TangentImpulse, Vector, DIM}; use crate::utils::{SimdBasis, SimdDot, SimdRealCopy}; -use na::{Matrix2, Vector2}; -use num::Zero; -use simba::simd::{SimdPartialOrd, SimdValue}; +use na::Vector2; +use simba::simd::SimdValue; #[derive(Copy, Clone, Debug)] pub(crate) struct TwoBodyConstraintTangentPart<N: SimdRealCopy> { diff --git a/src/dynamics/solver/contact_constraint/two_body_constraint_simd.rs b/src/dynamics/solver/contact_constraint/two_body_constraint_simd.rs index 0b1b419..4c4ef52 100644 --- a/src/dynamics/solver/contact_constraint/two_body_constraint_simd.rs +++ b/src/dynamics/solver/contact_constraint/two_body_constraint_simd.rs @@ -14,7 +14,6 @@ use crate::math::{ #[cfg(feature = "dim2")] use crate::utils::SimdBasis; use crate::utils::{self, SimdAngularInertia, SimdCross, SimdDot}; -use na::Matrix2; use num::Zero; use parry::math::SimdBool; use parry::utils::SdpMatrix2; diff --git a/src/dynamics/solver/velocity_solver.rs b/src/dynamics/solver/velocity_solver.rs index 7ea48ab..b0bafb8 100644 --- a/src/dynamics/solver/velocity_solver.rs +++ b/src/dynamics/solver/velocity_solver.rs @@ -10,7 +10,6 @@ use crate::math::Real; use crate::prelude::RigidBodyVelocity; use crate::utils::SimdAngularInertia; use na::DVector; -use ordered_float::OrderedFloat; pub(crate) struct VelocitySolver { pub solver_bodies: Vec<SolverBody>, diff --git a/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs b/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs index 0fa499f..c02b222 100644 --- a/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs +++ b/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs @@ -3,7 +3,7 @@ use super::{ }; use crate::geometry::{ BroadPhaseProxyIndex, Collider, ColliderBroadPhaseData, ColliderChanges, ColliderHandle, - ColliderPosition, ColliderSet, ColliderShape, + ColliderSet, }; use crate::math::{Isometry, Real}; use crate::prelude::{BroadPhase, RigidBodySet}; @@ -606,7 +606,7 @@ impl BroadPhase for BroadPhaseMultiSap { prediction_distance, *handle, &mut new_proxy_id, - &co, + co, next_pos.as_ref(), ) { need_region_propagation = true; diff --git a/src/geometry/broad_phase_qbvh.rs b/src/geometry/broad_phase_qbvh.rs index be8c53b..5fd6bcf 100644 --- a/src/geometry/broad_phase_qbvh.rs +++ b/src/geometry/broad_phase_qbvh.rs @@ -1,5 +1,4 @@ use crate::geometry::{BroadPhasePairEvent, ColliderHandle, ColliderPair, ColliderSet}; -use parry::bounding_volume::BoundingVolume; use parry::math::Real; use parry::partitioning::Qbvh; use parry::partitioning::QbvhUpdateWorkspace; diff --git a/src/geometry/contact_pair.rs b/src/geometry/contact_pair.rs index ee3a6ac..f5d0f64 100644 --- a/src/geometry/contact_pair.rs +++ b/src/geometry/contact_pair.rs @@ -1,9 +1,8 @@ use crate::dynamics::{RigidBodyHandle, RigidBodySet}; use crate::geometry::{ColliderHandle, ColliderSet, Contact, ContactManifold}; -use crate::math::{Point, Real, TangentImpulse, Vector, ANG_DIM}; +use crate::math::{Point, Real, TangentImpulse, Vector}; use crate::pipeline::EventHandler; use crate::prelude::CollisionEventFlags; -use parry::math::AngVector; use parry::query::ContactManifoldsWorkspace; use super::CollisionEvent; @@ -304,7 +303,9 @@ pub struct SolverContact { pub tangent_velocity: Vector<Real>, /// Whether or not this contact existed during the last timestep. pub is_new: bool, + /// Impulse used to warmstart the solve for the normal constraint. pub warmstart_impulse: Real, + /// Impulse used to warmstart the solve for the friction constraints. pub warmstart_tangent_impulse: TangentImpulse<Real>, } @@ -166,6 +166,7 @@ pub mod math { #[cfg(feature = "dim2")] pub type JacobianViewMut<'a, N> = na::MatrixViewMut3xX<'a, N>; + /// The type of impulse applied for friction constraints. #[cfg(feature = "dim2")] pub type TangentImpulse<N> = na::Vector1<N>; @@ -198,6 +199,7 @@ pub mod math { #[cfg(feature = "dim3")] pub type JacobianViewMut<'a, N> = na::MatrixViewMut6xX<'a, N>; + /// The type of impulse applied for friction constraints. #[cfg(feature = "dim3")] pub type TangentImpulse<N> = na::Vector2<N>; diff --git a/src/pipeline/query_pipeline.rs b/src/pipeline/query_pipeline.rs index 59af7c6..bca0cc4 100644 --- a/src/pipeline/query_pipeline.rs +++ b/src/pipeline/query_pipeline.rs @@ -16,7 +16,6 @@ use parry::query::visitors::{ }; use parry::query::{DefaultQueryDispatcher, NonlinearRigidMotion, QueryDispatcher, TOI}; use parry::shape::{FeatureId, Shape, TypedSimdCompositeShape}; -use parry::utils::DefaultStorage; use std::sync::Arc; /// A pipeline for performing queries on all the colliders of a scene. @@ -248,7 +247,6 @@ impl<'a> TypedSimdCompositeShape for QueryPipelineAsCompositeShape<'a> { type PartShape = dyn Shape; type PartNormalConstraints = dyn NormalConstraints; type PartId = ColliderHandle; - type QbvhStorage = DefaultStorage; fn map_typed_part_at( &self, diff --git a/src_testbed/testbed.rs b/src_testbed/testbed.rs index d5406d0..f76100d 100644 --- a/src_testbed/testbed.rs +++ b/src_testbed/testbed.rs @@ -1114,7 +1114,6 @@ fn update_testbed( ) { let meshes = &mut *meshes; let materials = &mut *materials; - let prev_example = state.selected_example; // Handle inputs { diff --git a/src_testbed/ui.rs b/src_testbed/ui.rs index e18cc65..7f3bdac 100644 --- a/src_testbed/ui.rs +++ b/src_testbed/ui.rs @@ -10,7 +10,6 @@ use crate::testbed::{ }; use crate::PhysicsState; -use bevy_egui::egui::WidgetType::CollapsingHeader; use bevy_egui::egui::{Slider, Ui}; use bevy_egui::{egui, EguiContexts}; use rapier::dynamics::IntegrationParameters; |
