From 73e2fb77d633574af86159c5e58ff3767cdc136f Mon Sep 17 00:00:00 2001 From: Aceeri Date: Wed, 23 Aug 2023 22:03:58 -0700 Subject: [PATCH 01/10] Set up cargo toml to support f64, begin making things agnostic to f32/f64 --- bevy_rapier2d/Cargo.toml | 23 +++++++++++++---------- bevy_rapier3d/Cargo.toml | 23 +++++++++++++---------- src/lib.rs | 25 ++++++++++++++++++------- 3 files changed, 44 insertions(+), 27 deletions(-) diff --git a/bevy_rapier2d/Cargo.toml b/bevy_rapier2d/Cargo.toml index a691f05a..3f58e724 100644 --- a/bevy_rapier2d/Cargo.toml +++ b/bevy_rapier2d/Cargo.toml @@ -18,16 +18,18 @@ path = "../src/lib.rs" required-features = [ "dim2" ] [features] -default = [ "dim2", "async-collider", "debug-render-2d" ] +default = [ "dim2", "async-collider", "debug-render-2d", "f32" ] +f32 = [ "rapier2d" ] +f64 = [ "rapier2d-f64" ] dim2 = [] -debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier2d/debug-render", "bevy/bevy_asset" ] -debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier2d/debug-render", "bevy/bevy_asset" ] -parallel = [ "rapier2d/parallel" ] -simd-stable = [ "rapier2d/simd-stable" ] -simd-nightly = [ "rapier2d/simd-nightly" ] -wasm-bindgen = [ "rapier2d/wasm-bindgen" ] -serde-serialize = [ "rapier2d/serde-serialize", "bevy/serialize", "serde" ] -enhanced-determinism = [ "rapier2d/enhanced-determinism" ] +debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier2d?/debug-render", "rapier2d-f64?/debug-render", "bevy/bevy_asset" ] +debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier2d?/debug-render", "rapier2d-f64?/debug-render", "bevy/bevy_asset" ] +parallel = [ "rapier2d?/parallel", "rapier2d-f64?/parallel" ] +simd-stable = [ "rapier2d?/simd-stable", "rapier2d-f64?/simd-stable" ] +simd-nightly = [ "rapier2d?/simd-nightly", "rapier2d-f64?/simd-nightly" ] +wasm-bindgen = [ "rapier2d?/wasm-bindgen", "rapier2d-f64?/wasm-bindgen" ] +serde-serialize = [ "rapier2d-f64?/serde-serialize", "rapier2d?/serde-serialize", "bevy/serialize", "serde" ] +enhanced-determinism = [ "rapier2d?/enhanced-determinism", "rapier2d-f64?/enhanced-determinism" ] headless = [] async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] @@ -35,7 +37,8 @@ async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet -rapier2d = "0.17.0" +rapier2d = { version = "0.17.0", optional = true } +rapier2d-f64 = { version = "0.17.0", optional = true } bitflags = "1" #bevy_prototype_debug_lines = { version = "0.6", optional = true } log = "0.4" diff --git a/bevy_rapier3d/Cargo.toml b/bevy_rapier3d/Cargo.toml index 1082f501..fa153283 100644 --- a/bevy_rapier3d/Cargo.toml +++ b/bevy_rapier3d/Cargo.toml @@ -18,17 +18,19 @@ path = "../src/lib.rs" required-features = [ "dim3" ] [features] -default = [ "dim3", "async-collider", "debug-render-3d" ] +default = [ "dim3", "async-collider", "debug-render-3d", "f32" ] +f32 = [ "rapier3d" ] +f64 = [ "rapier3d-f64" ] dim3 = [] debug-render = [ "debug-render-3d" ] -debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier3d/debug-render", "bevy/bevy_asset" ] -debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier3d/debug-render", "bevy/bevy_asset" ] -parallel = [ "rapier3d/parallel" ] -simd-stable = [ "rapier3d/simd-stable" ] -simd-nightly = [ "rapier3d/simd-nightly" ] -wasm-bindgen = [ "rapier3d/wasm-bindgen" ] -serde-serialize = [ "rapier3d/serde-serialize", "bevy/serialize", "serde" ] -enhanced-determinism = [ "rapier3d/enhanced-determinism" ] +debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier3d?/debug-render", "rapier3d-f64?/debug-render", "bevy/bevy_asset" ] +debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier3d?/debug-render", "rapier3d-f64?/debug-render", "bevy/bevy_asset" ] +parallel = [ "rapier3d?/parallel", "rapier3d-f64?/parallel" ] +simd-stable = [ "rapier3d?/simd-stable", "rapier3d-f64?/simd-stable" ] +simd-nightly = [ "rapier3d?/simd-nightly", "rapier3d-f64?/simd-nightly" ] +wasm-bindgen = [ "rapier3d?/wasm-bindgen", "rapier3d-f64?/wasm-bindgen" ] +serde-serialize = [ "rapier3d-f64?/serde-serialize", "rapier3d?/serde-serialize", "bevy/serialize", "serde" ] +enhanced-determinism = [ "rapier3d?/enhanced-determinism", "rapier3d-f64?/enhanced-determinism" ] headless = [ ] async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] @@ -36,7 +38,8 @@ async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet -rapier3d = "0.17.0" +rapier3d = { version = "0.17.0", optional = true } +rapier3d-f64 = { version = "0.17.0", optional = true } bitflags = "1" #bevy_prototype_debug_lines = { version = "0.6", features = ["3d"], optional = true } log = "0.4" diff --git a/src/lib.rs b/src/lib.rs index 557cd268..e97bacfb 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -17,21 +17,27 @@ extern crate serde; pub extern crate nalgebra as na; -#[cfg(feature = "dim2")] +#[cfg(all(feature = "dim2", feature = "f32"))] pub extern crate rapier2d as rapier; -#[cfg(feature = "dim3")] +#[cfg(all(feature = "dim2", feature = "f64"))] +pub extern crate rapier3d_f64 as rapier; +#[cfg(all(feature = "dim3", feature = "f32"))] pub extern crate rapier3d as rapier; +#[cfg(all(feature = "dim3", feature = "f64"))] +pub extern crate rapier3d_f64 as rapier; pub use rapier::parry; /// Type aliases to select the right vector/rotation types based /// on the dimension used by the engine. #[cfg(feature = "dim2")] pub mod math { - use bevy::math::Vec2; /// The real type (f32 or f64). pub type Real = rapier::math::Real; /// The vector type. - pub type Vect = Vec2; + #[cfg(feature = "f32")] + pub type Vect = bevy::math::Vec2; + #[cfg(feature = "f64")] + pub type Vect = bevy::math::DVec2; /// The rotation type (in 2D this is an angle in radians). pub type Rot = Real; } @@ -40,13 +46,18 @@ pub mod math { /// on the dimension used by the engine. #[cfg(feature = "dim3")] pub mod math { - use bevy::math::{Quat, Vec3}; /// The real type (f32 or f64). pub type Real = rapier::math::Real; /// The vector type. - pub type Vect = Vec3; + #[cfg(feature = "f32")] + pub type Vect = bevy::math::Vec3; + #[cfg(feature = "f64")] + pub type Vect = bevy::math::DVec3; /// The rotation type. - pub type Rot = Quat; + #[cfg(feature = "f32")] + pub type Rot = bevy::math::Quat; + #[cfg(feature = "f64")] + pub type Rot = bevy::math::DQuat; } /// Components related to physics dynamics (rigid-bodies, velocities, etc.) From 79aa0d7265cf67d5dad5581412ff2c8f86391567 Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 00:59:06 -0700 Subject: [PATCH 02/10] f64 feature flag for bevy rapier --- bevy_rapier3d/examples/boxes3.rs | 6 +- src/dynamics/rigid_body.rs | 37 ++--- src/geometry/collider.rs | 35 ++--- src/geometry/shape_views/round_shape.rs | 7 +- src/plugin/configuration.rs | 14 +- src/plugin/context.rs | 14 +- src/plugin/plugin.rs | 4 +- src/plugin/systems.rs | 16 +-- src/render/mod.rs | 14 +- src/utils/as_real.rs | 180 ++++++++++++++++++++++++ src/utils/mod.rs | 51 +++++-- 11 files changed, 299 insertions(+), 79 deletions(-) create mode 100644 src/utils/as_real.rs diff --git a/bevy_rapier3d/examples/boxes3.rs b/bevy_rapier3d/examples/boxes3.rs index 3d510720..e3d45bc5 100644 --- a/bevy_rapier3d/examples/boxes3.rs +++ b/bevy_rapier3d/examples/boxes3.rs @@ -1,5 +1,5 @@ use bevy::prelude::*; -use bevy_rapier3d::prelude::*; +use bevy_rapier3d::{utils::as_real::*, prelude::*}; fn main() { App::new() @@ -34,7 +34,7 @@ pub fn setup_physics(mut commands: Commands) { commands.spawn(( TransformBundle::from(Transform::from_xyz(0.0, -ground_height, 0.0)), - Collider::cuboid(ground_size, ground_height, ground_size), + Collider::cuboid(ground_size.as_real(), ground_height.as_real(), ground_size.as_real()), )); /* @@ -72,7 +72,7 @@ pub fn setup_physics(mut commands: Commands) { child.spawn(( TransformBundle::from(Transform::from_xyz(x, y, z)), RigidBody::Dynamic, - Collider::cuboid(rad, rad, rad), + Collider::cuboid(rad.as_real(), rad.as_real(), rad.as_real()), ColliderDebugColor(colors[color % 3]), )); }); diff --git a/src/dynamics/rigid_body.rs b/src/dynamics/rigid_body.rs index f2be60ec..31213fa5 100644 --- a/src/dynamics/rigid_body.rs +++ b/src/dynamics/rigid_body.rs @@ -1,4 +1,5 @@ use crate::math::Vect; +use crate::prelude::Real; use bevy::prelude::*; use rapier::prelude::{ Isometry, LockedAxes as RapierLockedAxes, RigidBodyActivation, RigidBodyHandle, RigidBodyType, @@ -70,7 +71,7 @@ pub struct Velocity { pub linvel: Vect, /// The angular velocity of the rigid-body. #[cfg(feature = "dim2")] - pub angvel: f32, + pub angvel: Real, /// The angular velocity of the rigid-body. #[cfg(feature = "dim3")] pub angvel: Vect, @@ -101,7 +102,7 @@ impl Velocity { /// Initialize a velocity with the given angular velocity, and a linear velocity of zero. #[cfg(feature = "dim2")] - pub const fn angular(angvel: f32) -> Self { + pub const fn angular(angvel: Real) -> Self { Self { linvel: Vect::ZERO, angvel, @@ -138,7 +139,7 @@ pub enum AdditionalMassProperties { /// This mass will be added to the rigid-body. The rigid-body’s total /// angular inertia tensor (obtained from its attached colliders) will /// be scaled accordingly. - Mass(f32), + Mass(Real), /// These mass properties will be added to the rigid-body. MassProperties(MassProperties), } @@ -190,10 +191,10 @@ pub struct MassProperties { /// The center of mass of a rigid-body expressed in its local-space. pub local_center_of_mass: Vect, /// The mass of a rigid-body. - pub mass: f32, + pub mass: Real, /// The principal angular inertia of the rigid-body. #[cfg(feature = "dim2")] - pub principal_inertia: f32, + pub principal_inertia: Real, /// The principal vectors of the local angular inertia tensor of the rigid-body. #[cfg(feature = "dim3")] pub principal_inertia_local_frame: crate::math::Rot, @@ -205,7 +206,7 @@ pub struct MassProperties { impl MassProperties { /// Converts these mass-properties to Rapier’s `MassProperties` structure. #[cfg(feature = "dim2")] - pub fn into_rapier(self, physics_scale: f32) -> rapier::dynamics::MassProperties { + pub fn into_rapier(self, physics_scale: Real) -> rapier::dynamics::MassProperties { rapier::dynamics::MassProperties::new( (self.local_center_of_mass / physics_scale).into(), self.mass, @@ -216,7 +217,7 @@ impl MassProperties { /// Converts these mass-properties to Rapier’s `MassProperties` structure. #[cfg(feature = "dim3")] - pub fn into_rapier(self, physics_scale: f32) -> rapier::dynamics::MassProperties { + pub fn into_rapier(self, physics_scale: Real) -> rapier::dynamics::MassProperties { rapier::dynamics::MassProperties::with_principal_inertia_frame( (self.local_center_of_mass / physics_scale).into(), self.mass, @@ -226,7 +227,7 @@ impl MassProperties { } /// Converts Rapier’s `MassProperties` structure to `Self`. - pub fn from_rapier(mprops: rapier::dynamics::MassProperties, physics_scale: f32) -> Self { + pub fn from_rapier(mprops: rapier::dynamics::MassProperties, physics_scale: Real) -> Self { #[allow(clippy::useless_conversion)] // Need to convert if dim3 enabled Self { mass: mprops.mass(), @@ -279,7 +280,7 @@ pub struct ExternalForce { pub force: Vect, /// The angular torque applied to the rigid-body. #[cfg(feature = "dim2")] - pub torque: f32, + pub torque: Real, /// The angular torque applied to the rigid-body. #[cfg(feature = "dim3")] pub torque: Vect, @@ -351,7 +352,7 @@ pub struct ExternalImpulse { pub impulse: Vect, /// The angular impulse applied to the rigid-body. #[cfg(feature = "dim2")] - pub torque_impulse: f32, + pub torque_impulse: Real, /// The angular impulse applied to the rigid-body. #[cfg(feature = "dim3")] pub torque_impulse: Vect, @@ -421,7 +422,7 @@ impl SubAssign for ExternalImpulse { /// applied to this rigid-body. #[derive(Copy, Clone, Debug, PartialEq, Component, Reflect)] #[reflect(Component, PartialEq)] -pub struct GravityScale(pub f32); +pub struct GravityScale(pub Real); impl Default for GravityScale { fn default() -> Self { @@ -476,9 +477,9 @@ impl Dominance { #[reflect(Component, PartialEq)] pub struct Sleeping { /// The linear velocity below which the body can fall asleep. - pub linear_threshold: f32, + pub linear_threshold: Real, /// The angular velocity below which the body can fall asleep. - pub angular_threshold: f32, + pub angular_threshold: Real, /// Is this body sleeping? pub sleeping: bool, } @@ -510,9 +511,9 @@ impl Default for Sleeping { pub struct Damping { // TODO: rename these to "linear" and "angular"? /// Damping factor for gradually slowing down the translational motion of the rigid-body. - pub linear_damping: f32, + pub linear_damping: Real, /// Damping factor for gradually slowing down the angular motion of the rigid-body. - pub angular_damping: f32, + pub angular_damping: Real, } impl Default for Damping { @@ -530,14 +531,14 @@ impl Default for Damping { #[derive(Copy, Clone, Debug, Default, PartialEq, Component)] pub struct TransformInterpolation { /// The starting point of the interpolation. - pub start: Option>, + pub start: Option>, /// The end point of the interpolation. - pub end: Option>, + pub end: Option>, } impl TransformInterpolation { /// Interpolates between the start and end positions with `t` in the range `[0..1]`. - pub fn lerp_slerp(&self, t: f32) -> Option> { + pub fn lerp_slerp(&self, t: Real) -> Option> { if let (Some(start), Some(end)) = (self.start, self.end) { Some(start.lerp_slerp(&end, t)) } else { diff --git a/src/geometry/collider.rs b/src/geometry/collider.rs index a7dd2384..8a70b1be 100644 --- a/src/geometry/collider.rs +++ b/src/geometry/collider.rs @@ -10,7 +10,8 @@ use rapier::geometry::Shape; use rapier::prelude::{ColliderHandle, InteractionGroups, SharedShape}; use crate::dynamics::{CoefficientCombineRule, MassProperties}; -use crate::math::Vect; +use crate::math::{Real, Vect}; +use crate::utils::as_real::*; /// The Rapier handle of a collider that was inserted to the physics scene. #[derive(Copy, Clone, Debug, Component)] @@ -109,9 +110,9 @@ pub struct Sensor; #[reflect(Component, PartialEq)] pub enum ColliderMassProperties { /// The mass-properties are computed automatically from the collider’s shape and this density. - Density(f32), + Density(Real), /// The mass-properties are computed automatically from the collider’s shape and this mass. - Mass(f32), + Mass(Real), /// The mass-properties of the collider are replaced by the ones specified here. MassProperties(MassProperties), } @@ -130,7 +131,7 @@ pub struct Friction { /// /// The greater the value, the stronger the friction forces will be. /// Should be `>= 0`. - pub coefficient: f32, + pub coefficient: Real, /// The rule applied to combine the friction coefficients of two colliders in contact. pub combine_rule: CoefficientCombineRule, } @@ -147,18 +148,18 @@ impl Default for Friction { impl Friction { /// Creates a `Friction` component from the given friction coefficient, and using the default /// `CoefficientCombineRule::Average` coefficient combine rule. - pub const fn new(coefficient: f32) -> Self { + pub const fn new(coefficient: Real) -> Self { Self { - coefficient, + coefficient: coefficient, combine_rule: CoefficientCombineRule::Average, } } /// Creates a `Friction` component from the given friction coefficient, and using the default /// `CoefficientCombineRule::Average` coefficient combine rule. - pub const fn coefficient(coefficient: f32) -> Self { + pub const fn coefficient(coefficient: Real) -> Self { Self { - coefficient, + coefficient: coefficient, combine_rule: CoefficientCombineRule::Average, } } @@ -172,7 +173,7 @@ pub struct Restitution { /// /// The greater the value, the stronger the restitution forces will be. /// Should be `>= 0`. - pub coefficient: f32, + pub coefficient: Real, /// The rule applied to combine the friction coefficients of two colliders in contact. pub combine_rule: CoefficientCombineRule, } @@ -180,18 +181,18 @@ pub struct Restitution { impl Restitution { /// Creates a `Restitution` component from the given restitution coefficient, and using the default /// `CoefficientCombineRule::Average` coefficient combine rule. - pub const fn new(coefficient: f32) -> Self { + pub const fn new(coefficient: Real) -> Self { Self { - coefficient, + coefficient: coefficient, combine_rule: CoefficientCombineRule::Average, } } /// Creates a `Restitution` component from the given restitution coefficient, and using the default /// `CoefficientCombineRule::Average` coefficient combine rule. - pub const fn coefficient(coefficient: f32) -> Self { + pub const fn coefficient(coefficient: Real) -> Self { Self { - coefficient, + coefficient: coefficient, combine_rule: CoefficientCombineRule::Average, } } @@ -457,11 +458,11 @@ impl From for rapier::pipeline::ActiveEvents { /// The total force magnitude beyond which a contact force event can be emitted. #[derive(Copy, Clone, PartialEq, Component, Reflect)] #[reflect(Component)] -pub struct ContactForceEventThreshold(pub f32); +pub struct ContactForceEventThreshold(pub Real); impl Default for ContactForceEventThreshold { fn default() -> Self { - Self(f32::MAX) + Self(Real::MAX) } } @@ -506,8 +507,8 @@ pub struct ColliderDisabled; /// We restrict the scaling increment to 1.0e-4, to avoid numerical jitter /// due to the extraction of scaling factor from the GlobalTransform matrix. pub fn get_snapped_scale(scale: Vect) -> Vect { - fn snap_value(new: f32) -> f32 { - const PRECISION: f32 = 1.0e4; + fn snap_value(new: Real) -> Real { + const PRECISION: Real = 1.0e4; (new * PRECISION).round() / PRECISION } diff --git a/src/geometry/shape_views/round_shape.rs b/src/geometry/shape_views/round_shape.rs index 936a1170..a798c365 100644 --- a/src/geometry/shape_views/round_shape.rs +++ b/src/geometry/shape_views/round_shape.rs @@ -1,5 +1,6 @@ use crate::geometry::shape_views::{CuboidView, CuboidViewMut, TriangleView, TriangleViewMut}; use rapier::geometry::{RoundCuboid, RoundTriangle}; +use crate::math::{Real, Vect}; #[cfg(feature = "dim2")] use { @@ -27,7 +28,7 @@ macro_rules! round_shape_view( impl<'a> $RoundShapeView<'a> { /// The radius of the round border of this shape. - pub fn border_radius(&self) -> f32 { + pub fn border_radius(&self) -> Real { self.raw.border_radius } @@ -47,12 +48,12 @@ macro_rules! round_shape_view( impl<'a> $RoundShapeViewMut<'a> { /// The radius of the round border of this shape. - pub fn border_radius(&self) -> f32 { + pub fn border_radius(&self) -> Real { self.raw.border_radius } /// Set the radius of the round border of this shape. - pub fn set_border_radius(&mut self, new_border_radius: f32) { + pub fn set_border_radius(&mut self, new_border_radius: Real) { self.raw.border_radius = new_border_radius; } diff --git a/src/plugin/configuration.rs b/src/plugin/configuration.rs index dac478b0..a407b364 100644 --- a/src/plugin/configuration.rs +++ b/src/plugin/configuration.rs @@ -1,12 +1,12 @@ use bevy::prelude::Resource; -use crate::math::Vect; +use crate::math::{Vect, Real}; /// Difference between simulation and rendering time #[derive(Resource, Default)] pub struct SimulationToRenderTime { /// Difference between simulation and rendering time - pub diff: f32, + pub diff: Real, } /// The different ways of adjusting the timestep length. @@ -16,7 +16,7 @@ pub enum TimestepMode { /// `dt` seconds at each Bevy tick by performing `substeps` of length `dt / substeps`. Fixed { /// The physics simulation will be advanced by this total amount at each Bevy tick. - dt: f32, + dt: Real, /// This number of substeps of length `dt / substeps` will be performed at each Bevy tick. substeps: usize, }, @@ -26,10 +26,10 @@ pub enum TimestepMode { /// `time_scale < 1.0` makes the simulation run in slow-motion. Variable { /// Maximum amount of time the physics simulation may be advanced at each Bevy tick. - max_dt: f32, + max_dt: Real, /// Multiplier controlling if the physics simulation should advance faster (> 1.0), /// at the same speed (= 1.0) or slower (< 1.0) than the real time. - time_scale: f32, + time_scale: Real, /// The number of substeps that will be performed at each tick. substeps: usize, }, @@ -40,10 +40,10 @@ pub enum TimestepMode { Interpolated { /// The physics simulation will be advanced by this total amount at each Bevy tick, unless /// the physics simulation time is ahead of a the real time. - dt: f32, + dt: Real, /// Multiplier controlling if the physics simulation should advance faster (> 1.0), /// at the same speed (= 1.0) or slower (< 1.0) than the real time. - time_scale: f32, + time_scale: Real, /// The number of substeps that will be performed whenever the physics simulation is advanced. substeps: usize, }, diff --git a/src/plugin/context.rs b/src/plugin/context.rs index 0dadbc47..ce1398a5 100644 --- a/src/plugin/context.rs +++ b/src/plugin/context.rs @@ -18,6 +18,7 @@ use crate::control::{CharacterCollision, MoveShapeOptions, MoveShapeOutput}; use crate::dynamics::TransformInterpolation; use crate::plugin::configuration::{SimulationToRenderTime, TimestepMode}; use crate::prelude::{CollisionGroups, RapierRigidBodyHandle}; +use crate::utils::as_real::*; use rapier::control::CharacterAutostep; /// The Rapier context, containing all the state of the physics engine. @@ -232,7 +233,7 @@ impl RapierContext { time_scale, substeps, } => { - sim_to_render_time.diff += time.delta_seconds(); + sim_to_render_time.diff += time.delta_seconds_f64().as_single(); while sim_to_render_time.diff > 0.0 { // NOTE: in this comparison we do the same computations we @@ -282,7 +283,7 @@ impl RapierContext { } => { let mut substep_integration_parameters = self.integration_parameters; substep_integration_parameters.dt = - (time.delta_seconds() * time_scale).min(max_dt) / (substeps as Real); + (time.delta_seconds_f64().as_single() * time_scale).min(max_dt) / (substeps as Real); for _ in 0..substeps { self.pipeline.step( @@ -729,17 +730,18 @@ impl RapierContext { aabb: bevy::render::primitives::Aabb, mut callback: impl FnMut(Entity) -> bool, ) { + let scale = self.physics_scale; #[cfg(feature = "dim2")] use bevy::math::Vec3Swizzles; #[cfg(feature = "dim2")] let scaled_aabb = rapier::prelude::Aabb { - mins: (aabb.min().xy() / self.physics_scale).into(), - maxs: (aabb.max().xy() / self.physics_scale).into(), + mins: (aabb.min().xy().as_real() / scale).into(), + maxs: (aabb.max().xy().as_real() / scale).into(), }; #[cfg(feature = "dim3")] let scaled_aabb = rapier::prelude::Aabb { - mins: (aabb.min() / self.physics_scale).into(), - maxs: (aabb.max() / self.physics_scale).into(), + mins: (aabb.min().as_real() / scale).into(), + maxs: (aabb.max().as_real() / scale).into(), }; #[allow(clippy::redundant_closure)] // False-positive, we can't move callback, closure becomes `FnOnce` diff --git a/src/plugin/plugin.rs b/src/plugin/plugin.rs index fc5aa295..cf2120bc 100644 --- a/src/plugin/plugin.rs +++ b/src/plugin/plugin.rs @@ -19,7 +19,7 @@ pub type NoUserData = (); /// Rapier physics engine. pub struct RapierPhysicsPlugin { schedule: Box, - physics_scale: f32, + physics_scale: Real, default_system_setup: bool, _phantom: PhantomData, } @@ -35,7 +35,7 @@ where /// all the length-related quantities by the `physics_scale` factor. This should /// likely always be 1.0 in 3D. In 2D, this is useful to specify a "pixels-per-meter" /// conversion ratio. - pub fn with_physics_scale(mut self, physics_scale: f32) -> Self { + pub fn with_physics_scale(mut self, physics_scale: Real) -> Self { self.physics_scale = physics_scale; self } diff --git a/src/plugin/systems.rs b/src/plugin/systems.rs index aadbf662..63d3ddf3 100644 --- a/src/plugin/systems.rs +++ b/src/plugin/systems.rs @@ -18,7 +18,7 @@ use crate::prelude::{ BevyPhysicsHooks, BevyPhysicsHooksAdapter, CollidingEntities, KinematicCharacterController, KinematicCharacterControllerOutput, MassModifiedEvent, RigidBodyDisabled, }; -use crate::utils; +use crate::utils::{self, as_real::*}; use bevy::ecs::system::{StaticSystemParam, SystemParamItem}; use bevy::prelude::*; use rapier::prelude::*; @@ -100,15 +100,15 @@ pub fn apply_scale( let effective_scale = match custom_scale { Some(ColliderScale::Absolute(scale)) => *scale, Some(ColliderScale::Relative(scale)) => { - *scale * transform.compute_transform().scale.xy() + *scale * transform.compute_transform().scale.xy().as_real() } - None => transform.compute_transform().scale.xy(), + None => transform.compute_transform().scale.xy().as_real(), }; #[cfg(feature = "dim3")] let effective_scale = match custom_scale { Some(ColliderScale::Absolute(scale)) => *scale, - Some(ColliderScale::Relative(scale)) => *scale * transform.compute_transform().scale, - None => transform.compute_transform().scale, + Some(ColliderScale::Relative(scale)) => *scale * transform.compute_transform().scale.as_real(), + None => transform.compute_transform().scale.as_real(), }; if shape.scale != crate::geometry::get_snapped_scale(effective_scale) { @@ -1465,11 +1465,11 @@ pub fn update_character_controls( if let Ok(mut transform) = transforms.get_mut(entity_to_move) { // TODO: take the parent’s GlobalTransform rotation into account? - transform.translation.x += movement.translation.x * physics_scale; - transform.translation.y += movement.translation.y * physics_scale; + transform.translation.x += (movement.translation.x * physics_scale).as_single(); + transform.translation.y += (movement.translation.y * physics_scale).as_single(); #[cfg(feature = "dim3")] { - transform.translation.z += movement.translation.z * physics_scale; + transform.translation.z += (movement.translation.z * physics_scale).as_single(); } } diff --git a/src/render/mod.rs b/src/render/mod.rs index 7bc01880..cb504ce2 100644 --- a/src/render/mod.rs +++ b/src/render/mod.rs @@ -126,11 +126,11 @@ impl<'world, 'state, 'a, 'b> DebugRenderBackend for BevyLinesRenderBackend<'worl b: Point, color: [f32; 4], ) { - let scale = self.physics_scale; + let scale = self.physics_scale as f32; let color = self.object_color(object, color); self.gizmos.line( - [a.x * scale, a.y * scale, 0.0].into(), - [b.x * scale, b.y * scale, 0.0].into(), + [a.x as f32 * scale, a.y as f32 * scale, 0.0].into(), + [b.x as f32 * scale, b.y as f32 * scale, 0.0].into(), Color::hsla(color[0], color[1], color[2], color[3]), ) } @@ -146,8 +146,8 @@ impl<'world, 'state, 'a, 'b> DebugRenderBackend for BevyLinesRenderBackend<'worl let scale = self.physics_scale; let color = self.object_color(object, color); self.gizmos.line( - [a.x * scale, a.y * scale, a.z * scale].into(), - [b.x * scale, b.y * scale, b.z * scale].into(), + [a.x as f32 * scale, a.y as f32 * scale, a.z as f32 * scale].into(), + [b.x as f32 * scale, b.y as f32 * scale, b.z as f32 * scale].into(), Color::hsla(color[0], color[1], color[2], color[3]), ) } @@ -164,14 +164,14 @@ fn debug_render_scene( } let mut backend = BevyLinesRenderBackend { - physics_scale: rapier_context.physics_scale, + physics_scale: rapier_context.physics_scale as f32, custom_colors, context: &rapier_context, gizmos, }; let unscaled_style = render_context.pipeline.style; - render_context.pipeline.style.rigid_body_axes_length /= rapier_context.physics_scale; + render_context.pipeline.style.rigid_body_axes_length /= rapier_context.physics_scale as f32; render_context.pipeline.render( &mut backend, &rapier_context.bodies, diff --git a/src/utils/as_real.rs b/src/utils/as_real.rs new file mode 100644 index 00000000..7cff3f6f --- /dev/null +++ b/src/utils/as_real.rs @@ -0,0 +1,180 @@ + +use bevy::math::*; + +/// Convert value into the precision the compilation is using. +pub trait AsReal { + type Real; + fn as_real(self) -> Self::Real; +} + +/// Convert value into single precision floating point. +pub trait AsSingle { + type Single; + fn as_single(self) -> Self::Single; +} + +macro_rules! as_real_self { + ($ty:ty) => { + impl AsReal for $ty { + type Real = $ty; + fn as_real(self) -> Self::Real { + self + } + } + } +} + +macro_rules! as_single_self { + ($ty:ty) => { + impl AsSingle for $ty { + type Single = $ty; + fn as_single(self) -> Self::Single { + self + } + } + } +} + +as_single_self!(f32); +as_single_self!(Vec2); +as_single_self!(Vec3); +as_single_self!(Vec3A); +as_single_self!(Vec4); +as_single_self!(Quat); + +impl AsSingle for f64 { + type Single = f32; + fn as_single(self) -> Self::Single { + self as f32 + } +} + +impl AsSingle for DVec2 { + type Single = Vec2; + fn as_single(self) -> Self::Single { + self.as_vec2() + } +} + +impl AsSingle for DVec3 { + type Single = Vec3; + fn as_single(self) -> Self::Single { + self.as_vec3() + } +} + +impl AsSingle for DVec4 { + type Single = Vec4; + fn as_single(self) -> Self::Single { + self.as_vec4() + } +} + +impl AsSingle for DQuat { + type Single = Quat; + fn as_single(self) -> Self::Single { + self.as_f32() + } +} + +#[cfg(feature = "f32")] +mod real { + use bevy::math::*; + use super::{AsReal, AsSingle}; + + as_real_self!(f32); + as_real_self!(Vec2); + as_real_self!(Vec3); + as_real_self!(Vec3A); + as_real_self!(Vec4); + as_real_self!(Quat); + + impl AsReal for f64 { + type Real = f32; + fn as_real(self) -> Self::Real { + self.as_single() + } + } + + impl AsReal for DVec2 { + type Real = Vec2; + fn as_real(self) -> Self::Real { + self.as_single() + } + } + + impl AsReal for DVec3 { + type Real = Vec3; + fn as_real(self) -> Self::Real { + self.as_single() + } + } + + impl AsReal for DVec4 { + type Real = Vec4; + fn as_real(self) -> Self::Real { + self.as_single() + } + } + + impl AsReal for DQuat { + type Real = Quat; + fn as_real(self) -> Self::Real { + self.as_single() + } + } +} + +#[cfg(feature = "f64")] +mod real { + use bevy::math::*; + use super::AsReal; + + as_real_self!(f64); + as_real_self!(DVec2); + as_real_self!(DVec3); + as_real_self!(DVec4); + as_real_self!(DQuat); + + impl AsReal for f32 { + type Real = f64; + fn as_real(self) -> Self::Real { + self as f64 + } + } + + impl AsReal for Vec2 { + type Real = DVec2; + fn as_real(self) -> Self::Real { + self.as_dvec2() + } + } + + impl AsReal for Vec3 { + type Real = DVec3; + fn as_real(self) -> Self::Real { + self.as_dvec3() + } + } + + impl AsReal for Vec3A { + type Real = DVec3; + fn as_real(self) -> Self::Real { + self.as_dvec3() + } + } + + impl AsReal for Vec4 { + type Real = DVec4; + fn as_real(self) -> Self::Real { + self.as_dvec4() + } + } + + impl AsReal for Quat { + type Real = DQuat; + fn as_real(self) -> Self::Real { + self.as_f64() + } + } +} diff --git a/src/utils/mod.rs b/src/utils/mod.rs index 5523dac0..d8ecd996 100644 --- a/src/utils/mod.rs +++ b/src/utils/mod.rs @@ -1,14 +1,31 @@ use bevy::prelude::Transform; use rapier::math::{Isometry, Real}; +pub mod as_real; +pub use as_real::*; + /// Converts a Rapier isometry to a Bevy transform. /// /// The translation is multiplied by the `physics_scale`. #[cfg(feature = "dim2")] pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform { + #[cfg(feature = "f32")] + let (translation, rotation) = { + use bevy::math::{Vec3, Quat}; + let translation: Vec3 = iso.translation.vector.into(); + let rotation = Quat::from_rotation_z(iso.rotation.angle()); + (translation, rotation) + }; + #[cfg(feature = "f64")] + let (translation, rotation) = { + use bevy::math::{DVec3, DQuat}; + let translation: DVec3 = iso.translation.vector.into(); + let rotation = DQuat::from_rotation_z(iso.rotation.angle()); + (translation, rotation) + }; Transform { - translation: (iso.translation.vector.push(0.0) * physics_scale).into(), - rotation: bevy::prelude::Quat::from_rotation_z(iso.rotation.angle()), + translation: translation.as_single(), + rotation: rotation.as_single(), ..Default::default() } } @@ -18,9 +35,23 @@ pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform /// The translation is multiplied by the `physics_scale`. #[cfg(feature = "dim3")] pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform { + #[cfg(feature = "f32")] + let (translation, rotation) = { + use bevy::math::{Vec3, Quat}; + let translation: Vec3 = iso.translation.vector.into(); + let rotation: Quat = iso.rotation.into(); + (translation, rotation) + }; + #[cfg(feature = "f64")] + let (translation, rotation) = { + use bevy::math::{DVec3, DQuat}; + let translation: DVec3 = iso.translation.vector.into(); + let rotation: DQuat = iso.rotation.into(); + (translation, rotation) + }; Transform { - translation: (iso.translation.vector * physics_scale).into(), - rotation: iso.rotation.into(), + translation: (translation * physics_scale).as_single(), + rotation: rotation.as_single(), ..Default::default() } } @@ -31,9 +62,11 @@ pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform #[cfg(feature = "dim2")] pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Isometry { use bevy::math::Vec3Swizzles; + let translation = transform.translation.as_real(); + let rotation = transform.rotation.to_scaled_axis().z.as_real(); Isometry::new( - (transform.translation / physics_scale).xy().into(), - transform.rotation.to_scaled_axis().z, + (translation / physics_scale).xy().into(), + rotation, ) } @@ -42,9 +75,11 @@ pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Is /// The translation is divided by the `physics_scale`. #[cfg(feature = "dim3")] pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Isometry { + let translation = transform.translation.as_real(); + let rotation = transform.rotation.as_real(); Isometry::from_parts( - (transform.translation / physics_scale).into(), - transform.rotation.into(), + (translation / physics_scale).into(), + rotation.into(), ) } From 62715ea65cddba4e2d379e22f5a75dd232606d99 Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 05:18:49 -0700 Subject: [PATCH 03/10] AsPrecise trait, most examples compile now --- bevy_rapier2d/examples/boxes2.rs | 2 +- bevy_rapier3d/examples/boxes3.rs | 6 +- bevy_rapier3d/examples/joints3.rs | 4 +- src/dynamics/fixed_joint.rs | 18 ++-- src/dynamics/generic_joint.rs | 26 +++--- src/dynamics/prismatic_joint.rs | 44 +++++----- src/dynamics/revolute_joint.rs | 25 +++--- src/dynamics/rope_joint.rs | 26 +++--- src/dynamics/spherical_joint.rs | 18 ++-- src/geometry/collider.rs | 2 +- src/geometry/collider_impl.rs | 75 ++++++++-------- src/lib.rs | 10 ++- src/plugin/context.rs | 14 +-- src/plugin/plugin.rs | 3 +- src/plugin/systems.rs | 10 +-- src/render/mod.rs | 8 +- src/utils/{as_real.rs => as_precise.rs} | 110 ++++++++++++------------ src/utils/mod.rs | 22 ++--- 18 files changed, 215 insertions(+), 208 deletions(-) rename src/utils/{as_real.rs => as_precise.rs} (52%) diff --git a/bevy_rapier2d/examples/boxes2.rs b/bevy_rapier2d/examples/boxes2.rs index a942c5a5..7ae08857 100644 --- a/bevy_rapier2d/examples/boxes2.rs +++ b/bevy_rapier2d/examples/boxes2.rs @@ -56,7 +56,7 @@ pub fn setup_physics(mut commands: Commands) { commands.spawn(( TransformBundle::from(Transform::from_xyz(x, y, 0.0)), RigidBody::Dynamic, - Collider::cuboid(rad, rad), + Collider::cuboid(rad.as_precise(), rad.as_precise()), )); } diff --git a/bevy_rapier3d/examples/boxes3.rs b/bevy_rapier3d/examples/boxes3.rs index e3d45bc5..9ec2877d 100644 --- a/bevy_rapier3d/examples/boxes3.rs +++ b/bevy_rapier3d/examples/boxes3.rs @@ -1,5 +1,5 @@ use bevy::prelude::*; -use bevy_rapier3d::{utils::as_real::*, prelude::*}; +use bevy_rapier3d::{utils::as_precise::*, prelude::*}; fn main() { App::new() @@ -34,7 +34,7 @@ pub fn setup_physics(mut commands: Commands) { commands.spawn(( TransformBundle::from(Transform::from_xyz(0.0, -ground_height, 0.0)), - Collider::cuboid(ground_size.as_real(), ground_height.as_real(), ground_size.as_real()), + Collider::cuboid(ground_size.as_precise(), ground_height.as_precise(), ground_size.as_precise()), )); /* @@ -72,7 +72,7 @@ pub fn setup_physics(mut commands: Commands) { child.spawn(( TransformBundle::from(Transform::from_xyz(x, y, z)), RigidBody::Dynamic, - Collider::cuboid(rad.as_real(), rad.as_real(), rad.as_real()), + Collider::cuboid(rad.as_precise(), rad.as_precise(), rad.as_precise()), ColliderDebugColor(colors[color % 3]), )); }); diff --git a/bevy_rapier3d/examples/joints3.rs b/bevy_rapier3d/examples/joints3.rs index a7cb84f9..96ad7d9b 100644 --- a/bevy_rapier3d/examples/joints3.rs +++ b/bevy_rapier3d/examples/joints3.rs @@ -25,7 +25,7 @@ fn setup_graphics(mut commands: Commands) { }); } -fn create_prismatic_joints(commands: &mut Commands, origin: Vect, num: usize) { +fn create_prismatic_joints(commands: &mut Commands, origin: Vec3, num: usize) { let rad = 0.4; let shift = 1.0; @@ -62,7 +62,7 @@ fn create_prismatic_joints(commands: &mut Commands, origin: Vect, num: usize) { } } -fn create_rope_joints(commands: &mut Commands, origin: Vect, num: usize) { +fn create_rope_joints(commands: &mut Commands, origin: Vec3, num: usize) { let rad = 0.4; let shift = 1.0; diff --git a/src/dynamics/fixed_joint.rs b/src/dynamics/fixed_joint.rs index 3bfe9346..ca1d7045 100644 --- a/src/dynamics/fixed_joint.rs +++ b/src/dynamics/fixed_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Rot, Vect}; +use crate::math::{Rot, Vect, AsPrecise}; use rapier::dynamics::JointAxesMask; #[derive(Copy, Clone, Debug, PartialEq)] @@ -65,8 +65,8 @@ impl FixedJoint { } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. - pub fn set_local_anchor1(&mut self, anchor1: Vect) -> &mut Self { - self.data.set_local_anchor1(anchor1); + pub fn set_local_anchor1(&mut self, anchor1: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor1(anchor1.as_precise()); self } @@ -77,8 +77,8 @@ impl FixedJoint { } /// Sets the joint’s anchor, expressed in the local-space of the second rigid-body. - pub fn set_local_anchor2(&mut self, anchor2: Vect) -> &mut Self { - self.data.set_local_anchor2(anchor2); + pub fn set_local_anchor2(&mut self, anchor2: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor2(anchor2.as_precise()); self } } @@ -115,15 +115,15 @@ impl FixedJointBuilder { /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. #[must_use] - pub fn local_anchor1(mut self, anchor1: Vect) -> Self { - self.0.set_local_anchor1(anchor1); + pub fn local_anchor1(mut self, anchor1: impl AsPrecise) -> Self { + self.0.set_local_anchor1(anchor1.as_precise()); 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: Vect) -> Self { - self.0.set_local_anchor2(anchor2); + pub fn local_anchor2(mut self, anchor2: impl AsPrecise) -> Self { + self.0.set_local_anchor2(anchor2.as_precise()); self } diff --git a/src/dynamics/generic_joint.rs b/src/dynamics/generic_joint.rs index 62c4da1f..5ddf8a41 100644 --- a/src/dynamics/generic_joint.rs +++ b/src/dynamics/generic_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{FixedJoint, PrismaticJoint, RevoluteJoint, RopeJoint}; -use crate::math::{Real, Rot, Vect}; +use crate::math::{Real, Rot, Vect, AsPrecise}; use rapier::dynamics::{ GenericJoint as RapierGenericJoint, JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel, @@ -116,8 +116,8 @@ impl GenericJoint { } /// 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: Vect) -> &mut Self { - self.raw.set_local_axis1(local_axis.try_into().unwrap()); + pub fn set_local_axis1(&mut self, local_axis: impl AsPrecise) -> &mut Self { + self.raw.set_local_axis1(local_axis.as_precise().try_into().unwrap()); self } @@ -128,8 +128,8 @@ impl GenericJoint { } /// 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: Vect) -> &mut Self { - self.raw.set_local_axis2(local_axis.try_into().unwrap()); + pub fn set_local_axis2(&mut self, local_axis: impl AsPrecise) -> &mut Self { + self.raw.set_local_axis2(local_axis.as_precise().try_into().unwrap()); self } @@ -140,8 +140,8 @@ impl GenericJoint { } /// Sets anchor of this joint, expressed in the first rigid-body’s local-space. - pub fn set_local_anchor1(&mut self, anchor1: Vect) -> &mut Self { - self.raw.set_local_anchor1(anchor1.into()); + pub fn set_local_anchor1(&mut self, anchor1: impl AsPrecise) -> &mut Self { + self.raw.set_local_anchor1(anchor1.as_precise().into()); self } @@ -152,8 +152,8 @@ impl GenericJoint { } /// Sets anchor of this joint, expressed in the second rigid-body’s local-space. - pub fn set_local_anchor2(&mut self, anchor2: Vect) -> &mut Self { - self.raw.set_local_anchor2(anchor2.into()); + pub fn set_local_anchor2(&mut self, anchor2: impl AsPrecise) -> &mut Self { + self.raw.set_local_anchor2(anchor2.as_precise().into()); self } @@ -361,15 +361,15 @@ impl GenericJointBuilder { /// Sets the anchor of this joint, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_anchor1(mut self, anchor1: Vect) -> Self { - self.0.set_local_anchor1(anchor1); + pub fn local_anchor1(mut self, anchor1: impl AsPrecise) -> Self { + self.0.set_local_anchor1(anchor1.as_precise()); self } /// Sets the anchor of this joint, expressed in the second rigid-body’s local-space. #[must_use] - pub fn local_anchor2(mut self, anchor2: Vect) -> Self { - self.0.set_local_anchor2(anchor2); + pub fn local_anchor2(mut self, anchor2: impl AsPrecise) -> Self { + self.0.set_local_anchor2(anchor2.as_precise()); self } diff --git a/src/dynamics/prismatic_joint.rs b/src/dynamics/prismatic_joint.rs index 5d3f35e4..f6e2ac40 100644 --- a/src/dynamics/prismatic_joint.rs +++ b/src/dynamics/prismatic_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Real, Vect}; +use crate::math::{Real, Vect, AsPrecise}; use rapier::dynamics::{JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel}; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] @@ -14,10 +14,10 @@ impl PrismaticJoint { /// Creates a new prismatic joint allowing only relative translations along the specified axis. /// /// This axis is expressed in the local-space of both rigid-bodies. - pub fn new(axis: Vect) -> Self { + pub fn new(axis: impl AsPrecise) -> Self { let data = GenericJointBuilder::new(JointAxesMask::LOCKED_PRISMATIC_AXES) - .local_axis1(axis) - .local_axis2(axis) + .local_axis1(axis.as_precise()) + .local_axis2(axis.as_precise()) .build(); Self { data } } @@ -45,8 +45,8 @@ impl PrismaticJoint { } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. - pub fn set_local_anchor1(&mut self, anchor1: Vect) -> &mut Self { - self.data.set_local_anchor1(anchor1); + pub fn set_local_anchor1(&mut self, anchor1: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor1(anchor1.as_precise()); self } @@ -57,8 +57,8 @@ impl PrismaticJoint { } /// Sets the joint’s anchor, expressed in the local-space of the second rigid-body. - pub fn set_local_anchor2(&mut self, anchor2: Vect) -> &mut Self { - self.data.set_local_anchor2(anchor2); + pub fn set_local_anchor2(&mut self, anchor2: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor2(anchor2.as_precise()); self } @@ -69,8 +69,8 @@ impl PrismaticJoint { } /// Sets the principal axis of the joint, expressed in the local-space of the first rigid-body. - pub fn set_local_axis1(&mut self, axis1: Vect) -> &mut Self { - self.data.set_local_axis1(axis1); + pub fn set_local_axis1(&mut self, axis1: impl AsPrecise) -> &mut Self { + self.data.set_local_axis1(axis1.as_precise()); self } @@ -81,8 +81,8 @@ impl PrismaticJoint { } /// Sets the principal axis of the joint, expressed in the local-space of the second rigid-body. - pub fn set_local_axis2(&mut self, axis2: Vect) -> &mut Self { - self.data.set_local_axis2(axis2); + pub fn set_local_axis2(&mut self, axis2: impl AsPrecise) -> &mut Self { + self.data.set_local_axis2(axis2.as_precise()); self } @@ -166,35 +166,35 @@ impl PrismaticJointBuilder { /// Creates a new builder for prismatic joints. /// /// This axis is expressed in the local-space of both rigid-bodies. - pub fn new(axis: Vect) -> Self { - Self(PrismaticJoint::new(axis)) + pub fn new(axis: impl AsPrecise) -> Self { + Self(PrismaticJoint::new(axis.as_precise())) } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. #[must_use] - pub fn local_anchor1(mut self, anchor1: Vect) -> Self { - self.0.set_local_anchor1(anchor1); + pub fn local_anchor1(mut self, anchor1: impl AsPrecise) -> Self { + self.0.set_local_anchor1(anchor1.as_precise()); 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: Vect) -> Self { - self.0.set_local_anchor2(anchor2); + pub fn local_anchor2(mut self, anchor2: impl AsPrecise) -> Self { + self.0.set_local_anchor2(anchor2.as_precise()); self } /// Sets the principal axis of the joint, expressed in the local-space of the first rigid-body. #[must_use] - pub fn local_axis1(mut self, axis1: Vect) -> Self { - self.0.set_local_axis1(axis1); + pub fn local_axis1(mut self, axis1: impl AsPrecise) -> Self { + self.0.set_local_axis1(axis1.as_precise()); self } /// Sets the principal axis of the joint, expressed in the local-space of the second rigid-body. #[must_use] - pub fn local_axis2(mut self, axis2: Vect) -> Self { - self.0.set_local_axis2(axis2); + pub fn local_axis2(mut self, axis2: impl AsPrecise) -> Self { + self.0.set_local_axis2(axis2.as_precise()); self } diff --git a/src/dynamics/revolute_joint.rs b/src/dynamics/revolute_joint.rs index 590c033c..095b69ef 100644 --- a/src/dynamics/revolute_joint.rs +++ b/src/dynamics/revolute_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Real, Vect}; +use crate::math::{Real, Vect, AsPrecise}; use rapier::dynamics::{JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel}; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] @@ -29,7 +29,8 @@ impl RevoluteJoint { /// /// This axis is expressed in the local-space of both rigid-bodies. #[cfg(feature = "dim3")] - pub fn new(axis: Vect) -> Self { + pub fn new(axis: impl AsPrecise) -> Self { + let axis = axis.as_precise(); let data = GenericJointBuilder::new(JointAxesMask::LOCKED_REVOLUTE_AXES) .local_axis1(axis) .local_axis2(axis) @@ -60,8 +61,8 @@ impl RevoluteJoint { } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. - pub fn set_local_anchor1(&mut self, anchor1: Vect) -> &mut Self { - self.data.set_local_anchor1(anchor1); + pub fn set_local_anchor1(&mut self, anchor1: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor1(anchor1.as_precise()); self } @@ -72,8 +73,8 @@ impl RevoluteJoint { } /// Sets the joint’s anchor, expressed in the local-space of the second rigid-body. - pub fn set_local_anchor2(&mut self, anchor2: Vect) -> &mut Self { - self.data.set_local_anchor2(anchor2); + pub fn set_local_anchor2(&mut self, anchor2: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor2(anchor2.as_precise()); self } @@ -171,21 +172,21 @@ impl RevoluteJointBuilder { /// /// This axis is expressed in the local-space of both rigid-bodies. #[cfg(feature = "dim3")] - pub fn new(axis: Vect) -> Self { - Self(RevoluteJoint::new(axis)) + pub fn new(axis: impl AsPrecise) -> Self { + Self(RevoluteJoint::new(axis.as_precise())) } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. #[must_use] - pub fn local_anchor1(mut self, anchor1: Vect) -> Self { - self.0.set_local_anchor1(anchor1); + pub fn local_anchor1(mut self, anchor1: impl AsPrecise) -> Self { + self.0.set_local_anchor1(anchor1.as_precise()); 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: Vect) -> Self { - self.0.set_local_anchor2(anchor2); + pub fn local_anchor2(mut self, anchor2: impl AsPrecise) -> Self { + self.0.set_local_anchor2(anchor2.as_precise()); self } diff --git a/src/dynamics/rope_joint.rs b/src/dynamics/rope_joint.rs index cac1cb65..884e095a 100644 --- a/src/dynamics/rope_joint.rs +++ b/src/dynamics/rope_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Real, Vect}; +use crate::math::{Real, Vect, AsPrecise}; use rapier::dynamics::{JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel}; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] @@ -42,8 +42,8 @@ impl RopeJoint { } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. - pub fn set_local_anchor1(&mut self, anchor1: Vect) -> &mut Self { - self.data.set_local_anchor1(anchor1); + pub fn set_local_anchor1(&mut self, anchor1: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor1(anchor1.as_precise()); self } @@ -54,8 +54,8 @@ impl RopeJoint { } /// Sets the joint’s anchor, expressed in the local-space of the second rigid-body. - pub fn set_local_anchor2(&mut self, anchor2: Vect) -> &mut Self { - self.data.set_local_anchor2(anchor2); + pub fn set_local_anchor2(&mut self, anchor2: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor2(anchor2.as_precise()); self } @@ -66,8 +66,8 @@ impl RopeJoint { } /// Sets the principal axis of the joint, expressed in the local-space of the first rigid-body. - pub fn set_local_axis1(&mut self, axis1: Vect) -> &mut Self { - self.data.set_local_axis1(axis1); + pub fn set_local_axis1(&mut self, axis1: impl AsPrecise) -> &mut Self { + self.data.set_local_axis1(axis1.as_precise()); self } @@ -78,8 +78,8 @@ impl RopeJoint { } /// Sets the principal axis of the joint, expressed in the local-space of the second rigid-body. - pub fn set_local_axis2(&mut self, axis2: Vect) -> &mut Self { - self.data.set_local_axis2(axis2); + pub fn set_local_axis2(&mut self, axis2: impl AsPrecise) -> &mut Self { + self.data.set_local_axis2(axis2.as_precise()); self } @@ -199,15 +199,15 @@ impl RopeJointBuilder { /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. #[must_use] - pub fn local_anchor1(mut self, anchor1: Vect) -> Self { - self.0.set_local_anchor1(anchor1); + pub fn local_anchor1(mut self, anchor1: impl AsPrecise) -> Self { + self.0.set_local_anchor1(anchor1.as_precise()); 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: Vect) -> Self { - self.0.set_local_anchor2(anchor2); + pub fn local_anchor2(mut self, anchor2: impl AsPrecise) -> Self { + self.0.set_local_anchor2(anchor2.as_precise()); self } diff --git a/src/dynamics/spherical_joint.rs b/src/dynamics/spherical_joint.rs index a8619d53..dc92fa39 100644 --- a/src/dynamics/spherical_joint.rs +++ b/src/dynamics/spherical_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Real, Vect}; +use crate::math::{Real, Vect, AsPrecise}; use rapier::dynamics::{JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel}; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] @@ -46,8 +46,8 @@ impl SphericalJoint { } /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. - pub fn set_local_anchor1(&mut self, anchor1: Vect) -> &mut Self { - self.data.set_local_anchor1(anchor1); + pub fn set_local_anchor1(&mut self, anchor1: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor1(anchor1.as_precise()); self } @@ -58,8 +58,8 @@ impl SphericalJoint { } /// Sets the joint’s anchor, expressed in the local-space of the second rigid-body. - pub fn set_local_anchor2(&mut self, anchor2: Vect) -> &mut Self { - self.data.set_local_anchor2(anchor2); + pub fn set_local_anchor2(&mut self, anchor2: impl AsPrecise) -> &mut Self { + self.data.set_local_anchor2(anchor2.as_precise()); self } @@ -157,15 +157,15 @@ impl SphericalJointBuilder { /// Sets the joint’s anchor, expressed in the local-space of the first rigid-body. #[must_use] - pub fn local_anchor1(mut self, anchor1: Vect) -> Self { - self.0.set_local_anchor1(anchor1); + pub fn local_anchor1(mut self, anchor1: impl AsPrecise) -> Self { + self.0.set_local_anchor1(anchor1.as_precise()); 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: Vect) -> Self { - self.0.set_local_anchor2(anchor2); + pub fn local_anchor2(mut self, anchor2: impl AsPrecise) -> Self { + self.0.set_local_anchor2(anchor2.as_precise()); self } diff --git a/src/geometry/collider.rs b/src/geometry/collider.rs index 8a70b1be..02111e7b 100644 --- a/src/geometry/collider.rs +++ b/src/geometry/collider.rs @@ -11,7 +11,7 @@ use rapier::prelude::{ColliderHandle, InteractionGroups, SharedShape}; use crate::dynamics::{CoefficientCombineRule, MassProperties}; use crate::math::{Real, Vect}; -use crate::utils::as_real::*; +use crate::utils::as_precise::*; /// The Rapier handle of a collider that was inserted to the physics scene. #[derive(Copy, Clone, Debug, Component)] diff --git a/src/geometry/collider_impl.rs b/src/geometry/collider_impl.rs index f526ecd8..e2b255ee 100644 --- a/src/geometry/collider_impl.rs +++ b/src/geometry/collider_impl.rs @@ -13,6 +13,7 @@ use super::{get_snapped_scale, shape_views::*}; use crate::geometry::ComputedColliderShape; use crate::geometry::{Collider, PointProjection, RayIntersection, TriMeshFlags, VHACDParameters}; use crate::math::{Real, Rot, Vect}; +use crate::utils::as_precise::AsPrecise; impl Collider { /// The scaling factor that was applied to this collider. @@ -37,111 +38,111 @@ impl Collider { } /// Initialize a new collider with a ball shape defined by its radius. - pub fn ball(radius: Real) -> Self { - SharedShape::ball(radius).into() + pub fn ball(radius: impl AsPrecise) -> Self { + SharedShape::ball(radius.as_precise()).into() } /// Initialize a new collider build with a half-space shape defined by the outward normal /// of its planar boundary. - pub fn halfspace(outward_normal: Vect) -> Option { + pub fn halfspace(outward_normal: impl AsPrecise) -> Option { use rapier::na::Unit; - let normal = Vector::from(outward_normal); + let normal = Vector::from(outward_normal.as_precise()); Unit::try_new(normal, 1.0e-6).map(|n| SharedShape::halfspace(n).into()) } /// Initialize a new collider with a cylindrical shape defined by its half-height /// (along along the y axis) and its radius. #[cfg(feature = "dim3")] - pub fn cylinder(half_height: Real, radius: Real) -> Self { - SharedShape::cylinder(half_height, radius).into() + pub fn cylinder(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + SharedShape::cylinder(half_height.as_precise(), radius.as_precise()).into() } /// Initialize a new collider with a rounded cylindrical shape defined by its half-height /// (along along the y axis), its radius, and its roundedness (the /// radius of the sphere used for dilating the cylinder). #[cfg(feature = "dim3")] - pub fn round_cylinder(half_height: Real, radius: Real, border_radius: Real) -> Self { - SharedShape::round_cylinder(half_height, radius, border_radius).into() + pub fn round_cylinder(half_height: impl AsPrecise, radius: impl AsPrecise, border_radius: impl AsPrecise) -> Self { + SharedShape::round_cylinder(half_height.as_precise(), radius.as_precise(), border_radius.as_precise()).into() } /// Initialize a new collider with a cone shape defined by its half-height /// (along along the y axis) and its basis radius. #[cfg(feature = "dim3")] - pub fn cone(half_height: Real, radius: Real) -> Self { - SharedShape::cone(half_height, radius).into() + pub fn cone(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + SharedShape::cone(half_height.as_precise(), radius.as_precise()).into() } /// Initialize a new collider with a rounded cone shape defined by its half-height /// (along along the y axis), its radius, and its roundedness (the /// radius of the sphere used for dilating the cylinder). #[cfg(feature = "dim3")] - pub fn round_cone(half_height: Real, radius: Real, border_radius: Real) -> Self { - SharedShape::round_cone(half_height, radius, border_radius).into() + pub fn round_cone(half_height: impl AsPrecise, radius: impl AsPrecise, border_radius: impl AsPrecise) -> Self { + SharedShape::round_cone(half_height.as_precise(), radius.as_precise(), border_radius.as_precise()).into() } /// Initialize a new collider with a cuboid shape defined by its half-extents. #[cfg(feature = "dim2")] - pub fn cuboid(half_x: Real, half_y: Real) -> Self { - SharedShape::cuboid(half_x, half_y).into() + pub fn cuboid(half_x: impl AsPrecise, half_y: impl AsPrecise) -> Self { + SharedShape::cuboid(half_x.as_precise(), half_y.as_precise()).into() } /// Initialize a new collider with a round cuboid shape defined by its half-extents /// and border radius. #[cfg(feature = "dim2")] - pub fn round_cuboid(half_x: Real, half_y: Real, border_radius: Real) -> Self { - SharedShape::round_cuboid(half_x, half_y, border_radius).into() + pub fn round_cuboid(half_x: impl AsPrecise, half_y: impl AsPrecise, border_radius: impl AsPrecise) -> Self { + SharedShape::round_cuboid(half_x.as_precise(), half_y.as_precise(), border_radius.as_precise()).into() } /// Initialize a new collider with a capsule shape. - pub fn capsule(start: Vect, end: Vect, radius: Real) -> Self { - SharedShape::capsule(start.into(), end.into(), radius).into() + pub fn capsule(start: impl AsPrecise, end: impl AsPrecise, radius: impl AsPrecise) -> Self { + SharedShape::capsule(start.as_precise().into(), end.as_precise().into(), radius.as_precise()).into() } /// Initialize a new collider with a capsule shape aligned with the `x` axis. - pub fn capsule_x(half_height: Real, radius: Real) -> Self { - let p = Point::from(Vector::x() * half_height); - SharedShape::capsule(-p, p, radius).into() + pub fn capsule_x(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + let p = Point::from(Vector::x() * half_height.as_precise()); + SharedShape::capsule(-p, p, radius.as_precise()).into() } /// Initialize a new collider with a capsule shape aligned with the `y` axis. - pub fn capsule_y(half_height: Real, radius: Real) -> Self { - let p = Point::from(Vector::y() * half_height); - SharedShape::capsule(-p, p, radius).into() + pub fn capsule_y(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + let p = Point::from(Vector::y() * half_height.as_precise()); + SharedShape::capsule(-p, p, radius.as_precise()).into() } /// Initialize a new collider with a capsule shape aligned with the `z` axis. #[cfg(feature = "dim3")] - pub fn capsule_z(half_height: Real, radius: Real) -> Self { - let p = Point::from(Vector::z() * half_height); - SharedShape::capsule(-p, p, radius).into() + pub fn capsule_z(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + let p = Point::from(Vector::z() * half_height.as_precise()); + SharedShape::capsule(-p, p, radius.as_precise()).into() } /// Initialize a new collider with a cuboid shape defined by its half-extents. #[cfg(feature = "dim3")] - pub fn cuboid(hx: Real, hy: Real, hz: Real) -> Self { - SharedShape::cuboid(hx, hy, hz).into() + pub fn cuboid(hx: impl AsPrecise, hy: impl AsPrecise, hz: impl AsPrecise) -> Self { + SharedShape::cuboid(hx.as_precise(), hy.as_precise(), hz.as_precise()).into() } /// Initialize a new collider with a round cuboid shape defined by its half-extents /// and border radius. #[cfg(feature = "dim3")] - pub fn round_cuboid(half_x: Real, half_y: Real, half_z: Real, border_radius: Real) -> Self { - SharedShape::round_cuboid(half_x, half_y, half_z, border_radius).into() + pub fn round_cuboid(half_x: impl AsPrecise, half_y: impl AsPrecise, half_z: impl AsPrecise, border_radius: impl AsPrecise) -> Self { + SharedShape::round_cuboid(half_x.as_precise(), half_y.as_precise(), half_z.as_precise(), border_radius.as_precise()).into() } /// Initializes a collider with a segment shape. - pub fn segment(a: Vect, b: Vect) -> Self { - SharedShape::segment(a.into(), b.into()).into() + pub fn segment(a: impl AsPrecise, b: impl AsPrecise) -> Self { + SharedShape::segment(a.as_precise().into(), b.as_precise().into()).into() } /// Initializes a collider with a triangle shape. - pub fn triangle(a: Vect, b: Vect, c: Vect) -> Self { - SharedShape::triangle(a.into(), b.into(), c.into()).into() + pub fn triangle(a: impl AsPrecise, b: impl AsPrecise, c: impl AsPrecise) -> Self { + SharedShape::triangle(a.as_precise().into(), b.as_precise().into(), c.as_precise().into()).into() } /// Initializes a collider with a triangle shape with round corners. - pub fn round_triangle(a: Vect, b: Vect, c: Vect, border_radius: Real) -> Self { - SharedShape::round_triangle(a.into(), b.into(), c.into(), border_radius).into() + pub fn round_triangle(a: impl AsPrecise, b: impl AsPrecise, c: impl AsPrecise, border_radius: impl AsPrecise) -> Self { + SharedShape::round_triangle(a.as_precise().into(), b.as_precise().into(), c.as_precise().into(), border_radius.as_precise()).into() } /// Initializes a collider with a polyline shape defined by its vertex and index buffers. diff --git a/src/lib.rs b/src/lib.rs index e97bacfb..8b57f9b9 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -20,7 +20,7 @@ pub extern crate nalgebra as na; #[cfg(all(feature = "dim2", feature = "f32"))] pub extern crate rapier2d as rapier; #[cfg(all(feature = "dim2", feature = "f64"))] -pub extern crate rapier3d_f64 as rapier; +pub extern crate rapier2d_f64 as rapier; #[cfg(all(feature = "dim3", feature = "f32"))] pub extern crate rapier3d as rapier; #[cfg(all(feature = "dim3", feature = "f64"))] @@ -28,9 +28,11 @@ pub extern crate rapier3d_f64 as rapier; pub use rapier::parry; /// Type aliases to select the right vector/rotation types based -/// on the dimension used by the engine. +/// on the dimension and precision used by the engine. #[cfg(feature = "dim2")] pub mod math { + pub use crate::utils::as_precise::*; + /// The real type (f32 or f64). pub type Real = rapier::math::Real; /// The vector type. @@ -43,9 +45,11 @@ pub mod math { } /// Type aliases to select the right vector/rotation types based -/// on the dimension used by the engine. +/// on the dimension and precision used by the engine. #[cfg(feature = "dim3")] pub mod math { + pub use crate::utils::as_precise::*; + /// The real type (f32 or f64). pub type Real = rapier::math::Real; /// The vector type. diff --git a/src/plugin/context.rs b/src/plugin/context.rs index ce1398a5..087d0bc5 100644 --- a/src/plugin/context.rs +++ b/src/plugin/context.rs @@ -18,7 +18,7 @@ use crate::control::{CharacterCollision, MoveShapeOptions, MoveShapeOutput}; use crate::dynamics::TransformInterpolation; use crate::plugin::configuration::{SimulationToRenderTime, TimestepMode}; use crate::prelude::{CollisionGroups, RapierRigidBodyHandle}; -use crate::utils::as_real::*; +use crate::utils::as_precise::*; use rapier::control::CharacterAutostep; /// The Rapier context, containing all the state of the physics engine. @@ -233,7 +233,7 @@ impl RapierContext { time_scale, substeps, } => { - sim_to_render_time.diff += time.delta_seconds_f64().as_single(); + sim_to_render_time.diff += time.delta_seconds_f64().as_precise(); while sim_to_render_time.diff > 0.0 { // NOTE: in this comparison we do the same computations we @@ -283,7 +283,7 @@ impl RapierContext { } => { let mut substep_integration_parameters = self.integration_parameters; substep_integration_parameters.dt = - (time.delta_seconds_f64().as_single() * time_scale).min(max_dt) / (substeps as Real); + (time.delta_seconds_f64().as_precise() * time_scale).min(max_dt) / (substeps as Real); for _ in 0..substeps { self.pipeline.step( @@ -735,13 +735,13 @@ impl RapierContext { use bevy::math::Vec3Swizzles; #[cfg(feature = "dim2")] let scaled_aabb = rapier::prelude::Aabb { - mins: (aabb.min().xy().as_real() / scale).into(), - maxs: (aabb.max().xy().as_real() / scale).into(), + mins: (aabb.min().xy().as_precise() / scale).into(), + maxs: (aabb.max().xy().as_precise() / scale).into(), }; #[cfg(feature = "dim3")] let scaled_aabb = rapier::prelude::Aabb { - mins: (aabb.min().as_real() / scale).into(), - maxs: (aabb.max().as_real() / scale).into(), + mins: (aabb.min().as_precise() / scale).into(), + maxs: (aabb.max().as_precise() / scale).into(), }; #[allow(clippy::redundant_closure)] // False-positive, we can't move callback, closure becomes `FnOnce` diff --git a/src/plugin/plugin.rs b/src/plugin/plugin.rs index cf2120bc..ebd783dc 100644 --- a/src/plugin/plugin.rs +++ b/src/plugin/plugin.rs @@ -2,6 +2,7 @@ use crate::pipeline::{CollisionEvent, ContactForceEvent}; use crate::plugin::configuration::SimulationToRenderTime; use crate::plugin::{systems, RapierConfiguration, RapierContext}; use crate::prelude::*; +use crate::math::Real; use bevy::ecs::{ event::Events, schedule::{ScheduleLabel, SystemConfigs}, @@ -53,7 +54,7 @@ where /// /// This conversion unit assumes that the 2D camera uses an unscaled projection. #[cfg(feature = "dim2")] - pub fn pixels_per_meter(pixels_per_meter: f32) -> Self { + pub fn pixels_per_meter(pixels_per_meter: Real) -> Self { Self { physics_scale: pixels_per_meter, default_system_setup: true, diff --git a/src/plugin/systems.rs b/src/plugin/systems.rs index 63d3ddf3..5c545abf 100644 --- a/src/plugin/systems.rs +++ b/src/plugin/systems.rs @@ -18,7 +18,7 @@ use crate::prelude::{ BevyPhysicsHooks, BevyPhysicsHooksAdapter, CollidingEntities, KinematicCharacterController, KinematicCharacterControllerOutput, MassModifiedEvent, RigidBodyDisabled, }; -use crate::utils::{self, as_real::*}; +use crate::utils::{self, as_precise::*}; use bevy::ecs::system::{StaticSystemParam, SystemParamItem}; use bevy::prelude::*; use rapier::prelude::*; @@ -100,15 +100,15 @@ pub fn apply_scale( let effective_scale = match custom_scale { Some(ColliderScale::Absolute(scale)) => *scale, Some(ColliderScale::Relative(scale)) => { - *scale * transform.compute_transform().scale.xy().as_real() + *scale * transform.compute_transform().scale.xy().as_precise() } - None => transform.compute_transform().scale.xy().as_real(), + None => transform.compute_transform().scale.xy().as_precise(), }; #[cfg(feature = "dim3")] let effective_scale = match custom_scale { Some(ColliderScale::Absolute(scale)) => *scale, - Some(ColliderScale::Relative(scale)) => *scale * transform.compute_transform().scale.as_real(), - None => transform.compute_transform().scale.as_real(), + Some(ColliderScale::Relative(scale)) => *scale * transform.compute_transform().scale.as_precise(), + None => transform.compute_transform().scale.as_precise(), }; if shape.scale != crate::geometry::get_snapped_scale(effective_scale) { diff --git a/src/render/mod.rs b/src/render/mod.rs index cb504ce2..64d9c75b 100644 --- a/src/render/mod.rs +++ b/src/render/mod.rs @@ -95,7 +95,7 @@ impl Plugin for RapierDebugRenderPlugin { } struct BevyLinesRenderBackend<'world, 'state, 'a, 'b> { - physics_scale: f32, + physics_scale: Real, custom_colors: Query<'world, 'state, &'a ColliderDebugColor>, context: &'b RapierContext, gizmos: Gizmos<'state>, @@ -143,7 +143,7 @@ impl<'world, 'state, 'a, 'b> DebugRenderBackend for BevyLinesRenderBackend<'worl b: Point, color: [f32; 4], ) { - let scale = self.physics_scale; + let scale = self.physics_scale as f32; let color = self.object_color(object, color); self.gizmos.line( [a.x as f32 * scale, a.y as f32 * scale, a.z as f32 * scale].into(), @@ -164,14 +164,14 @@ fn debug_render_scene( } let mut backend = BevyLinesRenderBackend { - physics_scale: rapier_context.physics_scale as f32, + physics_scale: rapier_context.physics_scale, custom_colors, context: &rapier_context, gizmos, }; let unscaled_style = render_context.pipeline.style; - render_context.pipeline.style.rigid_body_axes_length /= rapier_context.physics_scale as f32; + render_context.pipeline.style.rigid_body_axes_length /= rapier_context.physics_scale; render_context.pipeline.render( &mut backend, &rapier_context.bodies, diff --git a/src/utils/as_real.rs b/src/utils/as_precise.rs similarity index 52% rename from src/utils/as_real.rs rename to src/utils/as_precise.rs index 7cff3f6f..fc7840dd 100644 --- a/src/utils/as_real.rs +++ b/src/utils/as_precise.rs @@ -2,9 +2,9 @@ use bevy::math::*; /// Convert value into the precision the compilation is using. -pub trait AsReal { - type Real; - fn as_real(self) -> Self::Real; +pub trait AsPrecise: Clone + Copy { + type Out; + fn as_precise(self) -> Self::Out; } /// Convert value into single precision floating point. @@ -13,11 +13,11 @@ pub trait AsSingle { fn as_single(self) -> Self::Single; } -macro_rules! as_real_self { +macro_rules! as_precise_self { ($ty:ty) => { - impl AsReal for $ty { - type Real = $ty; - fn as_real(self) -> Self::Real { + impl AsPrecise for $ty { + type Out = $ty; + fn as_precise(self) -> Self::Out { self } } @@ -80,46 +80,46 @@ impl AsSingle for DQuat { #[cfg(feature = "f32")] mod real { use bevy::math::*; - use super::{AsReal, AsSingle}; - - as_real_self!(f32); - as_real_self!(Vec2); - as_real_self!(Vec3); - as_real_self!(Vec3A); - as_real_self!(Vec4); - as_real_self!(Quat); - - impl AsReal for f64 { - type Real = f32; - fn as_real(self) -> Self::Real { + use super::{AsPrecise, AsSingle}; + + as_precise_self!(f32); + as_precise_self!(Vec2); + as_precise_self!(Vec3); + as_precise_self!(Vec3A); + as_precise_self!(Vec4); + as_precise_self!(Quat); + + impl AsPrecise for f64 { + type Out = f32; + fn as_precise(self) -> Self::Out { self.as_single() } } - impl AsReal for DVec2 { - type Real = Vec2; - fn as_real(self) -> Self::Real { + impl AsPrecise for DVec2 { + type Out = Vec2; + fn as_precise(self) -> Self::Out { self.as_single() } } - impl AsReal for DVec3 { - type Real = Vec3; - fn as_real(self) -> Self::Real { + impl AsPrecise for DVec3 { + type Out = Vec3; + fn as_precise(self) -> Self::Out { self.as_single() } } - impl AsReal for DVec4 { - type Real = Vec4; - fn as_real(self) -> Self::Real { + impl AsPrecise for DVec4 { + type Out = Vec4; + fn as_precise(self) -> Self::Out { self.as_single() } } - impl AsReal for DQuat { - type Real = Quat; - fn as_real(self) -> Self::Real { + impl AsPrecise for DQuat { + type Out = Quat; + fn as_precise(self) -> Self::Out { self.as_single() } } @@ -128,52 +128,52 @@ mod real { #[cfg(feature = "f64")] mod real { use bevy::math::*; - use super::AsReal; + use super::AsPrecise; - as_real_self!(f64); - as_real_self!(DVec2); - as_real_self!(DVec3); - as_real_self!(DVec4); - as_real_self!(DQuat); + as_precise_self!(f64); + as_precise_self!(DVec2); + as_precise_self!(DVec3); + as_precise_self!(DVec4); + as_precise_self!(DQuat); - impl AsReal for f32 { - type Real = f64; - fn as_real(self) -> Self::Real { + impl AsPrecise for f32 { + type Out = f64; + fn as_precise(self) -> Self::Out { self as f64 } } - impl AsReal for Vec2 { - type Real = DVec2; - fn as_real(self) -> Self::Real { + impl AsPrecise for Vec2 { + type Out = DVec2; + fn as_precise(self) -> Self::Out { self.as_dvec2() } } - impl AsReal for Vec3 { - type Real = DVec3; - fn as_real(self) -> Self::Real { + impl AsPrecise for Vec3 { + type Out = DVec3; + fn as_precise(self) -> Self::Out { self.as_dvec3() } } - impl AsReal for Vec3A { - type Real = DVec3; - fn as_real(self) -> Self::Real { + impl AsPrecise for Vec3A { + type Out = DVec3; + fn as_precise(self) -> Self::Out { self.as_dvec3() } } - impl AsReal for Vec4 { - type Real = DVec4; - fn as_real(self) -> Self::Real { + impl AsPrecise for Vec4 { + type Out = DVec4; + fn as_precise(self) -> Self::Out { self.as_dvec4() } } - impl AsReal for Quat { - type Real = DQuat; - fn as_real(self) -> Self::Real { + impl AsPrecise for Quat { + type Out = DQuat; + fn as_precise(self) -> Self::Out { self.as_f64() } } diff --git a/src/utils/mod.rs b/src/utils/mod.rs index d8ecd996..6b55c4da 100644 --- a/src/utils/mod.rs +++ b/src/utils/mod.rs @@ -1,8 +1,8 @@ use bevy::prelude::Transform; use rapier::math::{Isometry, Real}; -pub mod as_real; -pub use as_real::*; +pub mod as_precise; +pub use as_precise::*; /// Converts a Rapier isometry to a Bevy transform. /// @@ -11,20 +11,20 @@ pub use as_real::*; pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform { #[cfg(feature = "f32")] let (translation, rotation) = { - use bevy::math::{Vec3, Quat}; - let translation: Vec3 = iso.translation.vector.into(); + use bevy::math::{Vec2, Quat}; + let translation: Vec2 = iso.translation.vector.into(); let rotation = Quat::from_rotation_z(iso.rotation.angle()); (translation, rotation) }; #[cfg(feature = "f64")] let (translation, rotation) = { - use bevy::math::{DVec3, DQuat}; - let translation: DVec3 = iso.translation.vector.into(); + use bevy::math::{DVec2, DQuat}; + let translation: DVec2 = iso.translation.vector.into(); let rotation = DQuat::from_rotation_z(iso.rotation.angle()); (translation, rotation) }; Transform { - translation: translation.as_single(), + translation: translation.as_single().extend(0.0), rotation: rotation.as_single(), ..Default::default() } @@ -62,8 +62,8 @@ pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform #[cfg(feature = "dim2")] pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Isometry { use bevy::math::Vec3Swizzles; - let translation = transform.translation.as_real(); - let rotation = transform.rotation.to_scaled_axis().z.as_real(); + let translation = transform.translation.as_precise(); + let rotation = transform.rotation.to_scaled_axis().z.as_precise(); Isometry::new( (translation / physics_scale).xy().into(), rotation, @@ -75,8 +75,8 @@ pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Is /// The translation is divided by the `physics_scale`. #[cfg(feature = "dim3")] pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Isometry { - let translation = transform.translation.as_real(); - let rotation = transform.rotation.as_real(); + let translation = transform.translation.as_precise(); + let rotation = transform.rotation.as_precise(); Isometry::from_parts( (translation / physics_scale).into(), rotation.into(), From 253df7845be323c869def1e54759d5da99532a31 Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 05:52:48 -0700 Subject: [PATCH 04/10] Convenience conversion so users don't need to manually convert all of the time --- bevy_rapier3d/examples/static_trimesh3.rs | 12 ++-- src/geometry/collider_impl.rs | 72 ++++++++++++----------- src/plugin/context.rs | 32 +++++----- 3 files changed, 59 insertions(+), 57 deletions(-) diff --git a/bevy_rapier3d/examples/static_trimesh3.rs b/bevy_rapier3d/examples/static_trimesh3.rs index 09c6e4bb..7fcd1a11 100644 --- a/bevy_rapier3d/examples/static_trimesh3.rs +++ b/bevy_rapier3d/examples/static_trimesh3.rs @@ -30,7 +30,7 @@ fn setup_graphics(mut commands: Commands) { } fn ramp_size() -> Vec3 { - Vec3::new(10.0, 1.0, 1.0) + Vec3::new(10.0, 1.5, 1.0) } pub fn setup_physics(mut commands: Commands) { @@ -62,7 +62,7 @@ pub fn setup_physics(mut commands: Commands) { let mut indices: Vec<[u32; 3]> = Vec::new(); let segments = 32; - let bowl_size = Vec3::new(10.0, 3.0, 10.0); + let bowl_size = Vec3::new(10.0, 6.0, 10.0); for ix in 0..=segments { for iz in 0..=segments { @@ -111,9 +111,9 @@ impl Default for BallState { fn default() -> Self { Self { seconds_until_next_spawn: 0.5, - seconds_between_spawns: 2.0, + seconds_between_spawns: 2.5, balls_spawned: 0, - max_balls: 10, + max_balls: 200, } } } @@ -129,7 +129,7 @@ fn ball_spawner( // NOTE: The timing here only works properly with `time_dependent_number_of_timesteps` // disabled, as it is for examples. - ball_state.seconds_until_next_spawn -= rapier_context.integration_parameters.dt; + ball_state.seconds_until_next_spawn -= rapier_context.integration_parameters.dt as f32; if ball_state.seconds_until_next_spawn > 0.0 { return; } @@ -142,7 +142,7 @@ fn ball_spawner( commands.spawn(( TransformBundle::from(Transform::from_xyz( ramp_size.x * 0.9, - ramp_size.y / 2.0 + rad * 3.0, + ramp_size.y + rad * 3.0, 0.0, )), RigidBody::Dynamic, diff --git a/src/geometry/collider_impl.rs b/src/geometry/collider_impl.rs index e2b255ee..3fc98ee7 100644 --- a/src/geometry/collider_impl.rs +++ b/src/geometry/collider_impl.rs @@ -152,19 +152,19 @@ impl Collider { } /// Initializes a collider with a triangle mesh shape defined by its vertex and index buffers. - pub fn trimesh(vertices: Vec, indices: Vec<[u32; 3]>) -> Self { - let vertices = vertices.into_iter().map(|v| v.into()).collect(); + pub fn trimesh>(vertices: Vec, indices: Vec<[u32; 3]>) -> Self { + let vertices = vertices.into_iter().map(|v| v.as_precise().into()).collect(); SharedShape::trimesh(vertices, indices).into() } /// Initializes a collider with a triangle mesh shape defined by its vertex and index buffers, and flags /// controlling its pre-processing. - pub fn trimesh_with_flags( - vertices: Vec, + pub fn trimesh_with_flags>( + vertices: Vec, indices: Vec<[u32; 3]>, flags: TriMeshFlags, ) -> Self { - let vertices = vertices.into_iter().map(|v| v.into()).collect(); + let vertices = vertices.into_iter().map(|v| v.as_precise().into()).collect(); SharedShape::trimesh_with_flags(vertices, indices, flags).into() } @@ -190,42 +190,42 @@ impl Collider { /// Initializes a collider with a compound shape obtained from the decomposition of /// the given trimesh (in 3D) or polyline (in 2D) into convex parts. - pub fn convex_decomposition(vertices: &[Vect], indices: &[[u32; DIM]]) -> Self { - let vertices: Vec<_> = vertices.iter().map(|v| (*v).into()).collect(); + pub fn convex_decomposition>(vertices: &[V], indices: &[[u32; DIM]]) -> Self { + let vertices: Vec<_> = vertices.iter().map(|v| (*v).as_precise().into()).collect(); SharedShape::convex_decomposition(&vertices, indices).into() } /// Initializes a collider with a compound shape obtained from the decomposition of /// the given trimesh (in 3D) or polyline (in 2D) into convex parts dilated with round corners. - pub fn round_convex_decomposition( - vertices: &[Vect], + pub fn round_convex_decomposition>( + vertices: &[V], indices: &[[u32; DIM]], border_radius: Real, ) -> Self { - let vertices: Vec<_> = vertices.iter().map(|v| (*v).into()).collect(); + let vertices: Vec<_> = vertices.iter().map(|v| (*v).as_precise().into()).collect(); SharedShape::round_convex_decomposition(&vertices, indices, border_radius).into() } /// Initializes a collider with a compound shape obtained from the decomposition of /// the given trimesh (in 3D) or polyline (in 2D) into convex parts. - pub fn convex_decomposition_with_params( - vertices: &[Vect], + pub fn convex_decomposition_with_params>( + vertices: &[V], indices: &[[u32; DIM]], params: &VHACDParameters, ) -> Self { - let vertices: Vec<_> = vertices.iter().map(|v| (*v).into()).collect(); + let vertices: Vec<_> = vertices.iter().map(|v| (*v).as_precise().into()).collect(); SharedShape::convex_decomposition_with_params(&vertices, indices, params).into() } /// Initializes a collider with a compound shape obtained from the decomposition of /// the given trimesh (in 3D) or polyline (in 2D) into convex parts dilated with round corners. - pub fn round_convex_decomposition_with_params( - vertices: &[Vect], + pub fn round_convex_decomposition_with_params>( + vertices: &[V], indices: &[[u32; DIM]], params: &VHACDParameters, border_radius: Real, ) -> Self { - let vertices: Vec<_> = vertices.iter().map(|v| (*v).into()).collect(); + let vertices: Vec<_> = vertices.iter().map(|v| (*v).as_precise().into()).collect(); SharedShape::round_convex_decomposition_with_params( &vertices, indices, @@ -237,25 +237,25 @@ impl Collider { /// Initializes a new collider with a 2D convex polygon or 3D convex polyhedron /// obtained after computing the convex-hull of the given points. - pub fn convex_hull(points: &[Vect]) -> Option { - let points: Vec<_> = points.iter().map(|v| (*v).into()).collect(); + pub fn convex_hull>(points: &[V]) -> Option { + let points: Vec<_> = points.iter().map(|v| (*v).as_precise().into()).collect(); SharedShape::convex_hull(&points).map(Into::into) } /// Initializes a new collider with a round 2D convex polygon or 3D convex polyhedron /// obtained after computing the convex-hull of the given points. The shape is dilated /// by a sphere of radius `border_radius`. - pub fn round_convex_hull(points: &[Vect], border_radius: Real) -> Option { - let points: Vec<_> = points.iter().map(|v| (*v).into()).collect(); - SharedShape::round_convex_hull(&points, border_radius).map(Into::into) + pub fn round_convex_hull>(points: &[V], border_radius: impl AsPrecise) -> Option { + let points: Vec<_> = points.iter().map(|v| (*v).as_precise().into()).collect(); + SharedShape::round_convex_hull(&points, border_radius.as_precise()).map(Into::into) } /// Creates a new collider that is a convex polygon formed by the /// given polyline assumed to be convex (no convex-hull will be automatically /// computed). #[cfg(feature = "dim2")] - pub fn convex_polyline(points: Vec) -> Option { - let points = points.into_iter().map(|v| v.into()).collect(); + pub fn convex_polyline>(points: Vec) -> Option { + let points = points.into_iter().map(|v| v.as_precise().into()).collect(); SharedShape::convex_polyline(points).map(Into::into) } @@ -263,8 +263,8 @@ impl Collider { /// given polyline assumed to be convex (no convex-hull will be automatically /// computed). The polygon shape is dilated by a sphere of radius `border_radius`. #[cfg(feature = "dim2")] - pub fn round_convex_polyline(points: Vec, border_radius: Real) -> Option { - let points = points.into_iter().map(|v| v.into()).collect(); + pub fn round_convex_polyline>(points: Vec, border_radius: Real) -> Option { + let points = points.into_iter().map(|v| v.as_precise().into()).collect(); SharedShape::round_convex_polyline(points, border_radius).map(Into::into) } @@ -272,8 +272,8 @@ impl Collider { /// given triangle-mesh assumed to be convex (no convex-hull will be automatically /// computed). #[cfg(feature = "dim3")] - pub fn convex_mesh(points: Vec, indices: &[[u32; 3]]) -> Option { - let points = points.into_iter().map(|v| v.into()).collect(); + pub fn convex_mesh>(points: Vec, indices: &[[u32; 3]]) -> Option { + let points = points.into_iter().map(|v| v.as_precise().into()).collect(); SharedShape::convex_mesh(points, indices).map(Into::into) } @@ -281,31 +281,33 @@ impl Collider { /// given triangle-mesh assumed to be convex (no convex-hull will be automatically /// computed). The triangle mesh shape is dilated by a sphere of radius `border_radius`. #[cfg(feature = "dim3")] - pub fn round_convex_mesh( - points: Vec, + pub fn round_convex_mesh>( + points: Vec, indices: &[[u32; 3]], - border_radius: Real, + border_radius: impl AsPrecise, ) -> Option { - let points = points.into_iter().map(|v| v.into()).collect(); - SharedShape::round_convex_mesh(points, indices, border_radius).map(Into::into) + let points = points.into_iter().map(|v| v.as_precise().into()).collect(); + SharedShape::round_convex_mesh(points, indices, border_radius.as_precise()).map(Into::into) } /// Initializes a collider with a heightfield shape defined by its set of height and a scale /// factor along each coordinate axis. #[cfg(feature = "dim2")] - pub fn heightfield(heights: Vec, scale: Vect) -> Self { - SharedShape::heightfield(DVector::from_vec(heights), scale.into()).into() + pub fn heightfield>(heights: Vec, scale: impl AsPrecise) -> Self { + let heights = heights.into_iter().map(|v| v.as_precise().into()).collect(); + SharedShape::heightfield(DVector::from_vec(heights), scale.as_precise().into()).into() } /// Initializes a collider with a heightfield shape defined by its set of height (in /// column-major format) and a scale factor along each coordinate axis. #[cfg(feature = "dim3")] - pub fn heightfield(heights: Vec, num_rows: usize, num_cols: usize, scale: Vect) -> Self { + pub fn heightfield>(heights: Vec, num_rows: usize, num_cols: usize, scale: Vect) -> Self { assert_eq!( heights.len(), num_rows * num_cols, "Invalid number of heights provided." ); + let heights = heights.into_iter().map(|v| v.as_precise().into()).collect(); let heights = rapier::na::DMatrix::from_vec(num_rows, num_cols, heights); SharedShape::heightfield(heights, scale.into()).into() } diff --git a/src/plugin/context.rs b/src/plugin/context.rs index 087d0bc5..d89d7276 100644 --- a/src/plugin/context.rs +++ b/src/plugin/context.rs @@ -486,15 +486,15 @@ impl RapierContext { /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. pub fn cast_ray( &self, - ray_origin: Vect, - ray_dir: Vect, - max_toi: Real, + ray_origin: impl AsPrecise, + ray_dir: impl AsPrecise, + max_toi: impl AsPrecise, solid: bool, filter: QueryFilter, ) -> Option<(Entity, Real)> { let ray = Ray::new( - (ray_origin / self.physics_scale).into(), - (ray_dir / self.physics_scale).into(), + (ray_origin.as_precise() / self.physics_scale).into(), + (ray_dir.as_precise() / self.physics_scale).into(), ); let (h, toi) = self.with_query_filter(filter, move |filter| { @@ -502,7 +502,7 @@ impl RapierContext { &self.bodies, &self.colliders, &ray, - max_toi, + max_toi.as_precise(), solid, filter, ) @@ -770,14 +770,14 @@ impl RapierContext { #[allow(clippy::too_many_arguments)] pub fn cast_shape( &self, - shape_pos: Vect, - shape_rot: Rot, - shape_vel: Vect, + shape_pos: impl AsPrecise, + shape_rot: impl AsPrecise, + shape_vel: impl AsPrecise, shape: &Collider, - max_toi: Real, + max_toi: impl AsPrecise, filter: QueryFilter, ) -> Option<(Entity, Toi)> { - let scaled_transform = (shape_pos / self.physics_scale, shape_rot).into(); + let scaled_transform = (shape_pos.as_precise() / self.physics_scale, shape_rot.as_precise()).into(); let mut scaled_shape = shape.clone(); // TODO: how to set a good number of subdivisions, we don’t have access to the // RapierConfiguration::scaled_shape_subdivision here. @@ -788,9 +788,9 @@ impl RapierContext { &self.bodies, &self.colliders, &scaled_transform, - &(shape_vel / self.physics_scale).into(), + &(shape_vel.as_precise() / self.physics_scale).into(), &*scaled_shape.raw, - max_toi, + max_toi.as_precise(), true, filter, ) @@ -862,13 +862,13 @@ impl RapierContext { /// * `callback` - A function called with the entities of each collider intersecting the `shape`. pub fn intersections_with_shape( &self, - shape_pos: Vect, - shape_rot: Rot, + shape_pos: impl AsPrecise, + shape_rot: impl AsPrecise, shape: &Collider, filter: QueryFilter, mut callback: impl FnMut(Entity) -> bool, ) { - let scaled_transform = (shape_pos / self.physics_scale, shape_rot).into(); + let scaled_transform = (shape_pos.as_precise() / self.physics_scale, shape_rot.as_precise()).into(); let mut scaled_shape = shape.clone(); // TODO: how to set a good number of subdivisions, we don’t have access to the // RapierConfiguration::scaled_shape_subdivision here. From f600eef64751f3f48eb9b66fd14f40da83b39d6b Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 17:00:19 -0700 Subject: [PATCH 05/10] Separate out for consistency with rapier crates --- .github/workflows/main.yml | 12 ++ bevy_rapier2d/Cargo.toml | 24 ++-- bevy_rapier2d_f64/Cargo.toml | 53 ++++++++ bevy_rapier3d/Cargo.toml | 24 ++-- bevy_rapier3d/examples/boxes3.rs | 8 +- bevy_rapier3d_f64/Cargo.toml | 53 ++++++++ src/dynamics/fixed_joint.rs | 2 +- src/dynamics/generic_joint.rs | 8 +- src/dynamics/prismatic_joint.rs | 2 +- src/dynamics/revolute_joint.rs | 2 +- src/dynamics/rope_joint.rs | 2 +- src/dynamics/spherical_joint.rs | 2 +- src/geometry/collider.rs | 1 - src/geometry/collider_impl.rs | 168 ++++++++++++++++++++---- src/geometry/shape_views/round_shape.rs | 2 +- src/lib.rs | 3 + src/plugin/configuration.rs | 2 +- src/plugin/context.rs | 15 ++- src/plugin/plugin.rs | 2 +- src/plugin/systems.rs | 4 +- src/utils/as_precise.rs | 49 +++---- src/utils/mod.rs | 59 +++------ 22 files changed, 359 insertions(+), 138 deletions(-) create mode 100644 bevy_rapier2d_f64/Cargo.toml create mode 100644 bevy_rapier3d_f64/Cargo.toml diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index f00b84cf..2391219f 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -32,16 +32,28 @@ jobs: - run: sudo apt update && sudo apt-get install pkg-config libx11-dev libasound2-dev libudev-dev - name: Clippy for bevy_rapier2d run: cargo clippy --verbose -p bevy_rapier2d + - name: Clippy for bevy_rapier2d_f64 + run: cargo clippy --verbose -p bevy_rapier2d_f64 - name: Clippy for bevy_rapier3d run: cargo clippy --verbose -p bevy_rapier3d + - name: Clippy for bevy_rapier3d_f64 + run: cargo clippy --verbose -p bevy_rapier3d_f64 - name: Clippy for bevy_rapier2d (debug-render, simd, serde) run: cargo clippy --verbose -p bevy_rapier2d --features debug-render-2d,simd-stable,serde-serialize + - name: Clippy for bevy_rapier2d_f64 (debug-render, simd, serde) + run: cargo clippy --verbose -p bevy_rapier2d_f64 --features debug-render-2d,simd-stable,serde-serialize - name: Clippy for bevy_rapier3d (debug-render, simd, serde) run: cargo clippy --verbose -p bevy_rapier3d --features debug-render-3d,simd-stable,serde-serialize + - name: Clippy for bevy_rapier3d_f64 (debug-render, simd, serde) + run: cargo clippy --verbose -p bevy_rapier3d_f64 --features debug-render-3d,simd-stable,serde-serialize - name: Test for bevy_rapier2d run: cargo test --verbose -p bevy_rapier2d + - name: Test for bevy_rapier2d_f64 + run: cargo test --verbose -p bevy_rapier2d_f64 - name: Test for bevy_rapier3d run: cargo test --verbose -p bevy_rapier3d + - name: Test for bevy_rapier3d_f64 + run: cargo test --verbose -p bevy_rapier3d_f64 test-wasm: runs-on: ubuntu-latest env: diff --git a/bevy_rapier2d/Cargo.toml b/bevy_rapier2d/Cargo.toml index 3f58e724..47f3d706 100644 --- a/bevy_rapier2d/Cargo.toml +++ b/bevy_rapier2d/Cargo.toml @@ -15,21 +15,20 @@ edition = "2021" # See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html [lib] path = "../src/lib.rs" -required-features = [ "dim2" ] +required-features = [ "dim2", "f32" ] [features] default = [ "dim2", "async-collider", "debug-render-2d", "f32" ] -f32 = [ "rapier2d" ] -f64 = [ "rapier2d-f64" ] dim2 = [] -debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier2d?/debug-render", "rapier2d-f64?/debug-render", "bevy/bevy_asset" ] -debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier2d?/debug-render", "rapier2d-f64?/debug-render", "bevy/bevy_asset" ] -parallel = [ "rapier2d?/parallel", "rapier2d-f64?/parallel" ] -simd-stable = [ "rapier2d?/simd-stable", "rapier2d-f64?/simd-stable" ] -simd-nightly = [ "rapier2d?/simd-nightly", "rapier2d-f64?/simd-nightly" ] -wasm-bindgen = [ "rapier2d?/wasm-bindgen", "rapier2d-f64?/wasm-bindgen" ] -serde-serialize = [ "rapier2d-f64?/serde-serialize", "rapier2d?/serde-serialize", "bevy/serialize", "serde" ] -enhanced-determinism = [ "rapier2d?/enhanced-determinism", "rapier2d-f64?/enhanced-determinism" ] +f32 = [] +debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier2d/debug-render", "bevy/bevy_asset" ] +debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier2d/debug-render", "bevy/bevy_asset" ] +parallel = [ "rapier2d/parallel", ] +simd-stable = [ "rapier2d/simd-stable", ] +simd-nightly = [ "rapier2d/simd-nightly", ] +wasm-bindgen = [ "rapier2d/wasm-bindgen", ] +serde-serialize = [ "rapier2d/serde-serialize", "bevy/serialize", "serde" ] +enhanced-determinism = [ "rapier2d/enhanced-determinism", ] headless = [] async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] @@ -37,8 +36,7 @@ async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet -rapier2d = { version = "0.17.0", optional = true } -rapier2d-f64 = { version = "0.17.0", optional = true } +rapier2d = "0.17.0" bitflags = "1" #bevy_prototype_debug_lines = { version = "0.6", optional = true } log = "0.4" diff --git a/bevy_rapier2d_f64/Cargo.toml b/bevy_rapier2d_f64/Cargo.toml new file mode 100644 index 00000000..53ab2498 --- /dev/null +++ b/bevy_rapier2d_f64/Cargo.toml @@ -0,0 +1,53 @@ +[package] +name = "bevy_rapier2d_f64" +version = "0.22.0" +authors = ["Sébastien Crozet "] +description = "2-dimensional physics engine in Rust, official Bevy plugin." +documentation = "http://docs.rs/bevy_rapier3d" +homepage = "http://rapier.rs" +repository = "https://github.com/dimforge/bevy_rapier" +readme = "../README.md" +keywords = [ "physics", "dynamics", "rigid", "real-time", "joints" ] +license = "Apache-2.0" +edition = "2021" + + +# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html +[lib] +path = "../src/lib.rs" +required-features = [ "dim2", "f64" ] + +[features] +default = [ "dim2", "async-collider", "debug-render-2d", "f64" ] +dim3 = [] +f64 = [] +debug-render = [ "debug-render-3d" ] +debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier2d-f64/debug-render", "bevy/bevy_asset" ] +debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier2d-f64/debug-render", "bevy/bevy_asset" ] +parallel = [ "rapier2d-f64/parallel" ] +simd-stable = [ "rapier2d-f64/simd-stable" ] +simd-nightly = [ "rapier2d-f64/simd-nightly" ] +wasm-bindgen = [ "rapier2d-f64/wasm-bindgen" ] +serde-serialize = [ "rapier2d-f64/serde-serialize", "bevy/serialize", "serde" ] +enhanced-determinism = [ "rapier2d-f64/enhanced-determinism" ] +headless = [ ] +async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] + +[dependencies] +bevy = { version = "0.11", default-features = false } +nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } +# Don't enable the default features because we don't need the ColliderSet/RigidBodySet +rapier3d-f64 = "0.17" +bitflags = "1" +#bevy_prototype_debug_lines = { version = "0.6", features = ["3d"], optional = true } +log = "0.4" +serde = { version = "1", features = [ "derive" ], optional = true} + +[dev-dependencies] +bevy = { version = "0.11", default-features = false, features = ["x11"]} +approx = "0.5.1" +glam = { version = "0.24", features = [ "approx" ] } + +[package.metadata.docs.rs] +# Enable all the features when building the docs on docs.rs +features = [ "debug-render-2d", "serde-serialize" ] diff --git a/bevy_rapier3d/Cargo.toml b/bevy_rapier3d/Cargo.toml index fa153283..123f6e2f 100644 --- a/bevy_rapier3d/Cargo.toml +++ b/bevy_rapier3d/Cargo.toml @@ -15,22 +15,21 @@ edition = "2021" # See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html [lib] path = "../src/lib.rs" -required-features = [ "dim3" ] +required-features = [ "dim3", "f32" ] [features] default = [ "dim3", "async-collider", "debug-render-3d", "f32" ] -f32 = [ "rapier3d" ] -f64 = [ "rapier3d-f64" ] dim3 = [] +f32 = [] debug-render = [ "debug-render-3d" ] -debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier3d?/debug-render", "rapier3d-f64?/debug-render", "bevy/bevy_asset" ] -debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier3d?/debug-render", "rapier3d-f64?/debug-render", "bevy/bevy_asset" ] -parallel = [ "rapier3d?/parallel", "rapier3d-f64?/parallel" ] -simd-stable = [ "rapier3d?/simd-stable", "rapier3d-f64?/simd-stable" ] -simd-nightly = [ "rapier3d?/simd-nightly", "rapier3d-f64?/simd-nightly" ] -wasm-bindgen = [ "rapier3d?/wasm-bindgen", "rapier3d-f64?/wasm-bindgen" ] -serde-serialize = [ "rapier3d-f64?/serde-serialize", "rapier3d?/serde-serialize", "bevy/serialize", "serde" ] -enhanced-determinism = [ "rapier3d?/enhanced-determinism", "rapier3d-f64?/enhanced-determinism" ] +debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier3d/debug-render", "bevy/bevy_asset" ] +debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier3d/debug-render", "bevy/bevy_asset" ] +parallel = [ "rapier3d/parallel" ] +simd-stable = [ "rapier3d/simd-stable" ] +simd-nightly = [ "rapier3d/simd-nightly" ] +wasm-bindgen = [ "rapier3d/wasm-bindgen" ] +serde-serialize = [ "rapier3d/serde-serialize", "bevy/serialize", "serde" ] +enhanced-determinism = [ "rapier3d/enhanced-determinism" ] headless = [ ] async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] @@ -38,8 +37,7 @@ async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet -rapier3d = { version = "0.17.0", optional = true } -rapier3d-f64 = { version = "0.17.0", optional = true } +rapier3d = "0.17" bitflags = "1" #bevy_prototype_debug_lines = { version = "0.6", features = ["3d"], optional = true } log = "0.4" diff --git a/bevy_rapier3d/examples/boxes3.rs b/bevy_rapier3d/examples/boxes3.rs index 9ec2877d..2cd078f3 100644 --- a/bevy_rapier3d/examples/boxes3.rs +++ b/bevy_rapier3d/examples/boxes3.rs @@ -1,5 +1,5 @@ use bevy::prelude::*; -use bevy_rapier3d::{utils::as_precise::*, prelude::*}; +use bevy_rapier3d::{prelude::*, utils::as_precise::*}; fn main() { App::new() @@ -34,7 +34,11 @@ pub fn setup_physics(mut commands: Commands) { commands.spawn(( TransformBundle::from(Transform::from_xyz(0.0, -ground_height, 0.0)), - Collider::cuboid(ground_size.as_precise(), ground_height.as_precise(), ground_size.as_precise()), + Collider::cuboid( + ground_size.as_precise(), + ground_height.as_precise(), + ground_size.as_precise(), + ), )); /* diff --git a/bevy_rapier3d_f64/Cargo.toml b/bevy_rapier3d_f64/Cargo.toml new file mode 100644 index 00000000..6ee7c597 --- /dev/null +++ b/bevy_rapier3d_f64/Cargo.toml @@ -0,0 +1,53 @@ +[package] +name = "bevy_rapier3d_f64" +version = "0.22.0" +authors = ["Sébastien Crozet "] +description = "3-dimensional physics engine in Rust, official Bevy plugin." +documentation = "http://docs.rs/bevy_rapier3d" +homepage = "http://rapier.rs" +repository = "https://github.com/dimforge/bevy_rapier" +readme = "../README.md" +keywords = [ "physics", "dynamics", "rigid", "real-time", "joints" ] +license = "Apache-2.0" +edition = "2021" + + +# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html +[lib] +path = "../src/lib.rs" +required-features = [ "dim3", "f64" ] + +[features] +default = [ "dim3", "async-collider", "debug-render-3d", "f64" ] +dim3 = [] +f64 = [] +debug-render = [ "debug-render-3d" ] +debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier3d-f64/debug-render", "bevy/bevy_asset" ] +debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier3d-f64/debug-render", "bevy/bevy_asset" ] +parallel = [ "rapier3d-f64/parallel" ] +simd-stable = [ "rapier3d-f64/simd-stable" ] +simd-nightly = [ "rapier3d-f64/simd-nightly" ] +wasm-bindgen = [ "rapier3d-f64/wasm-bindgen" ] +serde-serialize = [ "rapier3d-f64/serde-serialize", "bevy/serialize", "serde" ] +enhanced-determinism = [ "rapier3d-f64/enhanced-determinism" ] +headless = [ ] +async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] + +[dependencies] +bevy = { version = "0.11", default-features = false } +nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } +# Don't enable the default features because we don't need the ColliderSet/RigidBodySet +rapier3d-f64 = "0.17" +bitflags = "1" +#bevy_prototype_debug_lines = { version = "0.6", features = ["3d"], optional = true } +log = "0.4" +serde = { version = "1", features = [ "derive" ], optional = true} + +[dev-dependencies] +bevy = { version = "0.11", default-features = false, features = ["x11"]} +approx = "0.5.1" +glam = { version = "0.24", features = [ "approx" ] } + +[package.metadata.docs.rs] +# Enable all the features when building the docs on docs.rs +features = [ "debug-render-3d", "serde-serialize" ] diff --git a/src/dynamics/fixed_joint.rs b/src/dynamics/fixed_joint.rs index ca1d7045..0f463be5 100644 --- a/src/dynamics/fixed_joint.rs +++ b/src/dynamics/fixed_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Rot, Vect, AsPrecise}; +use crate::math::{AsPrecise, Rot, Vect}; use rapier::dynamics::JointAxesMask; #[derive(Copy, Clone, Debug, PartialEq)] diff --git a/src/dynamics/generic_joint.rs b/src/dynamics/generic_joint.rs index 5ddf8a41..9c83b729 100644 --- a/src/dynamics/generic_joint.rs +++ b/src/dynamics/generic_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{FixedJoint, PrismaticJoint, RevoluteJoint, RopeJoint}; -use crate::math::{Real, Rot, Vect, AsPrecise}; +use crate::math::{AsPrecise, Real, Rot, Vect}; use rapier::dynamics::{ GenericJoint as RapierGenericJoint, JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel, @@ -117,7 +117,8 @@ impl GenericJoint { /// 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: impl AsPrecise) -> &mut Self { - self.raw.set_local_axis1(local_axis.as_precise().try_into().unwrap()); + self.raw + .set_local_axis1(local_axis.as_precise().try_into().unwrap()); self } @@ -129,7 +130,8 @@ impl GenericJoint { /// 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: impl AsPrecise) -> &mut Self { - self.raw.set_local_axis2(local_axis.as_precise().try_into().unwrap()); + self.raw + .set_local_axis2(local_axis.as_precise().try_into().unwrap()); self } diff --git a/src/dynamics/prismatic_joint.rs b/src/dynamics/prismatic_joint.rs index f6e2ac40..87fb69ca 100644 --- a/src/dynamics/prismatic_joint.rs +++ b/src/dynamics/prismatic_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Real, Vect, AsPrecise}; +use crate::math::{AsPrecise, Real, Vect}; use rapier::dynamics::{JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel}; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] diff --git a/src/dynamics/revolute_joint.rs b/src/dynamics/revolute_joint.rs index 095b69ef..038c20e0 100644 --- a/src/dynamics/revolute_joint.rs +++ b/src/dynamics/revolute_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Real, Vect, AsPrecise}; +use crate::math::{AsPrecise, Real, Vect}; use rapier::dynamics::{JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel}; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] diff --git a/src/dynamics/rope_joint.rs b/src/dynamics/rope_joint.rs index 884e095a..6eac01cd 100644 --- a/src/dynamics/rope_joint.rs +++ b/src/dynamics/rope_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Real, Vect, AsPrecise}; +use crate::math::{AsPrecise, Real, Vect}; use rapier::dynamics::{JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel}; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] diff --git a/src/dynamics/spherical_joint.rs b/src/dynamics/spherical_joint.rs index dc92fa39..de11eb19 100644 --- a/src/dynamics/spherical_joint.rs +++ b/src/dynamics/spherical_joint.rs @@ -1,5 +1,5 @@ use crate::dynamics::{GenericJoint, GenericJointBuilder}; -use crate::math::{Real, Vect, AsPrecise}; +use crate::math::{AsPrecise, Real, Vect}; use rapier::dynamics::{JointAxesMask, JointAxis, JointLimits, JointMotor, MotorModel}; #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] diff --git a/src/geometry/collider.rs b/src/geometry/collider.rs index 02111e7b..8e7245a0 100644 --- a/src/geometry/collider.rs +++ b/src/geometry/collider.rs @@ -11,7 +11,6 @@ use rapier::prelude::{ColliderHandle, InteractionGroups, SharedShape}; use crate::dynamics::{CoefficientCombineRule, MassProperties}; use crate::math::{Real, Vect}; -use crate::utils::as_precise::*; /// The Rapier handle of a collider that was inserted to the physics scene. #[derive(Copy, Clone, Debug, Component)] diff --git a/src/geometry/collider_impl.rs b/src/geometry/collider_impl.rs index 3fc98ee7..611a9bfd 100644 --- a/src/geometry/collider_impl.rs +++ b/src/geometry/collider_impl.rs @@ -53,7 +53,10 @@ impl Collider { /// Initialize a new collider with a cylindrical shape defined by its half-height /// (along along the y axis) and its radius. #[cfg(feature = "dim3")] - pub fn cylinder(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + pub fn cylinder( + half_height: impl AsPrecise, + radius: impl AsPrecise, + ) -> Self { SharedShape::cylinder(half_height.as_precise(), radius.as_precise()).into() } @@ -61,14 +64,26 @@ impl Collider { /// (along along the y axis), its radius, and its roundedness (the /// radius of the sphere used for dilating the cylinder). #[cfg(feature = "dim3")] - pub fn round_cylinder(half_height: impl AsPrecise, radius: impl AsPrecise, border_radius: impl AsPrecise) -> Self { - SharedShape::round_cylinder(half_height.as_precise(), radius.as_precise(), border_radius.as_precise()).into() + pub fn round_cylinder( + half_height: impl AsPrecise, + radius: impl AsPrecise, + border_radius: impl AsPrecise, + ) -> Self { + SharedShape::round_cylinder( + half_height.as_precise(), + radius.as_precise(), + border_radius.as_precise(), + ) + .into() } /// Initialize a new collider with a cone shape defined by its half-height /// (along along the y axis) and its basis radius. #[cfg(feature = "dim3")] - pub fn cone(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + pub fn cone( + half_height: impl AsPrecise, + radius: impl AsPrecise, + ) -> Self { SharedShape::cone(half_height.as_precise(), radius.as_precise()).into() } @@ -76,8 +91,17 @@ impl Collider { /// (along along the y axis), its radius, and its roundedness (the /// radius of the sphere used for dilating the cylinder). #[cfg(feature = "dim3")] - pub fn round_cone(half_height: impl AsPrecise, radius: impl AsPrecise, border_radius: impl AsPrecise) -> Self { - SharedShape::round_cone(half_height.as_precise(), radius.as_precise(), border_radius.as_precise()).into() + pub fn round_cone( + half_height: impl AsPrecise, + radius: impl AsPrecise, + border_radius: impl AsPrecise, + ) -> Self { + SharedShape::round_cone( + half_height.as_precise(), + radius.as_precise(), + border_radius.as_precise(), + ) + .into() } /// Initialize a new collider with a cuboid shape defined by its half-extents. @@ -89,45 +113,87 @@ impl Collider { /// Initialize a new collider with a round cuboid shape defined by its half-extents /// and border radius. #[cfg(feature = "dim2")] - pub fn round_cuboid(half_x: impl AsPrecise, half_y: impl AsPrecise, border_radius: impl AsPrecise) -> Self { - SharedShape::round_cuboid(half_x.as_precise(), half_y.as_precise(), border_radius.as_precise()).into() + pub fn round_cuboid( + half_x: impl AsPrecise, + half_y: impl AsPrecise, + border_radius: impl AsPrecise, + ) -> Self { + SharedShape::round_cuboid( + half_x.as_precise(), + half_y.as_precise(), + border_radius.as_precise(), + ) + .into() } /// Initialize a new collider with a capsule shape. - pub fn capsule(start: impl AsPrecise, end: impl AsPrecise, radius: impl AsPrecise) -> Self { - SharedShape::capsule(start.as_precise().into(), end.as_precise().into(), radius.as_precise()).into() + pub fn capsule( + start: impl AsPrecise, + end: impl AsPrecise, + radius: impl AsPrecise, + ) -> Self { + SharedShape::capsule( + start.as_precise().into(), + end.as_precise().into(), + radius.as_precise(), + ) + .into() } /// Initialize a new collider with a capsule shape aligned with the `x` axis. - pub fn capsule_x(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + pub fn capsule_x( + half_height: impl AsPrecise, + radius: impl AsPrecise, + ) -> Self { let p = Point::from(Vector::x() * half_height.as_precise()); SharedShape::capsule(-p, p, radius.as_precise()).into() } /// Initialize a new collider with a capsule shape aligned with the `y` axis. - pub fn capsule_y(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + pub fn capsule_y( + half_height: impl AsPrecise, + radius: impl AsPrecise, + ) -> Self { let p = Point::from(Vector::y() * half_height.as_precise()); SharedShape::capsule(-p, p, radius.as_precise()).into() } /// Initialize a new collider with a capsule shape aligned with the `z` axis. #[cfg(feature = "dim3")] - pub fn capsule_z(half_height: impl AsPrecise, radius: impl AsPrecise) -> Self { + pub fn capsule_z( + half_height: impl AsPrecise, + radius: impl AsPrecise, + ) -> Self { let p = Point::from(Vector::z() * half_height.as_precise()); SharedShape::capsule(-p, p, radius.as_precise()).into() } /// Initialize a new collider with a cuboid shape defined by its half-extents. #[cfg(feature = "dim3")] - pub fn cuboid(hx: impl AsPrecise, hy: impl AsPrecise, hz: impl AsPrecise) -> Self { + pub fn cuboid( + hx: impl AsPrecise, + hy: impl AsPrecise, + hz: impl AsPrecise, + ) -> Self { SharedShape::cuboid(hx.as_precise(), hy.as_precise(), hz.as_precise()).into() } /// Initialize a new collider with a round cuboid shape defined by its half-extents /// and border radius. #[cfg(feature = "dim3")] - pub fn round_cuboid(half_x: impl AsPrecise, half_y: impl AsPrecise, half_z: impl AsPrecise, border_radius: impl AsPrecise) -> Self { - SharedShape::round_cuboid(half_x.as_precise(), half_y.as_precise(), half_z.as_precise(), border_radius.as_precise()).into() + pub fn round_cuboid( + half_x: impl AsPrecise, + half_y: impl AsPrecise, + half_z: impl AsPrecise, + border_radius: impl AsPrecise, + ) -> Self { + SharedShape::round_cuboid( + half_x.as_precise(), + half_y.as_precise(), + half_z.as_precise(), + border_radius.as_precise(), + ) + .into() } /// Initializes a collider with a segment shape. @@ -136,13 +202,33 @@ impl Collider { } /// Initializes a collider with a triangle shape. - pub fn triangle(a: impl AsPrecise, b: impl AsPrecise, c: impl AsPrecise) -> Self { - SharedShape::triangle(a.as_precise().into(), b.as_precise().into(), c.as_precise().into()).into() + pub fn triangle( + a: impl AsPrecise, + b: impl AsPrecise, + c: impl AsPrecise, + ) -> Self { + SharedShape::triangle( + a.as_precise().into(), + b.as_precise().into(), + c.as_precise().into(), + ) + .into() } /// Initializes a collider with a triangle shape with round corners. - pub fn round_triangle(a: impl AsPrecise, b: impl AsPrecise, c: impl AsPrecise, border_radius: impl AsPrecise) -> Self { - SharedShape::round_triangle(a.as_precise().into(), b.as_precise().into(), c.as_precise().into(), border_radius.as_precise()).into() + pub fn round_triangle( + a: impl AsPrecise, + b: impl AsPrecise, + c: impl AsPrecise, + border_radius: impl AsPrecise, + ) -> Self { + SharedShape::round_triangle( + a.as_precise().into(), + b.as_precise().into(), + c.as_precise().into(), + border_radius.as_precise(), + ) + .into() } /// Initializes a collider with a polyline shape defined by its vertex and index buffers. @@ -153,7 +239,10 @@ impl Collider { /// Initializes a collider with a triangle mesh shape defined by its vertex and index buffers. pub fn trimesh>(vertices: Vec, indices: Vec<[u32; 3]>) -> Self { - let vertices = vertices.into_iter().map(|v| v.as_precise().into()).collect(); + let vertices = vertices + .into_iter() + .map(|v| v.as_precise().into()) + .collect(); SharedShape::trimesh(vertices, indices).into() } @@ -164,7 +253,10 @@ impl Collider { indices: Vec<[u32; 3]>, flags: TriMeshFlags, ) -> Self { - let vertices = vertices.into_iter().map(|v| v.as_precise().into()).collect(); + let vertices = vertices + .into_iter() + .map(|v| v.as_precise().into()) + .collect(); SharedShape::trimesh_with_flags(vertices, indices, flags).into() } @@ -190,7 +282,10 @@ impl Collider { /// Initializes a collider with a compound shape obtained from the decomposition of /// the given trimesh (in 3D) or polyline (in 2D) into convex parts. - pub fn convex_decomposition>(vertices: &[V], indices: &[[u32; DIM]]) -> Self { + pub fn convex_decomposition>( + vertices: &[V], + indices: &[[u32; DIM]], + ) -> Self { let vertices: Vec<_> = vertices.iter().map(|v| (*v).as_precise().into()).collect(); SharedShape::convex_decomposition(&vertices, indices).into() } @@ -245,7 +340,10 @@ impl Collider { /// Initializes a new collider with a round 2D convex polygon or 3D convex polyhedron /// obtained after computing the convex-hull of the given points. The shape is dilated /// by a sphere of radius `border_radius`. - pub fn round_convex_hull>(points: &[V], border_radius: impl AsPrecise) -> Option { + pub fn round_convex_hull>( + points: &[V], + border_radius: impl AsPrecise, + ) -> Option { let points: Vec<_> = points.iter().map(|v| (*v).as_precise().into()).collect(); SharedShape::round_convex_hull(&points, border_radius.as_precise()).map(Into::into) } @@ -263,7 +361,10 @@ impl Collider { /// given polyline assumed to be convex (no convex-hull will be automatically /// computed). The polygon shape is dilated by a sphere of radius `border_radius`. #[cfg(feature = "dim2")] - pub fn round_convex_polyline>(points: Vec, border_radius: Real) -> Option { + pub fn round_convex_polyline>( + points: Vec, + border_radius: Real, + ) -> Option { let points = points.into_iter().map(|v| v.as_precise().into()).collect(); SharedShape::round_convex_polyline(points, border_radius).map(Into::into) } @@ -272,7 +373,10 @@ impl Collider { /// given triangle-mesh assumed to be convex (no convex-hull will be automatically /// computed). #[cfg(feature = "dim3")] - pub fn convex_mesh>(points: Vec, indices: &[[u32; 3]]) -> Option { + pub fn convex_mesh>( + points: Vec, + indices: &[[u32; 3]], + ) -> Option { let points = points.into_iter().map(|v| v.as_precise().into()).collect(); SharedShape::convex_mesh(points, indices).map(Into::into) } @@ -293,7 +397,10 @@ impl Collider { /// Initializes a collider with a heightfield shape defined by its set of height and a scale /// factor along each coordinate axis. #[cfg(feature = "dim2")] - pub fn heightfield>(heights: Vec, scale: impl AsPrecise) -> Self { + pub fn heightfield>( + heights: Vec, + scale: impl AsPrecise, + ) -> Self { let heights = heights.into_iter().map(|v| v.as_precise().into()).collect(); SharedShape::heightfield(DVector::from_vec(heights), scale.as_precise().into()).into() } @@ -301,7 +408,12 @@ impl Collider { /// Initializes a collider with a heightfield shape defined by its set of height (in /// column-major format) and a scale factor along each coordinate axis. #[cfg(feature = "dim3")] - pub fn heightfield>(heights: Vec, num_rows: usize, num_cols: usize, scale: Vect) -> Self { + pub fn heightfield>( + heights: Vec, + num_rows: usize, + num_cols: usize, + scale: Vect, + ) -> Self { assert_eq!( heights.len(), num_rows * num_cols, diff --git a/src/geometry/shape_views/round_shape.rs b/src/geometry/shape_views/round_shape.rs index a798c365..254e813c 100644 --- a/src/geometry/shape_views/round_shape.rs +++ b/src/geometry/shape_views/round_shape.rs @@ -1,6 +1,6 @@ use crate::geometry::shape_views::{CuboidView, CuboidViewMut, TriangleView, TriangleViewMut}; +use crate::math::Real; use rapier::geometry::{RoundCuboid, RoundTriangle}; -use crate::math::{Real, Vect}; #[cfg(feature = "dim2")] use { diff --git a/src/lib.rs b/src/lib.rs index 8b57f9b9..217700b6 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -38,6 +38,7 @@ pub mod math { /// The vector type. #[cfg(feature = "f32")] pub type Vect = bevy::math::Vec2; + /// The vector type. #[cfg(feature = "f64")] pub type Vect = bevy::math::DVec2; /// The rotation type (in 2D this is an angle in radians). @@ -55,11 +56,13 @@ pub mod math { /// The vector type. #[cfg(feature = "f32")] pub type Vect = bevy::math::Vec3; + /// The vector type. #[cfg(feature = "f64")] pub type Vect = bevy::math::DVec3; /// The rotation type. #[cfg(feature = "f32")] pub type Rot = bevy::math::Quat; + /// The rotation type. #[cfg(feature = "f64")] pub type Rot = bevy::math::DQuat; } diff --git a/src/plugin/configuration.rs b/src/plugin/configuration.rs index a407b364..37ad3cb0 100644 --- a/src/plugin/configuration.rs +++ b/src/plugin/configuration.rs @@ -1,6 +1,6 @@ use bevy::prelude::Resource; -use crate::math::{Vect, Real}; +use crate::math::{Real, Vect}; /// Difference between simulation and rendering time #[derive(Resource, Default)] diff --git a/src/plugin/context.rs b/src/plugin/context.rs index d89d7276..bb184432 100644 --- a/src/plugin/context.rs +++ b/src/plugin/context.rs @@ -283,7 +283,8 @@ impl RapierContext { } => { let mut substep_integration_parameters = self.integration_parameters; substep_integration_parameters.dt = - (time.delta_seconds_f64().as_precise() * time_scale).min(max_dt) / (substeps as Real); + (time.delta_seconds_f64().as_precise() * time_scale).min(max_dt) + / (substeps as Real); for _ in 0..substeps { self.pipeline.step( @@ -777,7 +778,11 @@ impl RapierContext { max_toi: impl AsPrecise, filter: QueryFilter, ) -> Option<(Entity, Toi)> { - let scaled_transform = (shape_pos.as_precise() / self.physics_scale, shape_rot.as_precise()).into(); + let scaled_transform = ( + shape_pos.as_precise() / self.physics_scale, + shape_rot.as_precise(), + ) + .into(); let mut scaled_shape = shape.clone(); // TODO: how to set a good number of subdivisions, we don’t have access to the // RapierConfiguration::scaled_shape_subdivision here. @@ -868,7 +873,11 @@ impl RapierContext { filter: QueryFilter, mut callback: impl FnMut(Entity) -> bool, ) { - let scaled_transform = (shape_pos.as_precise() / self.physics_scale, shape_rot.as_precise()).into(); + let scaled_transform = ( + shape_pos.as_precise() / self.physics_scale, + shape_rot.as_precise(), + ) + .into(); let mut scaled_shape = shape.clone(); // TODO: how to set a good number of subdivisions, we don’t have access to the // RapierConfiguration::scaled_shape_subdivision here. diff --git a/src/plugin/plugin.rs b/src/plugin/plugin.rs index ebd783dc..afbf7e73 100644 --- a/src/plugin/plugin.rs +++ b/src/plugin/plugin.rs @@ -1,8 +1,8 @@ +use crate::math::Real; use crate::pipeline::{CollisionEvent, ContactForceEvent}; use crate::plugin::configuration::SimulationToRenderTime; use crate::plugin::{systems, RapierConfiguration, RapierContext}; use crate::prelude::*; -use crate::math::Real; use bevy::ecs::{ event::Events, schedule::{ScheduleLabel, SystemConfigs}, diff --git a/src/plugin/systems.rs b/src/plugin/systems.rs index 5c545abf..d40f6434 100644 --- a/src/plugin/systems.rs +++ b/src/plugin/systems.rs @@ -107,7 +107,9 @@ pub fn apply_scale( #[cfg(feature = "dim3")] let effective_scale = match custom_scale { Some(ColliderScale::Absolute(scale)) => *scale, - Some(ColliderScale::Relative(scale)) => *scale * transform.compute_transform().scale.as_precise(), + Some(ColliderScale::Relative(scale)) => { + *scale * transform.compute_transform().scale.as_precise() + } None => transform.compute_transform().scale.as_precise(), }; diff --git a/src/utils/as_precise.rs b/src/utils/as_precise.rs index fc7840dd..bcd9d4ca 100644 --- a/src/utils/as_precise.rs +++ b/src/utils/as_precise.rs @@ -1,16 +1,21 @@ - use bevy::math::*; -/// Convert value into the precision the compilation is using. +/// Convenience method for converting math types into single or double +/// floating point precision depending on feature flags. pub trait AsPrecise: Clone + Copy { + /// Single or double precision version of this type. type Out; + /// Convert into single or double precision floating point + /// depending on feature flags. fn as_precise(self) -> Self::Out; } -/// Convert value into single precision floating point. -pub trait AsSingle { - type Single; - fn as_single(self) -> Self::Single; +/// Convenience method for converting math types into single precision floating point. +pub trait AsSingle: Clone + Copy { + /// Single precision version of this type. + type Out; + /// Convert value into single precision floating point. + fn as_single(self) -> Self::Out; } macro_rules! as_precise_self { @@ -21,18 +26,18 @@ macro_rules! as_precise_self { self } } - } + }; } macro_rules! as_single_self { ($ty:ty) => { impl AsSingle for $ty { - type Single = $ty; - fn as_single(self) -> Self::Single { + type Out = $ty; + fn as_single(self) -> Self::Out { self } } - } + }; } as_single_self!(f32); @@ -43,44 +48,44 @@ as_single_self!(Vec4); as_single_self!(Quat); impl AsSingle for f64 { - type Single = f32; - fn as_single(self) -> Self::Single { + type Out = f32; + fn as_single(self) -> Self::Out { self as f32 } } impl AsSingle for DVec2 { - type Single = Vec2; - fn as_single(self) -> Self::Single { + type Out = Vec2; + fn as_single(self) -> Self::Out { self.as_vec2() } } impl AsSingle for DVec3 { - type Single = Vec3; - fn as_single(self) -> Self::Single { + type Out = Vec3; + fn as_single(self) -> Self::Out { self.as_vec3() } } impl AsSingle for DVec4 { - type Single = Vec4; - fn as_single(self) -> Self::Single { + type Out = Vec4; + fn as_single(self) -> Self::Out { self.as_vec4() } } impl AsSingle for DQuat { - type Single = Quat; - fn as_single(self) -> Self::Single { + type Out = Quat; + fn as_single(self) -> Self::Out { self.as_f32() } } #[cfg(feature = "f32")] mod real { - use bevy::math::*; use super::{AsPrecise, AsSingle}; + use bevy::math::*; as_precise_self!(f32); as_precise_self!(Vec2); @@ -127,8 +132,8 @@ mod real { #[cfg(feature = "f64")] mod real { - use bevy::math::*; use super::AsPrecise; + use bevy::math::*; as_precise_self!(f64); as_precise_self!(DVec2); diff --git a/src/utils/mod.rs b/src/utils/mod.rs index 6b55c4da..db4cd174 100644 --- a/src/utils/mod.rs +++ b/src/utils/mod.rs @@ -1,31 +1,20 @@ +use crate::math::*; use bevy::prelude::Transform; -use rapier::math::{Isometry, Real}; +use rapier::math::Isometry; +/// Conversions to various precisions for interop reasons. pub mod as_precise; -pub use as_precise::*; /// Converts a Rapier isometry to a Bevy transform. /// /// The translation is multiplied by the `physics_scale`. #[cfg(feature = "dim2")] pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform { - #[cfg(feature = "f32")] - let (translation, rotation) = { - use bevy::math::{Vec2, Quat}; - let translation: Vec2 = iso.translation.vector.into(); - let rotation = Quat::from_rotation_z(iso.rotation.angle()); - (translation, rotation) - }; - #[cfg(feature = "f64")] - let (translation, rotation) = { - use bevy::math::{DVec2, DQuat}; - let translation: DVec2 = iso.translation.vector.into(); - let rotation = DQuat::from_rotation_z(iso.rotation.angle()); - (translation, rotation) - }; + let translation = Vect::from(iso.translation.vector) * physics_scale; + let rotation = Quat::from_rotation_z(iso.rotation.angle()); Transform { translation: translation.as_single().extend(0.0), - rotation: rotation.as_single(), + rotation: rotation, ..Default::default() } } @@ -35,22 +24,10 @@ pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform /// The translation is multiplied by the `physics_scale`. #[cfg(feature = "dim3")] pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform { - #[cfg(feature = "f32")] - let (translation, rotation) = { - use bevy::math::{Vec3, Quat}; - let translation: Vec3 = iso.translation.vector.into(); - let rotation: Quat = iso.rotation.into(); - (translation, rotation) - }; - #[cfg(feature = "f64")] - let (translation, rotation) = { - use bevy::math::{DVec3, DQuat}; - let translation: DVec3 = iso.translation.vector.into(); - let rotation: DQuat = iso.rotation.into(); - (translation, rotation) - }; + let translation = Vect::from(iso.translation.vector) * physics_scale; + let rotation = Rot::from(iso.rotation); Transform { - translation: (translation * physics_scale).as_single(), + translation: translation.as_single(), rotation: rotation.as_single(), ..Default::default() } @@ -61,13 +38,10 @@ pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform /// The translation is divided by the `physics_scale`. #[cfg(feature = "dim2")] pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Isometry { - use bevy::math::Vec3Swizzles; - let translation = transform.translation.as_precise(); - let rotation = transform.rotation.to_scaled_axis().z.as_precise(); - Isometry::new( - (translation / physics_scale).xy().into(), - rotation, - ) + use bevy::math::{EulerRot, Vec3Swizzles}; + let translation = transform.translation.as_precise() / physics_scale; + let rotation = transform.rotation.to_euler(EulerRot::ZYX).0.as_precise(); + Isometry::new(translation.xy().into(), rotation) } /// Converts a Bevy transform to a Rapier isometry. @@ -75,12 +49,9 @@ pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Is /// The translation is divided by the `physics_scale`. #[cfg(feature = "dim3")] pub(crate) fn transform_to_iso(transform: &Transform, physics_scale: Real) -> Isometry { - let translation = transform.translation.as_precise(); + let translation = transform.translation.as_precise() / physics_scale; let rotation = transform.rotation.as_precise(); - Isometry::from_parts( - (translation / physics_scale).into(), - rotation.into(), - ) + Isometry::from_parts(translation.into(), rotation.into()) } #[cfg(test)] From 8151c65dd681ba77ef59e014fd3839efce00b436 Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 17:01:38 -0700 Subject: [PATCH 06/10] Remove unnecessary precision change --- bevy_rapier2d/examples/boxes2.rs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bevy_rapier2d/examples/boxes2.rs b/bevy_rapier2d/examples/boxes2.rs index 7ae08857..a942c5a5 100644 --- a/bevy_rapier2d/examples/boxes2.rs +++ b/bevy_rapier2d/examples/boxes2.rs @@ -56,7 +56,7 @@ pub fn setup_physics(mut commands: Commands) { commands.spawn(( TransformBundle::from(Transform::from_xyz(x, y, 0.0)), RigidBody::Dynamic, - Collider::cuboid(rad.as_precise(), rad.as_precise()), + Collider::cuboid(rad, rad), )); } From 401c47fc4f022389ac1909422292a2312b3d7087 Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 17:04:23 -0700 Subject: [PATCH 07/10] More unnecessary changes --- bevy_rapier2d/Cargo.toml | 8 ++++---- bevy_rapier3d/examples/boxes3.rs | 10 +++------- 2 files changed, 7 insertions(+), 11 deletions(-) diff --git a/bevy_rapier2d/Cargo.toml b/bevy_rapier2d/Cargo.toml index 47f3d706..47523eaf 100644 --- a/bevy_rapier2d/Cargo.toml +++ b/bevy_rapier2d/Cargo.toml @@ -23,10 +23,10 @@ dim2 = [] f32 = [] debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier2d/debug-render", "bevy/bevy_asset" ] debug-render-3d = [ "bevy/bevy_core_pipeline", "bevy/bevy_pbr", "bevy/bevy_gizmos", "rapier2d/debug-render", "bevy/bevy_asset" ] -parallel = [ "rapier2d/parallel", ] -simd-stable = [ "rapier2d/simd-stable", ] -simd-nightly = [ "rapier2d/simd-nightly", ] -wasm-bindgen = [ "rapier2d/wasm-bindgen", ] +parallel = [ "rapier2d/parallel" ] +simd-stable = [ "rapier2d/simd-stable" ] +simd-nightly = [ "rapier2d/simd-nightly" ] +wasm-bindgen = [ "rapier2d/wasm-bindgen" ] serde-serialize = [ "rapier2d/serde-serialize", "bevy/serialize", "serde" ] enhanced-determinism = [ "rapier2d/enhanced-determinism", ] headless = [] diff --git a/bevy_rapier3d/examples/boxes3.rs b/bevy_rapier3d/examples/boxes3.rs index 2cd078f3..3d510720 100644 --- a/bevy_rapier3d/examples/boxes3.rs +++ b/bevy_rapier3d/examples/boxes3.rs @@ -1,5 +1,5 @@ use bevy::prelude::*; -use bevy_rapier3d::{prelude::*, utils::as_precise::*}; +use bevy_rapier3d::prelude::*; fn main() { App::new() @@ -34,11 +34,7 @@ pub fn setup_physics(mut commands: Commands) { commands.spawn(( TransformBundle::from(Transform::from_xyz(0.0, -ground_height, 0.0)), - Collider::cuboid( - ground_size.as_precise(), - ground_height.as_precise(), - ground_size.as_precise(), - ), + Collider::cuboid(ground_size, ground_height, ground_size), )); /* @@ -76,7 +72,7 @@ pub fn setup_physics(mut commands: Commands) { child.spawn(( TransformBundle::from(Transform::from_xyz(x, y, z)), RigidBody::Dynamic, - Collider::cuboid(rad.as_precise(), rad.as_precise(), rad.as_precise()), + Collider::cuboid(rad, rad, rad), ColliderDebugColor(colors[color % 3]), )); }); From c9ca6d9bcbca6ff29267b13f086aec1cb93dd7fa Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 17:17:35 -0700 Subject: [PATCH 08/10] Some more convenience conversions in joints, fix up cargo toml and workspace --- Cargo.toml | 2 +- bevy_rapier2d_f64/Cargo.toml | 4 ++-- src/dynamics/fixed_joint.rs | 16 ++++++++-------- src/dynamics/generic_joint.rs | 22 ++++++++++++---------- src/utils/mod.rs | 3 ++- 5 files changed, 25 insertions(+), 22 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index a0431007..f1fddad4 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,5 +1,5 @@ [workspace] -members = ["bevy_rapier2d", "bevy_rapier3d"] +members = ["bevy_rapier2d", "bevy_rapier2d_f64", "bevy_rapier3d", "bevy_rapier3d_f64"] resolver = "2" [profile.dev] diff --git a/bevy_rapier2d_f64/Cargo.toml b/bevy_rapier2d_f64/Cargo.toml index 53ab2498..e3b26bf9 100644 --- a/bevy_rapier2d_f64/Cargo.toml +++ b/bevy_rapier2d_f64/Cargo.toml @@ -19,7 +19,7 @@ required-features = [ "dim2", "f64" ] [features] default = [ "dim2", "async-collider", "debug-render-2d", "f64" ] -dim3 = [] +dim2 = [] f64 = [] debug-render = [ "debug-render-3d" ] debug-render-2d = [ "bevy/bevy_core_pipeline", "bevy/bevy_sprite", "bevy/bevy_gizmos", "rapier2d-f64/debug-render", "bevy/bevy_asset" ] @@ -37,7 +37,7 @@ async-collider = [ "bevy/bevy_asset", "bevy/bevy_scene" ] bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet -rapier3d-f64 = "0.17" +rapier2d-f64 = "0.17" bitflags = "1" #bevy_prototype_debug_lines = { version = "0.6", features = ["3d"], optional = true } log = "0.4" diff --git a/src/dynamics/fixed_joint.rs b/src/dynamics/fixed_joint.rs index 0f463be5..54d48038 100644 --- a/src/dynamics/fixed_joint.rs +++ b/src/dynamics/fixed_joint.rs @@ -41,8 +41,8 @@ impl FixedJoint { } /// Sets the joint’s basis, expressed in the first rigid-body’s local-space. - pub fn set_local_basis1(&mut self, local_basis: Rot) -> &mut Self { - self.data.set_local_basis1(local_basis); + pub fn set_local_basis1(&mut self, local_basis: impl AsPrecise) -> &mut Self { + self.data.set_local_basis1(local_basis.as_precise()); self } @@ -53,8 +53,8 @@ impl FixedJoint { } /// Sets joint’s basis, expressed in the second rigid-body’s local-space. - pub fn set_local_basis2(&mut self, local_basis: Rot) -> &mut Self { - self.data.set_local_basis2(local_basis); + pub fn set_local_basis2(&mut self, local_basis: impl AsPrecise) -> &mut Self { + self.data.set_local_basis2(local_basis.as_precise()); self } @@ -101,15 +101,15 @@ impl FixedJointBuilder { /// Sets the joint’s basis, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_basis1(mut self, local_basis: Rot) -> Self { - self.0.set_local_basis1(local_basis); + pub fn local_basis1(mut self, local_basis: impl AsPrecise) -> Self { + self.0.set_local_basis1(local_basis.as_precise()); self } /// Sets joint’s basis, expressed in the second rigid-body’s local-space. #[must_use] - pub fn local_basis2(mut self, local_basis: Rot) -> Self { - self.0.set_local_basis2(local_basis); + pub fn local_basis2(mut self, local_basis: impl AsPrecise) -> Self { + self.0.set_local_basis2(local_basis.as_precise()); self } diff --git a/src/dynamics/generic_joint.rs b/src/dynamics/generic_joint.rs index 9c83b729..f7a08108 100644 --- a/src/dynamics/generic_joint.rs +++ b/src/dynamics/generic_joint.rs @@ -75,7 +75,8 @@ impl GenericJoint { } /// Sets the joint’s frame, expressed in the first rigid-body’s local-space. - pub fn set_local_basis1(&mut self, local_basis: Rot) -> &mut Self { + pub fn set_local_basis1(&mut self, local_basis: impl AsPrecise) -> &mut Self { + let local_basis = local_basis.as_precise(); #[cfg(feature = "dim2")] { self.raw.local_frame1.rotation = na::UnitComplex::new(local_basis); @@ -97,7 +98,8 @@ impl GenericJoint { } /// Sets the joint’s frame, expressed in the second rigid-body’s local-space. - pub fn set_local_basis2(&mut self, local_basis: Rot) -> &mut Self { + pub fn set_local_basis2(&mut self, local_basis: impl AsPrecise) -> &mut Self { + let local_basis = local_basis.as_precise(); #[cfg(feature = "dim2")] { self.raw.local_frame2.rotation = na::UnitComplex::new(local_basis); @@ -335,29 +337,29 @@ impl GenericJointBuilder { /// Sets the joint’s frame, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_basis1(mut self, local_basis: Rot) -> Self { - self.0.set_local_basis1(local_basis); + pub fn local_basis1(mut self, local_basis: impl AsPrecise) -> Self { + self.0.set_local_basis1(local_basis.as_precise()); self } /// Sets the joint’s frame, expressed in the second rigid-body’s local-space. #[must_use] - pub fn local_basis2(mut self, local_basis: Rot) -> Self { - self.0.set_local_basis2(local_basis); + pub fn local_basis2(mut self, local_basis: impl AsPrecise) -> Self { + self.0.set_local_basis2(local_basis.as_precise()); self } /// Sets the principal (local X) axis of this joint, expressed in the first rigid-body’s local-space. #[must_use] - pub fn local_axis1(mut self, local_axis: Vect) -> Self { - self.0.set_local_axis1(local_axis); + pub fn local_axis1(mut self, local_axis: impl AsPrecise) -> Self { + self.0.set_local_axis1(local_axis.as_precise()); self } /// Sets the principal (local X) axis of this joint, expressed in the second rigid-body’s local-space. #[must_use] - pub fn local_axis2(mut self, local_axis: Vect) -> Self { - self.0.set_local_axis2(local_axis); + pub fn local_axis2(mut self, local_axis: impl AsPrecise) -> Self { + self.0.set_local_axis2(local_axis.as_precise()); self } diff --git a/src/utils/mod.rs b/src/utils/mod.rs index db4cd174..b8f4b16e 100644 --- a/src/utils/mod.rs +++ b/src/utils/mod.rs @@ -10,8 +10,9 @@ pub mod as_precise; /// The translation is multiplied by the `physics_scale`. #[cfg(feature = "dim2")] pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform { + use bevy::math::Quat; let translation = Vect::from(iso.translation.vector) * physics_scale; - let rotation = Quat::from_rotation_z(iso.rotation.angle()); + let rotation = Quat::from_rotation_z(iso.rotation.angle().as_single()); Transform { translation: translation.as_single().extend(0.0), rotation: rotation, From 2b9e2eda6b1fb7824c218fd0d17ca976d04481be Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 17:20:31 -0700 Subject: [PATCH 09/10] Rust 1.72 formatting --- bevy_rapier3d/examples/ray_casting3.rs | 8 ++++++-- src/geometry/collider_impl.rs | 4 +++- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/bevy_rapier3d/examples/ray_casting3.rs b/bevy_rapier3d/examples/ray_casting3.rs index 50a27a4c..c6068117 100644 --- a/bevy_rapier3d/examples/ray_casting3.rs +++ b/bevy_rapier3d/examples/ray_casting3.rs @@ -80,12 +80,16 @@ fn cast_ray( ) { let window = windows.single(); - let Some(cursor_position) = window.cursor_position() else { return; }; + let Some(cursor_position) = window.cursor_position() else { + return; + }; // We will color in read the colliders hovered by the mouse. for (camera, camera_transform) in &cameras { // First, compute a ray from the mouse position. - let Some(ray) = camera.viewport_to_world(camera_transform, cursor_position) else { return; }; + let Some(ray) = camera.viewport_to_world(camera_transform, cursor_position) else { + return; + }; // Then cast the ray. let hit = rapier_context.cast_ray( diff --git a/src/geometry/collider_impl.rs b/src/geometry/collider_impl.rs index 611a9bfd..24cb8e5e 100644 --- a/src/geometry/collider_impl.rs +++ b/src/geometry/collider_impl.rs @@ -265,7 +265,9 @@ impl Collider { /// Returns `None` if the index buffer or vertex buffer of the mesh are in an incompatible format. #[cfg(all(feature = "dim3", feature = "async-collider"))] pub fn from_bevy_mesh(mesh: &Mesh, collider_shape: &ComputedColliderShape) -> Option { - let Some((vtx, idx)) = extract_mesh_vertices_indices(mesh) else { return None; }; + let Some((vtx, idx)) = extract_mesh_vertices_indices(mesh) else { + return None; + }; match collider_shape { ComputedColliderShape::TriMesh => Some( SharedShape::trimesh_with_flags(vtx, idx, TriMeshFlags::MERGE_DUPLICATE_VERTICES) From 2ead912da5410876ae68fe39cee267539bfac5fc Mon Sep 17 00:00:00 2001 From: Aceeri Date: Thu, 24 Aug 2023 17:54:30 -0700 Subject: [PATCH 10/10] Update bitflags to 2.4 --- bevy_rapier2d/Cargo.toml | 2 +- bevy_rapier2d_f64/Cargo.toml | 2 +- bevy_rapier3d/Cargo.toml | 2 +- bevy_rapier3d_f64/Cargo.toml | 2 +- src/dynamics/rigid_body.rs | 14 ++++--- src/geometry/collider.rs | 70 ++++++++++++++++++----------------- src/geometry/collider_impl.rs | 4 +- src/render/mod.rs | 18 ++++----- src/utils/mod.rs | 10 ++--- 9 files changed, 64 insertions(+), 60 deletions(-) diff --git a/bevy_rapier2d/Cargo.toml b/bevy_rapier2d/Cargo.toml index 47523eaf..6b02bbb4 100644 --- a/bevy_rapier2d/Cargo.toml +++ b/bevy_rapier2d/Cargo.toml @@ -37,7 +37,7 @@ bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet rapier2d = "0.17.0" -bitflags = "1" +bitflags = "2.4" #bevy_prototype_debug_lines = { version = "0.6", optional = true } log = "0.4" serde = { version = "1", features = [ "derive" ], optional = true} diff --git a/bevy_rapier2d_f64/Cargo.toml b/bevy_rapier2d_f64/Cargo.toml index e3b26bf9..cf9147d5 100644 --- a/bevy_rapier2d_f64/Cargo.toml +++ b/bevy_rapier2d_f64/Cargo.toml @@ -38,7 +38,7 @@ bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet rapier2d-f64 = "0.17" -bitflags = "1" +bitflags = "2.4" #bevy_prototype_debug_lines = { version = "0.6", features = ["3d"], optional = true } log = "0.4" serde = { version = "1", features = [ "derive" ], optional = true} diff --git a/bevy_rapier3d/Cargo.toml b/bevy_rapier3d/Cargo.toml index 123f6e2f..8876bfc5 100644 --- a/bevy_rapier3d/Cargo.toml +++ b/bevy_rapier3d/Cargo.toml @@ -38,7 +38,7 @@ bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet rapier3d = "0.17" -bitflags = "1" +bitflags = "2.4" #bevy_prototype_debug_lines = { version = "0.6", features = ["3d"], optional = true } log = "0.4" serde = { version = "1", features = [ "derive" ], optional = true} diff --git a/bevy_rapier3d_f64/Cargo.toml b/bevy_rapier3d_f64/Cargo.toml index 6ee7c597..756f0c98 100644 --- a/bevy_rapier3d_f64/Cargo.toml +++ b/bevy_rapier3d_f64/Cargo.toml @@ -38,7 +38,7 @@ bevy = { version = "0.11", default-features = false } nalgebra = { version = "0.32.3", features = [ "convert-glam024" ] } # Don't enable the default features because we don't need the ColliderSet/RigidBodySet rapier3d-f64 = "0.17" -bitflags = "1" +bitflags = "2.4" #bevy_prototype_debug_lines = { version = "0.6", features = ["3d"], optional = true } log = "0.4" serde = { version = "1", features = [ "derive" ], optional = true} diff --git a/src/dynamics/rigid_body.rs b/src/dynamics/rigid_body.rs index 31213fa5..9ae993e2 100644 --- a/src/dynamics/rigid_body.rs +++ b/src/dynamics/rigid_body.rs @@ -240,11 +240,13 @@ impl MassProperties { } } +#[derive(Default, Component, Reflect, Copy, Clone, Ord, PartialOrd, Eq, PartialEq, Hash)] +#[reflect(Component, PartialEq)] +/// Flags affecting the behavior of the constraints solver for a given contact manifold. +pub struct LockedAxes(u8); + bitflags::bitflags! { - #[derive(Default, Component, Reflect)] - #[reflect(Component, PartialEq)] - /// Flags affecting the behavior of the constraints solver for a given contact manifold. - pub struct LockedAxes: u8 { + impl LockedAxes: u8 { /// Flag indicating that the rigid-body cannot translate along the `X` axis. const TRANSLATION_LOCKED_X = 1 << 0; /// Flag indicating that the rigid-body cannot translate along the `Y` axis. @@ -252,7 +254,7 @@ bitflags::bitflags! { /// Flag indicating that the rigid-body cannot translate along the `Z` axis. const TRANSLATION_LOCKED_Z = 1 << 2; /// Flag indicating that the rigid-body cannot translate along any direction. - const TRANSLATION_LOCKED = Self::TRANSLATION_LOCKED_X.bits | Self::TRANSLATION_LOCKED_Y.bits | Self::TRANSLATION_LOCKED_Z.bits; + const TRANSLATION_LOCKED = Self::TRANSLATION_LOCKED_X.bits() | Self::TRANSLATION_LOCKED_Y.bits() | Self::TRANSLATION_LOCKED_Z.bits(); /// Flag indicating that the rigid-body cannot rotate along the `X` axis. const ROTATION_LOCKED_X = 1 << 3; /// Flag indicating that the rigid-body cannot rotate along the `Y` axis. @@ -260,7 +262,7 @@ bitflags::bitflags! { /// Flag indicating that the rigid-body cannot rotate along the `Z` axis. const ROTATION_LOCKED_Z = 1 << 5; /// Combination of flags indicating that the rigid-body cannot rotate along any axis. - const ROTATION_LOCKED = Self::ROTATION_LOCKED_X.bits | Self::ROTATION_LOCKED_Y.bits | Self::ROTATION_LOCKED_Z.bits; + const ROTATION_LOCKED = Self::ROTATION_LOCKED_X.bits() | Self::ROTATION_LOCKED_Y.bits() | Self::ROTATION_LOCKED_Z.bits(); } } diff --git a/src/geometry/collider.rs b/src/geometry/collider.rs index 8e7245a0..d47cc377 100644 --- a/src/geometry/collider.rs +++ b/src/geometry/collider.rs @@ -148,17 +148,14 @@ impl Friction { /// Creates a `Friction` component from the given friction coefficient, and using the default /// `CoefficientCombineRule::Average` coefficient combine rule. pub const fn new(coefficient: Real) -> Self { - Self { - coefficient: coefficient, - combine_rule: CoefficientCombineRule::Average, - } + Self::coefficient(coefficient) } /// Creates a `Friction` component from the given friction coefficient, and using the default /// `CoefficientCombineRule::Average` coefficient combine rule. pub const fn coefficient(coefficient: Real) -> Self { Self { - coefficient: coefficient, + coefficient, combine_rule: CoefficientCombineRule::Average, } } @@ -181,17 +178,14 @@ impl Restitution { /// Creates a `Restitution` component from the given restitution coefficient, and using the default /// `CoefficientCombineRule::Average` coefficient combine rule. pub const fn new(coefficient: Real) -> Self { - Self { - coefficient: coefficient, - combine_rule: CoefficientCombineRule::Average, - } + Self::coefficient(coefficient) } /// Creates a `Restitution` component from the given restitution coefficient, and using the default /// `CoefficientCombineRule::Average` coefficient combine rule. pub const fn coefficient(coefficient: Real) -> Self { Self { - coefficient: coefficient, + coefficient, combine_rule: CoefficientCombineRule::Average, } } @@ -206,13 +200,15 @@ impl Default for Restitution { } } +#[derive(Component, Reflect, Debug, Copy, Clone, Ord, PartialOrd, Eq, PartialEq, Hash)] +#[reflect(Component, Hash, PartialEq)] +#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] +/// Flags affecting whether or not collision-detection happens between two colliders +/// depending on the type of rigid-bodies they are attached to. +pub struct ActiveCollisionTypes(u16); + bitflags::bitflags! { - #[derive(Component, Reflect)] - #[reflect(Component, Hash, PartialEq)] - #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] - /// Flags affecting whether or not collision-detection happens between two colliders - /// depending on the type of rigid-bodies they are attached to. - pub struct ActiveCollisionTypes: u16 { + impl ActiveCollisionTypes: u16 { /// Enable collision-detection between a collider attached to a dynamic body /// and another collider attached to a dynamic body. const DYNAMIC_DYNAMIC = 0b0000_0000_0000_0001; @@ -245,17 +241,19 @@ impl Default for ActiveCollisionTypes { impl From for rapier::geometry::ActiveCollisionTypes { fn from(collision_types: ActiveCollisionTypes) -> rapier::geometry::ActiveCollisionTypes { - rapier::geometry::ActiveCollisionTypes::from_bits(collision_types.bits) + rapier::geometry::ActiveCollisionTypes::from_bits(collision_types.bits()) .expect("Internal error: invalid active events conversion.") } } +/// A bit mask identifying groups for interaction. +#[derive(Component, Reflect, Copy, Clone, Debug, PartialEq, Eq, Hash)] +#[reflect(Component, Hash, PartialEq)] +#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] +pub struct Group(u32); + bitflags::bitflags! { - /// A bit mask identifying groups for interaction. - #[derive(Component, Reflect)] - #[reflect(Component, Hash, PartialEq)] - #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] - pub struct Group: u32 { + impl Group: u32 { /// The group n°1. const GROUP_1 = 1 << 0; /// The group n°2. @@ -410,12 +408,14 @@ impl From for InteractionGroups { } } +#[derive(Default, Component, Reflect, Debug, Copy, Clone, Ord, PartialOrd, Eq, PartialEq, Hash)] +#[reflect(Component)] +#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] +/// Flags affecting the behavior of the constraints solver for a given contact manifold. +pub struct ActiveHooks(u32); + bitflags::bitflags! { - #[derive(Default, Component, Reflect)] - #[reflect(Component)] - #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] - /// Flags affecting the behavior of the constraints solver for a given contact manifold. - pub struct ActiveHooks: u32 { + impl ActiveHooks: u32 { /// If set, Rapier will call `PhysicsHooks::filter_contact_pair` whenever relevant. const FILTER_CONTACT_PAIRS = 0b0001; /// If set, Rapier will call `PhysicsHooks::filter_intersection_pair` whenever relevant. @@ -427,17 +427,19 @@ bitflags::bitflags! { impl From for rapier::pipeline::ActiveHooks { fn from(active_hooks: ActiveHooks) -> rapier::pipeline::ActiveHooks { - rapier::pipeline::ActiveHooks::from_bits(active_hooks.bits) + rapier::pipeline::ActiveHooks::from_bits(active_hooks.bits()) .expect("Internal error: invalid active events conversion.") } } +#[derive(Default, Component, Reflect, Debug, Copy, Clone, Ord, PartialOrd, Eq, PartialEq, Hash)] +#[reflect(Component)] +#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] +/// Flags affecting the events generated for this collider. +pub struct ActiveEvents(u32); + bitflags::bitflags! { - #[derive(Default, Component, Reflect)] - #[reflect(Component)] - #[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))] - /// Flags affecting the events generated for this collider. - pub struct ActiveEvents: u32 { + impl ActiveEvents: u32 { /// If set, Rapier will call `EventHandler::handle_collision_event` /// whenever relevant for this collider. const COLLISION_EVENTS = 0b0001; @@ -449,7 +451,7 @@ bitflags::bitflags! { impl From for rapier::pipeline::ActiveEvents { fn from(active_events: ActiveEvents) -> rapier::pipeline::ActiveEvents { - rapier::pipeline::ActiveEvents::from_bits(active_events.bits) + rapier::pipeline::ActiveEvents::from_bits(active_events.bits()) .expect("Internal error: invalid active events conversion.") } } diff --git a/src/geometry/collider_impl.rs b/src/geometry/collider_impl.rs index 24cb8e5e..c7b5f187 100644 --- a/src/geometry/collider_impl.rs +++ b/src/geometry/collider_impl.rs @@ -403,7 +403,7 @@ impl Collider { heights: Vec, scale: impl AsPrecise, ) -> Self { - let heights = heights.into_iter().map(|v| v.as_precise().into()).collect(); + let heights = heights.into_iter().map(|v| v.as_precise()).collect(); SharedShape::heightfield(DVector::from_vec(heights), scale.as_precise().into()).into() } @@ -421,7 +421,7 @@ impl Collider { num_rows * num_cols, "Invalid number of heights provided." ); - let heights = heights.into_iter().map(|v| v.as_precise().into()).collect(); + let heights = heights.into_iter().map(|v| v.as_precise()).collect(); let heights = rapier::na::DMatrix::from_vec(num_rows, num_cols, heights); SharedShape::heightfield(heights, scale.into()).into() } diff --git a/src/render/mod.rs b/src/render/mod.rs index 64d9c75b..2e2cc4d2 100644 --- a/src/render/mod.rs +++ b/src/render/mod.rs @@ -1,4 +1,5 @@ use crate::plugin::RapierContext; +use crate::prelude::*; use bevy::prelude::*; use bevy::transform::TransformSystem; use rapier::math::{Point, Real}; @@ -126,11 +127,12 @@ impl<'world, 'state, 'a, 'b> DebugRenderBackend for BevyLinesRenderBackend<'worl b: Point, color: [f32; 4], ) { - let scale = self.physics_scale as f32; + let a = (Vect::from(a) * self.physics_scale).as_single(); + let b = (Vect::from(b) * self.physics_scale).as_single(); let color = self.object_color(object, color); self.gizmos.line( - [a.x as f32 * scale, a.y as f32 * scale, 0.0].into(), - [b.x as f32 * scale, b.y as f32 * scale, 0.0].into(), + a.extend(0.0), + b.extend(0.0), Color::hsla(color[0], color[1], color[2], color[3]), ) } @@ -143,13 +145,11 @@ impl<'world, 'state, 'a, 'b> DebugRenderBackend for BevyLinesRenderBackend<'worl b: Point, color: [f32; 4], ) { - let scale = self.physics_scale as f32; + let a = (Vect::from(a) * self.physics_scale).as_single(); + let b = (Vect::from(b) * self.physics_scale).as_single(); let color = self.object_color(object, color); - self.gizmos.line( - [a.x as f32 * scale, a.y as f32 * scale, a.z as f32 * scale].into(), - [b.x as f32 * scale, b.y as f32 * scale, b.z as f32 * scale].into(), - Color::hsla(color[0], color[1], color[2], color[3]), - ) + self.gizmos + .line(a, b, Color::hsla(color[0], color[1], color[2], color[3])) } } diff --git a/src/utils/mod.rs b/src/utils/mod.rs index b8f4b16e..dfd0bc6d 100644 --- a/src/utils/mod.rs +++ b/src/utils/mod.rs @@ -15,7 +15,7 @@ pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform let rotation = Quat::from_rotation_z(iso.rotation.angle().as_single()); Transform { translation: translation.as_single().extend(0.0), - rotation: rotation, + rotation, ..Default::default() } } @@ -25,11 +25,11 @@ pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform /// The translation is multiplied by the `physics_scale`. #[cfg(feature = "dim3")] pub fn iso_to_transform(iso: &Isometry, physics_scale: Real) -> Transform { - let translation = Vect::from(iso.translation.vector) * physics_scale; - let rotation = Rot::from(iso.rotation); + let translation = (Vect::from(iso.translation.vector) * physics_scale).as_single(); + let rotation = Rot::from(iso.rotation).as_single(); Transform { - translation: translation.as_single(), - rotation: rotation.as_single(), + translation, + rotation, ..Default::default() } }