diff options
| author | Crozet Sébastien <developer@crozet.re> | 2020-10-31 14:42:14 +0100 |
|---|---|---|
| committer | Crozet Sébastien <developer@crozet.re> | 2020-11-19 13:55:19 +0100 |
| commit | 154bc70037d42ef15d9a6c3288b8006027c2cb94 (patch) | |
| tree | 7eb8e456c592054e85831dfb2d3194abea639d33 | |
| parent | c26c3af50803e964c86df52a0c29bc74362aea71 (diff) | |
| download | rapier-154bc70037d42ef15d9a6c3288b8006027c2cb94.tar.gz rapier-154bc70037d42ef15d9a6c3288b8006027c2cb94.tar.bz2 rapier-154bc70037d42ef15d9a6c3288b8006027c2cb94.zip | |
Remove the Salva integration code from rapier + add a plugin system to the testbed.
| -rw-r--r-- | Cargo.toml | 2 | ||||
| -rw-r--r-- | build/rapier2d/Cargo.toml | 2 | ||||
| -rw-r--r-- | build/rapier3d/Cargo.toml | 2 | ||||
| -rw-r--r-- | build/rapier_testbed2d/Cargo.toml | 1 | ||||
| -rw-r--r-- | examples2d/Cargo.toml | 1 | ||||
| -rw-r--r-- | examples3d/Cargo.toml | 1 | ||||
| -rw-r--r-- | src/geometry/shape.rs | 2 | ||||
| -rw-r--r-- | src/lib.rs | 4 | ||||
| -rw-r--r-- | src/pipeline/fluids_pipeline.rs | 293 | ||||
| -rw-r--r-- | src/pipeline/mod.rs | 4 | ||||
| -rw-r--r-- | src_testbed/engine.rs | 121 | ||||
| -rw-r--r-- | src_testbed/lib.rs | 8 | ||||
| -rw-r--r-- | src_testbed/plugin.rs | 12 | ||||
| -rw-r--r-- | src_testbed/testbed.rs | 268 |
14 files changed, 102 insertions, 619 deletions
@@ -10,8 +10,6 @@ members = [ "build/rapier2d", "build/rapier_testbed2d", "examples2d", "benchmark #nphysics2d = { path = "../nphysics/build/nphysics2d" } #nphysics3d = { path = "../nphysics/build/nphysics3d" } #kiss3d = { path = "../kiss3d" } -salva2d = { path = "../salva/build/salva2d" } -salva3d = { path = "../salva/build/salva3d" } [profile.release] #debug = true diff --git a/build/rapier2d/Cargo.toml b/build/rapier2d/Cargo.toml index 30818f4..1c24a5d 100644 --- a/build/rapier2d/Cargo.toml +++ b/build/rapier2d/Cargo.toml @@ -23,7 +23,6 @@ simd-is-enabled = [ ] wasm-bindgen = [ "instant/wasm-bindgen" ] serde-serialize = [ "erased-serde", "nalgebra/serde-serialize", "ncollide2d/serde-serialize", "serde", "generational-arena/serde", "bit-vec/serde", "arrayvec/serde" ] enhanced-determinism = [ "simba/libm_force", "indexmap" ] -fluids = [ "salva2d" ] [lib] name = "rapier2d" @@ -51,7 +50,6 @@ indexmap = { version = "1", features = [ "serde-1" ], optional = true } downcast-rs = "1.2" num-derive = "0.3" bitflags = "1" -salva2d = { version = "0.4", optional = true } [dev-dependencies] bincode = "1" diff --git a/build/rapier3d/Cargo.toml b/build/rapier3d/Cargo.toml index 3d77440..7e98cdf 100644 --- a/build/rapier3d/Cargo.toml +++ b/build/rapier3d/Cargo.toml @@ -23,7 +23,6 @@ simd-is-enabled = [ ] wasm-bindgen = [ "instant/wasm-bindgen" ] serde-serialize = [ "erased-serde", "nalgebra/serde-serialize", "ncollide3d/serde-serialize", "serde", "generational-arena/serde", "bit-vec/serde" ] enhanced-determinism = [ "simba/libm_force", "indexmap" ] -fluids = [ "salva3d" ] [lib] name = "rapier3d" @@ -51,7 +50,6 @@ indexmap = { version = "1", features = [ "serde-1" ], optional = true } downcast-rs = "1.2" num-derive = "0.3" bitflags = "1" -salva3d = { version = "0.4", optional = true } [dev-dependencies] bincode = "1" diff --git a/build/rapier_testbed2d/Cargo.toml b/build/rapier_testbed2d/Cargo.toml index 08c0893..273595f 100644 --- a/build/rapier_testbed2d/Cargo.toml +++ b/build/rapier_testbed2d/Cargo.toml @@ -39,7 +39,6 @@ flexbuffers = "0.1" Inflector = "0.11" md5 = "0.7" - [dependencies.rapier2d] path = "../rapier2d" version = "0.3" diff --git a/examples2d/Cargo.toml b/examples2d/Cargo.toml index 603f9c7..f1ed728 100644 --- a/examples2d/Cargo.toml +++ b/examples2d/Cargo.toml @@ -10,7 +10,6 @@ simd-stable = [ "rapier2d/simd-stable" ] simd-nightly = [ "rapier2d/simd-nightly" ] other-backends = [ "rapier_testbed2d/other-backends" ] enhanced-determinism = [ "rapier2d/enhanced-determinism" ] -fluids = [ "rapier2d/fluids" ] [dependencies] rand = "0.7" diff --git a/examples3d/Cargo.toml b/examples3d/Cargo.toml index 23118aa..5362554 100644 --- a/examples3d/Cargo.toml +++ b/examples3d/Cargo.toml @@ -10,7 +10,6 @@ simd-stable = [ "rapier3d/simd-stable" ] simd-nightly = [ "rapier3d/simd-nightly" ] other-backends = [ "rapier_testbed3d/other-backends" ] enhanced-determinism = [ "rapier3d/enhanced-determinism" ] -fluids = [ "rapier3d/fluids" ] [dependencies] rand = "0.7" diff --git a/src/geometry/shape.rs b/src/geometry/shape.rs index ec43bf7..5c96f68 100644 --- a/src/geometry/shape.rs +++ b/src/geometry/shape.rs @@ -64,6 +64,8 @@ pub trait Shape: RayCast<f32> + PointQuery<f32> + DowncastSync { None } + // TODO: add a compute_local_aabb method? + /// Computes the AABB of this shape. fn compute_aabb(&self, position: &Isometry<f32>) -> AABB<f32>; @@ -16,10 +16,6 @@ pub extern crate nalgebra as na; pub extern crate ncollide2d as ncollide; #[cfg(feature = "dim3")] pub extern crate ncollide3d as ncollide; -#[cfg(feature = "dim2")] -pub extern crate salva2d as salva; -#[cfg(feature = "dim3")] -pub extern crate salva3d as salva; #[cfg(feature = "serde")] #[macro_use] extern crate serde; diff --git a/src/pipeline/fluids_pipeline.rs b/src/pipeline/fluids_pipeline.rs deleted file mode 100644 index 8d1a8d5..0000000 --- a/src/pipeline/fluids_pipeline.rs +++ /dev/null @@ -1,293 +0,0 @@ -use crate::approx::AbsDiffEq; -use crate::dynamics::RigidBodySet; -use crate::geometry::{ColliderHandle, ColliderSet}; -use crate::math::{Point, Vector}; -use crate::salva::solver::DFSPHSolver; -use crate::salva::LiquidWorld; -use na::{RealField, Unit}; -use ncollide::bounding_volume::BoundingVolume; -use ncollide::query::PointQuery; -use ncollide::shape::FeatureId; -use salva::coupling::CouplingManager; -use salva::geometry::{HGrid, HGridEntry}; -use salva::object::{BoundaryHandle, BoundarySet, Fluid}; -use salva::TimestepManager; -use std::collections::HashMap; -use std::sync::RwLock; - -/// Pipeline for particle-based fluid simulation. -pub struct FluidsPipeline { - liquid_world: LiquidWorld, - coupling: ColliderCouplingSet, -} - -impl FluidsPipeline { - /// Initialize a new pipeline for fluids simulation. - /// - /// # Parameters - /// - /// - `particle_radius`: the radius of every particle for the fluid simulation. - /// - `smoothing_factor`: the smoothing factor used to compute the SPH kernel radius. - /// The kernel radius will be computed as `particle_radius * smoothing_factor * 2.0. - pub fn new(particle_radius: f32, smoothing_factor: f32) -> Self { - let dfsph: DFSPHSolver = DFSPHSolver::new(); - - Self { - liquid_world: LiquidWorld::new(dfsph, particle_radius, smoothing_factor), - coupling: ColliderCouplingSet::new(), - } - } - - /// Advances the fluid simulation by `dt` milliseconds. - /// - /// All the fluid particles will be affected by an acceleration equal to `gravity`. - /// This `step` function may apply forces to some rigid-bodies that interact with fluids. - /// However, it will not integrate these forces. Use the `PhysicsPipeline` for this integration. - pub fn step( - &mut self, - gravity: &Vector<f32>, - dt: f32, - colliders: &ColliderSet, - bodies: &mut RigidBodySet, - ) { - self.liquid_world.step_with_coupling( - dt, - gravity, - &mut self.coupling.as_manager_mut(colliders, bodies), - ) - } -} - -/// The way a collider is coupled to a boundary object. -pub enum ParticleSampling { - /// The collider shape is approximated with the given sample points in local-space. - /// - /// It is recommended that those points are separated by a distance smaller or equal to twice - /// the particle radius used to initialize the LiquidWorld. - StaticSampling(Vec<Point<f32>>), - /// The collider shape is approximated by a dynamic set of points automatically computed based on contacts with fluid particles. - DynamicContactSampling, -} - -struct ColliderCouplingEntry { - coupling_method: ParticleSampling, - boundary: BoundaryHandle, - features: Vec<FeatureId>, -} - -/// Structure managing all the coupling between colliders from rapier with boundaries and fluids from salva. -pub struct ColliderCouplingSet { - entries: HashMap<ColliderHandle, ColliderCouplingEntry>, -} - -impl ColliderCouplingSet { - /// Create a new collider coupling manager. - pub fn new() -> Self { - Self { - entries: HashMap::new(), - } - } - - /// Register a coupling between a boundary and a collider. - /// There can be only up to one coupling between a collider and a boundary object. If a coupling - /// already exists for this collider when calling this function, the handle of the previously coupled - /// boundary is returned. - pub fn register_coupling( - &mut self, - boundary: BoundaryHandle, - collider: ColliderHandle, - coupling_method: ParticleSampling, - ) -> Option<BoundaryHandle> { - let old = self.entries.insert( - collider, - ColliderCouplingEntry { - coupling_method, - boundary, - features: Vec::new(), - }, - ); - - old.map(|e| e.boundary) - } - - /// Unregister a coupling between a boundary and a collider. - /// Note that this does not remove the boundary itself from the liquid world. - /// Returns the handle of the boundary this collider was coupled with. - pub fn unregister_coupling(&mut self, collider: ColliderHandle) -> Option<BoundaryHandle> { - let deleted = self.entries.remove(&collider); - deleted.map(|e| e.boundary) - } - - /// Use this collider coupling set as a coupling manager. - pub fn as_manager_mut<'a>( - &'a mut self, - colliders: &'a ColliderSet, - bodies: &'a mut RigidBodySet, - ) -> ColliderCouplingManager { - ColliderCouplingManager { - coupling: self, - colliders, - bodies, - } - } -} - -/// A manager for coupling colliders from rapier2d/rapier3D with the boundary -/// objects from salva. -pub struct ColliderCouplingManager<'a> { - coupling: &'a mut ColliderCouplingSet, - colliders: &'a ColliderSet, - bodies: &'a mut RigidBodySet, -} - -impl<'a> CouplingManager for ColliderCouplingManager<'a> { - fn update_boundaries( - &mut self, - timestep: &TimestepManager, - h: f32, - particle_radius: f32, - hgrid: &HGrid<HGridEntry>, - fluids: &mut [Fluid], - boundaries: &mut BoundarySet, - ) { - for (collider, coupling) in &mut self.coupling.entries { - if let (Some(collider), Some(boundary)) = ( - self.colliders.get(*collider), - boundaries.get_mut(coupling.boundary), - ) { - // Update the boundary's ability to receive forces. - let body = self.bodies.get(collider.parent()); - if let Some(body) = body { - if !body.is_dynamic() { - boundary.forces = None; - } else { - boundary.forces = Some(RwLock::new(Vec::new())); - boundary.clear_forces(true); - } - } - - // Update positions and velocities. - boundary.positions.clear(); - boundary.velocities.clear(); - boundary.volumes.clear(); - coupling.features.clear(); - - match &coupling.coupling_method { - ParticleSampling::StaticSampling(points) => { - for pt in points { - boundary.positions.push(collider.position() * pt); - // FIXME: how do we get the point-velocity of deformable bodies correctly? - let velocity = body.map(|b| b.velocity_at_point(pt)); - - boundary - .velocities - .push(velocity.unwrap_or(Vector::zeros())); - } - - boundary.volumes.resize(points.len(), na::zero::<f32>()); - } - ParticleSampling::DynamicContactSampling => { - let prediction = h * na::convert::<_, f32>(0.5); - let margin = particle_radius * na::convert::<_, f32>(0.1); - let collider_pos = collider.position(); - let aabb = collider - .shape() - .compute_aabb(&collider_pos) - .loosened(h + prediction); - - for particle in hgrid - .cells_intersecting_aabb(&aabb.mins, &aabb.maxs) - .flat_map(|e| e.1) - { - match particle { - HGridEntry::FluidParticle(fluid_id, particle_id) => { - let fluid = &mut fluids[*fluid_id]; - let particle_pos = fluid.positions[*particle_id] - + fluid.velocities[*particle_id] * timestep.dt(); - - if aabb.contains_local_point(&particle_pos) { - let (proj, feature) = - collider.shape().project_point_with_feature( - &collider_pos, - &particle_pos, - ); - - let dpt = particle_pos - proj.point; - - if let Some((normal, depth)) = - Unit::try_new_and_get(dpt, f32::default_epsilon()) - { - if proj.is_inside { - fluid.positions[*particle_id] -= - *normal * (depth + margin); - - let vel_err = - normal.dot(&fluid.velocities[*particle_id]); - - if vel_err > na::zero::<f32>() { - fluid.velocities[*particle_id] -= - *normal * vel_err; - } - } else if depth > h + prediction { - continue; - } - } - - let velocity = - body.map(|b| b.velocity_at_point(&proj.point)); - - boundary - .velocities - .push(velocity.unwrap_or(Vector::zeros())); - boundary.positions.push(proj.point); - boundary.volumes.push(na::zero::<f32>()); - coupling.features.push(feature); - } - } - HGridEntry::BoundaryParticle(..) => { - // Not yet implemented. - } - } - } - } - } - - boundary.clear_forces(true); - } - } - } - - fn transmit_forces(&mut self, boundaries: &BoundarySet) { - for (collider, coupling) in &self.coupling.entries { - if let (Some(collider), Some(boundary)) = ( - self.colliders.get(*collider), - boundaries.get(coupling.boundary), - ) { - if boundary.positions.is_empty() { - continue; - } - - if let Some(forces) = &boundary.forces { - let forces = forces.read().unwrap(); - if let Some(mut body) = self.bodies.get_mut(collider.parent) { - for (pos, force) in boundary.positions.iter().zip(forces.iter().cloned()) { - // FIXME: how do we deal with large density ratio? - // Is it only an issue with PBF? - // The following commented code was an attempt to limit the force applied - // to the bodies in order to avoid large forces. - // - // let ratio = na::convert::<_, f32>(3.0) - // * body.part(body_part.1).unwrap().inertia().mass(); - // - // if ratio < na::convert::<_, f32>(1.0) { - // force *= ratio; - // } - - body.apply_force_at_point(force, *pos) - } - } - } - } - } - } -} diff --git a/src/pipeline/mod.rs b/src/pipeline/mod.rs index 6212acb..287de9d 100644 --- a/src/pipeline/mod.rs +++ b/src/pipeline/mod.rs @@ -2,14 +2,10 @@ pub use collision_pipeline::CollisionPipeline; pub use event_handler::{ChannelEventCollector, EventHandler}; -#[cfg(feature = "fluids")] -pub use fluids_pipeline::FluidsPipeline; pub use physics_pipeline::PhysicsPipeline; pub use query_pipeline::QueryPipeline; mod collision_pipeline; mod event_handler; -#[cfg(feature = "fluids")] -mod fluids_pipeline; mod physics_pipeline; mod query_pipeline; diff --git a/src_testbed/engine.rs b/src_testbed/engine.rs index 52b9ca9..ff5e1ef 100644 --- a/src_testbed/engine.rs +++ b/src_testbed/engine.rs @@ -15,15 +15,11 @@ use rapier::dynamics::{RigidBodyHandle, RigidBodySet}; use rapier::geometry::{Collider, ColliderHandle, ColliderSet}; //use crate::objects::capsule::Capsule; //use crate::objects::convex::Convex; -//#[cfg(feature = "fluids")] -//use crate::objects::fluid::Fluid as FluidNode; //#[cfg(feature = "dim3")] //use crate::objects::mesh::Mesh; //use crate::objects::plane::Plane; //#[cfg(feature = "dim2")] //use crate::objects::polyline::Polyline; -//#[cfg(feature = "fluids")] -//use crate::objects::FluidRenderingMode; use crate::objects::capsule::Capsule; #[cfg(feature = "dim3")] use crate::objects::cone::Cone; @@ -58,22 +54,12 @@ impl GraphicsWindow for Window { pub struct GraphicsManager { rand: Pcg32, b2sn: HashMap<RigidBodyHandle, Vec<Node>>, - #[cfg(feature = "fluids")] - f2sn: HashMap<FluidHandle, FluidNode>, - #[cfg(feature = "fluids")] - boundary2sn: HashMap<BoundaryHandle, FluidNode>, b2color: HashMap<RigidBodyHandle, Point3<f32>>, c2color: HashMap<ColliderHandle, Point3<f32>>, b2wireframe: HashMap<RigidBodyHandle, bool>, - #[cfg(feature = "fluids")] - f2color: HashMap<FluidHandle, Point3<f32>>, ground_color: Point3<f32>, camera: Camera, ground_handle: Option<RigidBodyHandle>, - #[cfg(feature = "fluids")] - fluid_rendering_mode: FluidRenderingMode, - #[cfg(feature = "fluids")] - render_boundary_particles: bool, } impl GraphicsManager { @@ -96,21 +82,11 @@ impl GraphicsManager { camera, rand: Pcg32::seed_from_u64(0), b2sn: HashMap::new(), - #[cfg(feature = "fluids")] - f2sn: HashMap::new(), - #[cfg(feature = "fluids")] - boundary2sn: HashMap::new(), b2color: HashMap::new(), c2color: HashMap::new(), - #[cfg(feature = "fluids")] - f2color: HashMap::new(), ground_color: Point3::new(0.5, 0.5, 0.5), b2wireframe: HashMap::new(), ground_handle: None, - #[cfg(feature = "fluids")] - fluid_rendering_mode: FluidRenderingMode::StaticColor, - #[cfg(feature = "fluids")] - render_boundary_particles: false, } } @@ -118,20 +94,6 @@ impl GraphicsManager { self.ground_handle = handle } - #[cfg(feature = "fluids")] - pub fn set_fluid_rendering_mode(&mut self, mode: FluidRenderingMode) { - self.fluid_rendering_mode = mode; - } - - #[cfg(feature = "fluids")] - pub fn enable_boundary_particles_rendering(&mut self, enabled: bool) { - self.render_boundary_particles = enabled; - - for sn in self.boundary2sn.values_mut() { - sn.scene_node_mut().set_visible(enabled); - } - } - pub fn clear(&mut self, window: &mut Window) { for sns in self.b2sn.values_mut() { for sn in sns.iter_mut() { @@ -141,17 +103,7 @@ impl GraphicsManager { } } - #[cfg(feature = "fluids")] - for sn in self.f2sn.values_mut().chain(self.boundary2sn.values_mut()) { - let node = sn.scene_node_mut(); - window.remove_graphics_node(node); - } - self.b2sn.clear(); - #[cfg(feature = "fluids")] - self.f2sn.clear(); - #[cfg(feature = "fluids")] - self.boundary2sn.clear(); self.c2color.clear(); self.b2color.clear(); self.b2wireframe.clear(); @@ -170,15 +122,6 @@ impl GraphicsManager { self.b2sn.remove(&body); } - #[cfg(feature = "fluids")] - pub fn set_fluid_color(&mut self, f: FluidHandle, color: Point3<f32>) { - self.f2color.insert(f, color); - - if let Some(n) = self.f2sn.get_mut(&f) { - n.set_color(color) - } - } - pub fn set_body_color(&mut self, b: RigidBodyHandle, color: Point3<f32>) { self.b2color.insert(b, color); @@ -234,6 +177,10 @@ impl GraphicsManager { } } + pub fn next_color(&mut self) -> Point3<f32> { + Self::gen_color(&mut self.rand) + } + fn gen_color(rng: &mut Pcg32) -> Point3<f32> { let mut color: Point3<f32> = rng.gen(); color *= 1.5; @@ -258,49 +205,6 @@ impl GraphicsManager { color } - #[cfg(feature = "fluids")] - pub fn add_fluid( - &mut self, - window: &mut Window, - handle: FluidHandle, - fluid: &Fluid<f32>, - particle_radius: f32, - ) { - let rand = &mut self.rand; - let color = *self - .f2color - .entry(handle) - .or_insert_with(|| Self::gen_color(rand)); - - self.add_fluid_with_color(window, handle, fluid, particle_radius, color); - } - - #[cfg(feature = "fluids")] - pub fn add_boundary( - &mut self, - window: &mut Window, - handle: BoundaryHandle, - boundary: &Boundary<f32>, - particle_radius: f32, - ) { - let color = self.ground_color; - let node = FluidNode::new(particle_radius, &boundary.positions, color, window); - self.boundary2sn.insert(handle, node); - } - - #[cfg(feature = "fluids")] - pub fn add_fluid_with_color( - &mut self, - window: &mut Window, - handle: FluidHandle, - fluid: &Fluid<f32>, - particle_radius: f32, - color: Point3<f32>, - ) { - let node = FluidNode::new(particle_radius, &fluid.positions, color, window); - self.f2sn.insert(handle, node); - } - pub fn add( &mut self, window: &mut Window, @@ -642,23 +546,6 @@ impl GraphicsManager { } */ - #[cfg(feature = "fluids")] - pub fn draw_fluids(&mut self, liquid_world: &LiquidWorld<f32>) { - for (i, fluid) in liquid_world.fluids().iter() { - if let Some(node) = self.f2sn.get_mut(&i) { - node.update_with_fluid(fluid, self.fluid_rendering_mode) - } - } - - if self.render_boundary_particles { - for (i, boundary) in liquid_world.boundaries().iter() { - if let Some(node) = self.boundary2sn.get_mut(&i) { - node.update_with_boundary(boundary) - } - } - } - } - pub fn draw(&mut self, _bodies: &RigidBodySet, colliders: &ColliderSet, window: &mut Window) { // use kiss3d::camera::Camera; // println!( diff --git a/src_testbed/lib.rs b/src_testbed/lib.rs index e077bb1..4b0830f 100644 --- a/src_testbed/lib.rs +++ b/src_testbed/lib.rs @@ -13,6 +13,10 @@ extern crate nphysics3d as nphysics; extern crate rapier2d as rapier; #[cfg(feature = "dim3")] extern crate rapier3d as rapier; +#[cfg(all(feature = "dim2", feature = "fluids"))] +extern crate salva2d as salva; +#[cfg(all(feature = "dim3", feature = "fluids"))] +extern crate salva3d as salva; #[macro_use] extern crate bitflags; @@ -22,7 +26,8 @@ extern crate bitflags; extern crate log; pub use crate::engine::GraphicsManager; -pub use crate::testbed::Testbed; +pub use crate::plugin::TestbedPlugin; +pub use crate::testbed::{PhysicsState, Testbed}; #[cfg(all(feature = "dim2", feature = "other-backends"))] mod box2d_backend; @@ -32,6 +37,7 @@ mod nphysics_backend; pub mod objects; #[cfg(all(feature = "dim3", feature = "other-backends"))] mod physx_backend; +mod plugin; mod testbed; mod ui; diff --git a/src_testbed/plugin.rs b/src_testbed/plugin.rs new file mode 100644 index 0000000..7ad018b --- /dev/null +++ b/src_testbed/plugin.rs @@ -0,0 +1,12 @@ +use crate::testbed::PhysicsState; +use kiss3d::window::Window; +use na::Point3; + +pub trait TestbedPlugin { + fn init_graphics(&mut self, window: &mut Window, gen_color: &mut dyn FnMut() -> Point3<f32>); + fn clear_graphics(&mut self, window: &mut Window); + fn run_callbacks(&mut self, window: &mut Window, physics: &mut PhysicsState, t: f32); + fn step(&mut self, physics: &mut PhysicsState); + fn draw(&mut self); + fn profiling_string(&self) -> String; +} diff --git a/src_testbed/testbed.rs b/src_testbed/testbed.rs index 66b5953..7a72293 100644 --- a/src_testbed/testbed.rs +++ b/src_testbed/testbed.rs @@ -4,8 +4,7 @@ use std::path::Path; use std::rc::Rc; use crate::engine::GraphicsManager; -#[cfg(feature = "fluids")] -use crate::objects::FluidRenderingMode; +use crate::plugin::TestbedPlugin; use crate::ui::TestbedUi; use crossbeam::channel::Receiver; use kiss3d::camera::Camera; @@ -29,8 +28,6 @@ use rapier::geometry::{ }; use rapier::math::Vector; use rapier::pipeline::{ChannelEventCollector, PhysicsPipeline, QueryPipeline}; -#[cfg(feature = "fluids")] -use salva::{coupling::ColliderCouplingSet, object::FluidHandle, LiquidWorld}; #[cfg(all(feature = "dim2", feature = "other-backends"))] use crate::box2d_backend::Box2dWorld; @@ -185,6 +182,8 @@ pub struct PhysicsState { pub joints: JointSet, pub pipeline: PhysicsPipeline, pub query_pipeline: QueryPipeline, + pub integration_parameters: IntegrationParameters, + pub gravity: Vector<f32>, } impl PhysicsState { @@ -197,6 +196,8 @@ impl PhysicsState { joints: JointSet::new(), pipeline: PhysicsPipeline::new(), query_pipeline: QueryPipeline::new(), + integration_parameters: IntegrationParameters::default(), + gravity: Vector::y() * -9.81, } } } @@ -225,25 +226,14 @@ pub struct TestbedState { pub timestep_id: usize, } -#[cfg(feature = "fluids")] -struct FluidsState { - world: LiquidWorld<f32>, - coupling: ColliderCouplingSet<f32, RigidBodyHandle>, -} - pub struct Testbed { builders: Vec<(&'static str, fn(&mut Testbed))>, - #[cfg(feature = "fluids")] - fluids: Option<FluidsState>, - gravity: Vector<f32>, - integration_parameters: IntegrationParameters, physics: PhysicsState, graphics: GraphicsManager, nsteps: usize, camera_locked: bool, // Used so that the camera can remain the same before and after we change backend or press the restart button. callbacks: Callbacks, - #[cfg(feature = "fluids")] - callbacks_fluids: CallbacksFluids, + plugins: Vec<Box<dyn TestbedPlugin>>, time: f32, hide_counters: bool, // persistant_contacts: HashMap<ContactId, bool>, @@ -264,20 +254,6 @@ pub struct Testbed { type Callbacks = Vec<Box<dyn FnMut(&mut Window, &mut PhysicsState, &PhysicsEvents, &mut GraphicsManager, f32)>>; -#[cfg(feature = "fluids")] -type CallbacksFluids = Vec< - Box< - dyn FnMut( - &mut Window, - &mut LiquidWorld<f32>, - &mut ColliderCouplingSet<f32, RigidBodyHandle>, - &mut PhysicsState, - &mut GraphicsManager, - f32, - ), - >, ->; - impl Testbed { pub fn new_empty() -> Testbed { let graphics = GraphicsManager::new(); @@ -330,8 +306,6 @@ impl Testbed { thread_pool, }; - let gravity = Vector::y() * -9.81; - let integration_parameters = IntegrationParameters::default(); let contact_channel = crossbeam::channel::unbounded(); let proximity_channel = crossbeam::channel::unbounded(); let event_handler = ChannelEventCollector::new(proximity_channel.0, contact_channel.0); @@ -343,14 +317,9 @@ impl Testbed { Testbed { builders: Vec::new(), - #[cfg(feature = "fluids")] - fluids: None, - gravity, - integration_parameters, physics, callbacks: Vec::new(), - #[cfg(feature = "fluids")] - callbacks_fluids: Vec::new(), + plugins: Vec::new(), graphics, nsteps: 1, camera_locked: false, @@ -404,6 +373,14 @@ impl Testbed { self.hide_counters = false; } + pub fn integration_parameters_mut(&mut self) -> &mut IntegrationParameters { + &mut self.physics.integration_parameters + } + + pub fn physics_state_mut(&mut self) -> &mut PhysicsState { + &mut self.physics + } + pub fn set_world(&mut self, bodies: RigidBodySet, colliders: ColliderSet, joints: JointSet) { self.set_world_with_gravity(bodies, colliders, joints, Vector::y() * -9.81) } @@ -451,8 +428,8 @@ impl Testbed { || self.state.selected_backend == PHYSX_BACKEND_TWO_FRICTION_DIR { self.physx = Some(PhysxWorld::from_rapier( - self.gravity, - &self.integration_parameters, + self.physics.gravity, + &self.physics.integration_parameters, &self.physics.bodies, &self.physics.colliders, &self.physics.joints, @@ -466,7 +443,7 @@ impl Testbed { { if self.state.selected_backend == NPHYSICS_BACKEND { self.nphysics = Some(NPhysicsWorld::from_rapier( - self.gravity, + self.physics.gravity, &self.physics.bodies, &self.physics.colliders, &self.physics.joints, @@ -475,19 +452,6 @@ impl Testbed { } } - #[cfg(feature = "fluids")] - pub fn set_liquid_world( - &mut self, - mut liquid_world: LiquidWorld<f32>, - coupling: ColliderCouplingSet<f32, RigidBodyHandle>, - ) { - liquid_world.counters.enable(); - self.fluids = Some(FluidsState { - world: liquid_world, - coupling, - }); - } - pub fn set_builders(&mut self, builders: Vec<(&'static str, fn(&mut Self))>) { self.state.example_names = builders.iter().map(|e| e.0).collect(); self.builders = builders @@ -515,25 +479,10 @@ impl Testbed { self.graphics.set_collider_initial_color(collider, color); } - #[cfg(feature = "fluids")] - pub fn set_flu |
