From 0d332930892184c34ab0adcc6b7a5866632f2ec1 Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Fri, 27 Sep 2024 12:01:35 +0200 Subject: [PATCH 1/9] profiling support --- .vscode/settings.json | 3 ++- crates/rapier2d-f64/Cargo.toml | 1 + crates/rapier2d/Cargo.toml | 1 + crates/rapier3d-f64/Cargo.toml | 1 + crates/rapier3d-stl/Cargo.toml | 9 ++++++++- crates/rapier3d-urdf/Cargo.toml | 9 ++++++++- crates/rapier3d/Cargo.toml | 1 + crates/rapier_testbed2d-f64/Cargo.toml | 2 +- crates/rapier_testbed2d/Cargo.toml | 2 +- crates/rapier_testbed3d-f64/Cargo.toml | 2 +- crates/rapier_testbed3d/Cargo.toml | 2 +- src/control/character_controller.rs | 5 +++++ src/control/ray_cast_vehicle_controller.rs | 3 +++ src/dynamics/ccd/ccd_solver.rs | 2 ++ src/dynamics/ccd/toi_entry.rs | 1 + .../joint/impulse_joint/impulse_joint_set.rs | 3 +++ src/dynamics/joint/multibody_joint/multibody.rs | 2 ++ src/dynamics/joint/multibody_joint/multibody_ik.rs | 2 ++ .../joint/multibody_joint/multibody_joint.rs | 1 + .../joint/multibody_joint/multibody_joint_set.rs | 7 +++++++ src/dynamics/rigid_body.rs | 3 +++ src/dynamics/rigid_body_components.rs | 1 + src/dynamics/rigid_body_set.rs | 1 + .../contact_constraint/contact_constraints_set.rs | 4 ++++ .../generic_one_body_constraint.rs | 1 + src/dynamics/solver/interaction_groups.rs | 1 + src/dynamics/solver/island_solver.rs | 1 + .../joint_constraint/joint_constraints_set.rs | 2 ++ .../joint_constraint/joint_velocity_constraint.rs | 1 + src/dynamics/solver/parallel_island_solver.rs | 1 + src/dynamics/solver/velocity_solver.rs | 2 ++ .../broad_phase_multi_sap/broad_phase_multi_sap.rs | 6 ++++++ src/geometry/broad_phase_multi_sap/sap_axis.rs | 2 ++ src/geometry/broad_phase_multi_sap/sap_layer.rs | 5 +++++ src/geometry/broad_phase_multi_sap/sap_region.rs | 1 + src/geometry/contact_pair.rs | 1 + src/geometry/interaction_graph.rs | 2 ++ src/geometry/mesh_converter.rs | 1 + src/geometry/narrow_phase.rs | 8 ++++++++ .../debug_render_pipeline/debug_render_pipeline.rs | 7 +++++++ src/pipeline/query_pipeline/mod.rs | 13 +++++++++++++ src_testbed/box2d_backend.rs | 3 +++ src_testbed/harness/mod.rs | 1 + src_testbed/physics/mod.rs | 1 + src_testbed/physx_backend.rs | 1 + src_testbed/testbed.rs | 1 + 46 files changed, 123 insertions(+), 7 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index e9327368b..22f0f9768 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -1,5 +1,6 @@ { "rust-analyzer.cargo.features": [ - "simd-stable" + "simd-stable", + "dim3" ] } \ No newline at end of file diff --git a/crates/rapier2d-f64/Cargo.toml b/crates/rapier2d-f64/Cargo.toml index 6517e0f8c..4a149e037 100644 --- a/crates/rapier2d-f64/Cargo.toml +++ b/crates/rapier2d-f64/Cargo.toml @@ -84,6 +84,7 @@ bitflags = "2" log = "0.4" ordered-float = "4" thiserror = "1" +profiling = "1.0" [dev-dependencies] bincode = "1" diff --git a/crates/rapier2d/Cargo.toml b/crates/rapier2d/Cargo.toml index e2afba125..f854cb4d5 100644 --- a/crates/rapier2d/Cargo.toml +++ b/crates/rapier2d/Cargo.toml @@ -84,6 +84,7 @@ bitflags = "2" log = "0.4" ordered-float = "4" thiserror = "1" +profiling = "1.0" [dev-dependencies] bincode = "1" diff --git a/crates/rapier3d-f64/Cargo.toml b/crates/rapier3d-f64/Cargo.toml index de8a7415e..a7ea58362 100644 --- a/crates/rapier3d-f64/Cargo.toml +++ b/crates/rapier3d-f64/Cargo.toml @@ -87,6 +87,7 @@ bitflags = "2" log = "0.4" ordered-float = "4" thiserror = "1" +profiling = "1.0" [dev-dependencies] bincode = "1" diff --git a/crates/rapier3d-stl/Cargo.toml b/crates/rapier3d-stl/Cargo.toml index f24f10242..3c84536bf 100644 --- a/crates/rapier3d-stl/Cargo.toml +++ b/crates/rapier3d-stl/Cargo.toml @@ -7,7 +7,13 @@ documentation = "https://docs.rs/rapier3d-stl" homepage = "https://rapier.rs" repository = "https://github.com/dimforge/rapier" readme = "README.md" -categories = ["science", "game-development", "mathematics", "simulation", "wasm"] +categories = [ + "science", + "game-development", + "mathematics", + "simulation", + "wasm", +] keywords = ["physics", "joints", "multibody", "robotics", "urdf"] license = "Apache-2.0" edition = "2021" @@ -15,5 +21,6 @@ edition = "2021" [dependencies] thiserror = "1.0.61" stl_io = "0.7" +profiling = "1.0" rapier3d = { version = "0.22", path = "../rapier3d" } diff --git a/crates/rapier3d-urdf/Cargo.toml b/crates/rapier3d-urdf/Cargo.toml index ef53da981..24cb7bc38 100644 --- a/crates/rapier3d-urdf/Cargo.toml +++ b/crates/rapier3d-urdf/Cargo.toml @@ -7,7 +7,13 @@ documentation = "https://docs.rs/rapier3d-urdf" homepage = "https://rapier.rs" repository = "https://github.com/dimforge/rapier" readme = "README.md" -categories = ["science", "game-development", "mathematics", "simulation", "wasm"] +categories = [ + "science", + "game-development", + "mathematics", + "simulation", + "wasm", +] keywords = ["physics", "joints", "multibody", "robotics", "urdf"] license = "Apache-2.0" edition = "2021" @@ -21,6 +27,7 @@ anyhow = "1" bitflags = "2" # NOTE: we are not using the (more recent) urdf-rs crate because of https://github.com/openrr/urdf-rs/issues/94 xurdf = "0.2" +profiling = "1.0" rapier3d = { version = "0.22", path = "../rapier3d" } rapier3d-stl = { version = "0.3.0", path = "../rapier3d-stl", optional = true } diff --git a/crates/rapier3d/Cargo.toml b/crates/rapier3d/Cargo.toml index bd9f77cbc..bc048c140 100644 --- a/crates/rapier3d/Cargo.toml +++ b/crates/rapier3d/Cargo.toml @@ -87,6 +87,7 @@ bitflags = "2" log = "0.4" ordered-float = "4" thiserror = "1" +profiling = "1.0" [dev-dependencies] bincode = "1" diff --git a/crates/rapier_testbed2d-f64/Cargo.toml b/crates/rapier_testbed2d-f64/Cargo.toml index 9770080b9..84a0473ef 100644 --- a/crates/rapier_testbed2d-f64/Cargo.toml +++ b/crates/rapier_testbed2d-f64/Cargo.toml @@ -55,7 +55,7 @@ bevy_ecs = "0.14" bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" -#bevy_prototype_debug_lines = "0.7" +profiling = "1.0" # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/crates/rapier_testbed2d/Cargo.toml b/crates/rapier_testbed2d/Cargo.toml index 77373bd45..ac7a0b554 100644 --- a/crates/rapier_testbed2d/Cargo.toml +++ b/crates/rapier_testbed2d/Cargo.toml @@ -55,7 +55,7 @@ bevy_ecs = "0.14" bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" -#bevy_prototype_debug_lines = "0.7" +profiling = "1.0" # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/crates/rapier_testbed3d-f64/Cargo.toml b/crates/rapier_testbed3d-f64/Cargo.toml index 3fa2511fe..d16989b2a 100644 --- a/crates/rapier_testbed3d-f64/Cargo.toml +++ b/crates/rapier_testbed3d-f64/Cargo.toml @@ -57,7 +57,7 @@ bevy_ecs = "0.14" bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" -#bevy_prototype_debug_lines = { version = "0.7", features = [ "3d" ] } +profiling = "1.0" # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/crates/rapier_testbed3d/Cargo.toml b/crates/rapier_testbed3d/Cargo.toml index a7a3fe85e..e213b073b 100644 --- a/crates/rapier_testbed3d/Cargo.toml +++ b/crates/rapier_testbed3d/Cargo.toml @@ -58,7 +58,7 @@ bevy_ecs = "0.14" bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" -#bevy_prototype_debug_lines = { version = "0.7", features = [ "3d" ] } +profiling = "1.0" # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/src/control/character_controller.rs b/src/control/character_controller.rs index c8a15c5f5..b9d9699a3 100644 --- a/src/control/character_controller.rs +++ b/src/control/character_controller.rs @@ -211,6 +211,7 @@ impl KinematicCharacterController { } /// Computes the possible movement for a shape. + #[profiling::function] pub fn move_shape( &self, dt: Real, @@ -401,6 +402,7 @@ impl KinematicCharacterController { self.offset.eval(up_extends) * 1.2 } + #[profiling::function] fn detect_grounded_status_and_apply_friction( &self, dt: Real, @@ -629,6 +631,7 @@ impl KinematicCharacterController { Vector2::new(side_extent, up_extent) } + #[profiling::function] fn handle_stairs( &self, bodies: &RigidBodySet, @@ -789,6 +792,7 @@ impl KinematicCharacterController { /// impulses to the rigid-bodies surrounding the character shape at the time of the collisions. /// Note that the impulse calculation is only approximate as it is not based on a global /// constraints resolution scheme. + #[profiling::function] pub fn solve_character_collision_impulses<'a>( &self, dt: Real, @@ -818,6 +822,7 @@ impl KinematicCharacterController { /// impulses to the rigid-bodies surrounding the character shape at the time of the collision. /// Note that the impulse calculation is only approximate as it is not based on a global /// constraints resolution scheme. + #[profiling::function] fn solve_single_character_collision_impulse( &self, dt: Real, diff --git a/src/control/ray_cast_vehicle_controller.rs b/src/control/ray_cast_vehicle_controller.rs index 98b63398b..eaa506b9e 100644 --- a/src/control/ray_cast_vehicle_controller.rs +++ b/src/control/ray_cast_vehicle_controller.rs @@ -321,6 +321,7 @@ impl DynamicRayCastVehicleController { wheel.wheel_axle_ws = chassis_transform * wheel.axle_cs; } + #[profiling::function] fn ray_cast( &mut self, bodies: &RigidBodySet, @@ -403,6 +404,7 @@ impl DynamicRayCastVehicleController { } /// Updates the vehicle’s velocity based on its suspension, engine force, and brake. + #[profiling::function] pub fn update_vehicle( &mut self, dt: Real, @@ -531,6 +533,7 @@ impl DynamicRayCastVehicleController { } } + #[profiling::function] fn update_friction(&mut self, bodies: &mut RigidBodySet, colliders: &ColliderSet, dt: Real) { let num_wheels = self.wheels.len(); diff --git a/src/dynamics/ccd/ccd_solver.rs b/src/dynamics/ccd/ccd_solver.rs index e9ecfb865..0f97cfca2 100644 --- a/src/dynamics/ccd/ccd_solver.rs +++ b/src/dynamics/ccd/ccd_solver.rs @@ -108,6 +108,7 @@ impl CCDSolver { } /// Find the first time a CCD-enabled body has a non-sensor collider hitting another non-sensor collider. + #[profiling::function] pub fn find_first_impact( &mut self, dt: Real, @@ -225,6 +226,7 @@ impl CCDSolver { } /// Outputs the set of bodies as well as their first time-of-impact event. + #[profiling::function] pub fn predict_impacts_at_next_positions( &mut self, dt: Real, diff --git a/src/dynamics/ccd/toi_entry.rs b/src/dynamics/ccd/toi_entry.rs index 82b453247..a85e10752 100644 --- a/src/dynamics/ccd/toi_entry.rs +++ b/src/dynamics/ccd/toi_entry.rs @@ -34,6 +34,7 @@ impl TOIEntry { } } + #[profiling::function] pub fn try_from_colliders( query_dispatcher: &QD, ch1: ColliderHandle, diff --git a/src/dynamics/joint/impulse_joint/impulse_joint_set.rs b/src/dynamics/joint/impulse_joint/impulse_joint_set.rs index 8f47e0e42..093a37226 100644 --- a/src/dynamics/joint/impulse_joint/impulse_joint_set.rs +++ b/src/dynamics/joint/impulse_joint/impulse_joint_set.rs @@ -244,6 +244,7 @@ impl ImpulseJointSet { /// /// If `wake_up` is set to `true`, then the bodies attached to this joint will be /// automatically woken up during the next timestep. + #[profiling::function] pub fn insert( &mut self, body1: RigidBodyHandle, @@ -329,6 +330,7 @@ impl ImpulseJointSet { /// /// If `wake_up` is set to `true`, then the bodies attached to this joint will be /// automatically woken up. + #[profiling::function] pub fn remove(&mut self, handle: ImpulseJointHandle, wake_up: bool) -> Option { let id = self.joint_ids.remove(handle.0)?; let endpoints = self.joint_graph.graph.edge_endpoints(id)?; @@ -356,6 +358,7 @@ impl ImpulseJointSet { /// The provided rigid-body handle is not required to identify a rigid-body that /// is still contained by the `bodies` component set. /// Returns the (now invalid) handles of the removed impulse_joints. + #[profiling::function] pub fn remove_joints_attached_to_rigid_body( &mut self, handle: RigidBodyHandle, diff --git a/src/dynamics/joint/multibody_joint/multibody.rs b/src/dynamics/joint/multibody_joint/multibody.rs index f05ce7565..cb256240e 100644 --- a/src/dynamics/joint/multibody_joint/multibody.rs +++ b/src/dynamics/joint/multibody_joint/multibody.rs @@ -489,6 +489,7 @@ impl Multibody { } /// Computes the constant terms of the dynamics. + #[profiling::function] pub(crate) fn update_dynamics(&mut self, dt: Real, bodies: &mut RigidBodySet) { /* * Compute velocities. @@ -1094,6 +1095,7 @@ impl Multibody { /// is the sum of the current position of `self` and this `displacement`. // TODO: this shares a lot of code with `forward_kinematics` and `update_body_jacobians`, except // that we are only traversing a single kinematic chain. Could this be refactored? + #[profiling::function] pub fn forward_kinematics_single_branch( &self, bodies: &RigidBodySet, diff --git a/src/dynamics/joint/multibody_joint/multibody_ik.rs b/src/dynamics/joint/multibody_joint/multibody_ik.rs index b5e0de676..6923eec67 100644 --- a/src/dynamics/joint/multibody_joint/multibody_ik.rs +++ b/src/dynamics/joint/multibody_joint/multibody_ik.rs @@ -64,6 +64,7 @@ impl Multibody { /// desired transform. /// /// The displacement calculated by this function is added to the `displacement` vector. + #[profiling::function] pub fn inverse_kinematics_delta_with_jacobian( jacobian: &Jacobian, desired_movement: &SpacialVector, @@ -88,6 +89,7 @@ impl Multibody { /// can be moved through the inverse-kinematics process. Any joint for which `joint_can_move` /// returns `false` will have its corresponding displacement constrained to 0. /// Set the closure to `|_| true` if all the joints are free to move. + #[profiling::function] pub fn inverse_kinematics( &self, bodies: &RigidBodySet, diff --git a/src/dynamics/joint/multibody_joint/multibody_joint.rs b/src/dynamics/joint/multibody_joint/multibody_joint.rs index 179b061c2..4785c38cd 100644 --- a/src/dynamics/joint/multibody_joint/multibody_joint.rs +++ b/src/dynamics/joint/multibody_joint/multibody_joint.rs @@ -86,6 +86,7 @@ impl MultibodyJoint { } /// Integrate the position of this multibody_joint. + #[profiling::function] pub fn integrate(&mut self, dt: Real, vels: &[Real]) { let locked_bits = self.data.locked_axes.bits(); let mut curr_free_dof = 0; diff --git a/src/dynamics/joint/multibody_joint/multibody_joint_set.rs b/src/dynamics/joint/multibody_joint/multibody_joint_set.rs index de1748c4a..ac00874ac 100644 --- a/src/dynamics/joint/multibody_joint/multibody_joint_set.rs +++ b/src/dynamics/joint/multibody_joint/multibody_joint_set.rs @@ -153,6 +153,7 @@ impl MultibodyJointSet { } /// Inserts a new multibody_joint into this set. + #[profiling::function] fn do_insert( &mut self, body1: RigidBodyHandle, @@ -213,6 +214,7 @@ impl MultibodyJointSet { } /// Removes a multibody_joint from this set. + #[profiling::function] pub fn remove(&mut self, handle: MultibodyJointHandle, wake_up: bool) { if let Some(removed) = self.rb2mb.get(handle.0).copied() { let multibody = self.multibodies.remove(removed.multibody.0).unwrap(); @@ -259,6 +261,7 @@ impl MultibodyJointSet { } /// Removes all the multibody_joints from the multibody the given rigid-body is part of. + #[profiling::function] pub fn remove_multibody_articulations(&mut self, handle: RigidBodyHandle, wake_up: bool) { if let Some(removed) = self.rb2mb.get(handle.0).copied() { // Remove the multibody. @@ -281,6 +284,7 @@ impl MultibodyJointSet { } /// Removes all the multibody joints attached to a rigid-body. + #[profiling::function] pub fn remove_joints_attached_to_rigid_body(&mut self, rb_to_remove: RigidBodyHandle) { // TODO: optimize this. if let Some(link_to_remove) = self.rb2mb.get(rb_to_remove.0).copied() { @@ -412,6 +416,7 @@ impl MultibodyJointSet { } /// Iterates through all the joints attached to the given rigid-body. + #[profiling::function] pub fn attached_joints( &self, rb: RigidBodyHandle, @@ -428,6 +433,7 @@ impl MultibodyJointSet { /// Iterate through the handles of all the rigid-bodies attached to this rigid-body /// by a multibody_joint. + #[profiling::function] pub fn attached_bodies( &self, body: RigidBodyHandle, @@ -441,6 +447,7 @@ impl MultibodyJointSet { /// Iterate through the handles of all the rigid-bodies attached to this rigid-body /// by an enabled multibody_joint. + #[profiling::function] pub fn bodies_attached_with_enabled_joint( &self, body: RigidBodyHandle, diff --git a/src/dynamics/rigid_body.rs b/src/dynamics/rigid_body.rs index 8522d4d43..60f403e7f 100644 --- a/src/dynamics/rigid_body.rs +++ b/src/dynamics/rigid_body.rs @@ -1016,6 +1016,7 @@ impl RigidBody { /// Applies an impulse at the center-of-mass of this rigid-body. /// The impulse is applied right away, changing the linear velocity. /// This does nothing on non-dynamic bodies. + #[profiling::function] pub fn apply_impulse(&mut self, impulse: Vector, wake_up: bool) { if !impulse.is_zero() && self.body_type == RigidBodyType::Dynamic { self.vels.linvel += impulse.component_mul(&self.mprops.effective_inv_mass); @@ -1030,6 +1031,7 @@ impl RigidBody { /// The impulse is applied right away, changing the angular velocity. /// This does nothing on non-dynamic bodies. #[cfg(feature = "dim2")] + #[profiling::function] pub fn apply_torque_impulse(&mut self, torque_impulse: Real, wake_up: bool) { if !torque_impulse.is_zero() && self.body_type == RigidBodyType::Dynamic { self.vels.angvel += self.mprops.effective_world_inv_inertia_sqrt @@ -1045,6 +1047,7 @@ impl RigidBody { /// The impulse is applied right away, changing the angular velocity. /// This does nothing on non-dynamic bodies. #[cfg(feature = "dim3")] + #[profiling::function] pub fn apply_torque_impulse(&mut self, torque_impulse: Vector, wake_up: bool) { if !torque_impulse.is_zero() && self.body_type == RigidBodyType::Dynamic { self.vels.angvel += self.mprops.effective_world_inv_inertia_sqrt diff --git a/src/dynamics/rigid_body_components.rs b/src/dynamics/rigid_body_components.rs index 6bc294969..e451510a7 100644 --- a/src/dynamics/rigid_body_components.rs +++ b/src/dynamics/rigid_body_components.rs @@ -624,6 +624,7 @@ impl RigidBodyVelocity { /// The kinetic energy of this rigid-body. #[must_use] + #[profiling::function] pub fn kinetic_energy(&self, rb_mprops: &RigidBodyMassProps) -> Real { let mut energy = (rb_mprops.mass() * self.linvel.norm_squared()) / 2.0; diff --git a/src/dynamics/rigid_body_set.rs b/src/dynamics/rigid_body_set.rs index 314530039..1261e4a54 100644 --- a/src/dynamics/rigid_body_set.rs +++ b/src/dynamics/rigid_body_set.rs @@ -84,6 +84,7 @@ impl RigidBodySet { } /// Removes a rigid-body, and all its attached colliders and impulse_joints, from these sets. + #[profiling::function] pub fn remove( &mut self, handle: RigidBodyHandle, diff --git a/src/dynamics/solver/contact_constraint/contact_constraints_set.rs b/src/dynamics/solver/contact_constraint/contact_constraints_set.rs index 4d2b40d5e..7b046b631 100644 --- a/src/dynamics/solver/contact_constraint/contact_constraints_set.rs +++ b/src/dynamics/solver/contact_constraint/contact_constraints_set.rs @@ -454,6 +454,7 @@ impl ContactConstraintsSet { } } + #[profiling::function] pub fn solve_restitution( &mut self, solver_vels: &mut [SolverVel], @@ -465,6 +466,7 @@ impl ContactConstraintsSet { } } + #[profiling::function] pub fn solve_restitution_wo_bias( &mut self, solver_vels: &mut [SolverVel], @@ -477,6 +479,7 @@ impl ContactConstraintsSet { } } + #[profiling::function] pub fn solve_friction( &mut self, solver_vels: &mut [SolverVel], @@ -495,6 +498,7 @@ impl ContactConstraintsSet { } } + #[profiling::function] pub fn update( &mut self, params: &IntegrationParameters, diff --git a/src/dynamics/solver/contact_constraint/generic_one_body_constraint.rs b/src/dynamics/solver/contact_constraint/generic_one_body_constraint.rs index e25499569..687340794 100644 --- a/src/dynamics/solver/contact_constraint/generic_one_body_constraint.rs +++ b/src/dynamics/solver/contact_constraint/generic_one_body_constraint.rs @@ -272,6 +272,7 @@ impl GenericOneBodyConstraint { ); } + #[profiling::function] pub fn solve( &mut self, jacobians: &DVector, diff --git a/src/dynamics/solver/interaction_groups.rs b/src/dynamics/solver/interaction_groups.rs index 1e834e6a3..13d66550d 100644 --- a/src/dynamics/solver/interaction_groups.rs +++ b/src/dynamics/solver/interaction_groups.rs @@ -218,6 +218,7 @@ impl InteractionGroups { } #[cfg(feature = "simd-is-enabled")] + #[profiling::function] pub fn group_joints( &mut self, island_id: usize, diff --git a/src/dynamics/solver/island_solver.rs b/src/dynamics/solver/island_solver.rs index f9c84a5f5..b7c44dfa3 100644 --- a/src/dynamics/solver/island_solver.rs +++ b/src/dynamics/solver/island_solver.rs @@ -28,6 +28,7 @@ impl IslandSolver { } } + #[profiling::function] pub fn init_and_solve( &mut self, island_id: usize, diff --git a/src/dynamics/solver/joint_constraint/joint_constraints_set.rs b/src/dynamics/solver/joint_constraint/joint_constraints_set.rs index 64c1e8337..14365383f 100644 --- a/src/dynamics/solver/joint_constraint/joint_constraints_set.rs +++ b/src/dynamics/solver/joint_constraint/joint_constraints_set.rs @@ -361,6 +361,7 @@ impl JointConstraintsSet { } } + #[profiling::function] pub fn solve( &mut self, solver_vels: &mut [SolverVel], @@ -391,6 +392,7 @@ impl JointConstraintsSet { } } + #[profiling::function] pub fn update( &mut self, params: &IntegrationParameters, diff --git a/src/dynamics/solver/joint_constraint/joint_velocity_constraint.rs b/src/dynamics/solver/joint_constraint/joint_velocity_constraint.rs index 60c42d30a..61a882194 100644 --- a/src/dynamics/solver/joint_constraint/joint_velocity_constraint.rs +++ b/src/dynamics/solver/joint_constraint/joint_velocity_constraint.rs @@ -110,6 +110,7 @@ pub struct JointTwoBodyConstraint { } impl JointTwoBodyConstraint { + #[profiling::function] pub fn solve_generic( &mut self, solver_vel1: &mut SolverVel, diff --git a/src/dynamics/solver/parallel_island_solver.rs b/src/dynamics/solver/parallel_island_solver.rs index 218d2af02..4cfa2d26b 100644 --- a/src/dynamics/solver/parallel_island_solver.rs +++ b/src/dynamics/solver/parallel_island_solver.rs @@ -160,6 +160,7 @@ impl ParallelIslandSolver { } } + #[profiling::function] pub fn init_and_solve<'s>( &'s mut self, scope: &Scope<'s>, diff --git a/src/dynamics/solver/velocity_solver.rs b/src/dynamics/solver/velocity_solver.rs index a4e03b280..bd6ac2cf9 100644 --- a/src/dynamics/solver/velocity_solver.rs +++ b/src/dynamics/solver/velocity_solver.rs @@ -149,6 +149,7 @@ impl VelocitySolver { } } + #[profiling::function] pub fn solve_constraints( &mut self, params: &IntegrationParameters, @@ -221,6 +222,7 @@ impl VelocitySolver { } } + #[profiling::function] pub fn integrate_positions( &mut self, params: &IntegrationParameters, diff --git a/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs b/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs index cd5ac2863..64409c14c 100644 --- a/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs +++ b/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs @@ -254,6 +254,7 @@ impl BroadPhaseMultiSap { /// This will: /// - Remove all the subregion proxies from the larger layer. /// - Pre-insert all the smaller layer's region proxies into this layer. + #[profiling::function] fn finalize_layer_insertion(&mut self, layer_id: u8) { // Remove all the region endpoints from the larger layer. // They will be automatically replaced by the new layer's regions. @@ -289,6 +290,7 @@ impl BroadPhaseMultiSap { /// the `update` function. /// 4. All the regions from the smaller layer are added to that new /// layer. + #[profiling::function] fn ensure_layer_exists(&mut self, new_depth: i8) -> u8 { // Special case: we don't have any layers yet. if self.layers.is_empty() { @@ -361,6 +363,7 @@ impl BroadPhaseMultiSap { } } + #[profiling::function] fn handle_modified_collider( &mut self, prediction_distance: Real, @@ -473,6 +476,7 @@ impl BroadPhaseMultiSap { /// added to its larger layer so we can detect when an object /// in a larger layer may start interacting with objects in a smaller /// layer. + #[profiling::function] fn propagate_created_regions(&mut self) { let mut curr_layer = Some(self.smallest_layer); @@ -502,6 +506,7 @@ impl BroadPhaseMultiSap { } } + #[profiling::function] fn update_layers_and_find_pairs(&mut self, out_events: &mut Vec) { if self.layers.is_empty() { return; @@ -579,6 +584,7 @@ impl BroadPhaseMultiSap { impl BroadPhase for BroadPhaseMultiSap { /// Updates the broad-phase, taking into account the new collider positions. + #[profiling::function] fn update( &mut self, dt: Real, diff --git a/src/geometry/broad_phase_multi_sap/sap_axis.rs b/src/geometry/broad_phase_multi_sap/sap_axis.rs index f1afdeeea..4e61c8bbb 100644 --- a/src/geometry/broad_phase_multi_sap/sap_axis.rs +++ b/src/geometry/broad_phase_multi_sap/sap_axis.rs @@ -36,6 +36,7 @@ impl SAPAxis { self.endpoints.push(SAPEndpoint::end_sentinel()); } + #[profiling::function] pub fn batch_insert( &mut self, dim: usize, @@ -222,6 +223,7 @@ impl SAPAxis { num_subproper_proxies_deleted } + #[profiling::function] pub fn update_endpoints( &mut self, dim: usize, diff --git a/src/geometry/broad_phase_multi_sap/sap_layer.rs b/src/geometry/broad_phase_multi_sap/sap_layer.rs index 262079826..d63ea522a 100644 --- a/src/geometry/broad_phase_multi_sap/sap_layer.rs +++ b/src/geometry/broad_phase_multi_sap/sap_layer.rs @@ -49,6 +49,7 @@ impl SAPLayer { /// Deletes from all the regions of this layer, all the endpoints corresponding /// to subregions. Clears the arrays of subregions indices from all the regions of /// this layer. + #[profiling::function] pub fn unregister_all_subregions(&mut self, proxies: &mut SAPProxies) { for region_id in self.regions.values() { // Extract the region to make the borrow-checker happy. @@ -108,6 +109,7 @@ impl SAPLayer { /// that subregion center. Because the hierarchical grid cells have aligned boundaries /// at each depth, we have the guarantee that a given subregion will only be part of /// one region on its parent "larger" layer. + #[profiling::function] fn register_subregion( &mut self, proxy_id: BroadPhaseProxyIndex, @@ -145,6 +147,7 @@ impl SAPLayer { } } + #[profiling::function] fn unregister_subregion( &mut self, proxy_id: BroadPhaseProxyIndex, @@ -219,6 +222,7 @@ impl SAPLayer { } } + #[profiling::function] pub fn preupdate_collider( &mut self, proxy_id: u32, @@ -273,6 +277,7 @@ impl SAPLayer { } } + #[profiling::function] pub fn predelete_proxy(&mut self, proxies: &mut SAPProxies, proxy_index: BroadPhaseProxyIndex) { // Discretize the Aabb to find the regions that need to be invalidated. let proxy_aabb = &mut proxies[proxy_index].aabb; diff --git a/src/geometry/broad_phase_multi_sap/sap_region.rs b/src/geometry/broad_phase_multi_sap/sap_region.rs index f54b4aeb5..7c876c514 100644 --- a/src/geometry/broad_phase_multi_sap/sap_region.rs +++ b/src/geometry/broad_phase_multi_sap/sap_region.rs @@ -214,6 +214,7 @@ impl SAPRegion { } } + #[profiling::function] pub fn update( &mut self, proxies: &SAPProxies, diff --git a/src/geometry/contact_pair.rs b/src/geometry/contact_pair.rs index 3d4e95523..3f569b200 100644 --- a/src/geometry/contact_pair.rs +++ b/src/geometry/contact_pair.rs @@ -186,6 +186,7 @@ impl ContactPair { /// /// Returns a reference to the contact, as well as the contact manifold /// it is part of. + #[profiling::function] pub fn find_deepest_contact(&self) -> Option<(&ContactManifold, &Contact)> { let mut deepest = None; diff --git a/src/geometry/interaction_graph.rs b/src/geometry/interaction_graph.rs index de2948b74..4fb5054aa 100644 --- a/src/geometry/interaction_graph.rs +++ b/src/geometry/interaction_graph.rs @@ -96,6 +96,7 @@ impl InteractionGraph { } /// The interaction between the two collision objects identified by their graph index. + #[profiling::function] pub fn interaction_pair( &self, id1: ColliderGraphIndex, @@ -111,6 +112,7 @@ impl InteractionGraph { } /// The interaction between the two collision objects identified by their graph index. + #[profiling::function] pub fn interaction_pair_mut( &mut self, id1: ColliderGraphIndex, diff --git a/src/geometry/mesh_converter.rs b/src/geometry/mesh_converter.rs index a4c886149..cfa1391c8 100644 --- a/src/geometry/mesh_converter.rs +++ b/src/geometry/mesh_converter.rs @@ -53,6 +53,7 @@ pub enum MeshConverter { impl MeshConverter { /// Applies the conversion rule described by this [`MeshConverter`] to build a shape from /// the given vertex and index buffers. + #[profiling::function] pub fn convert( &self, vertices: Vec>, diff --git a/src/geometry/narrow_phase.rs b/src/geometry/narrow_phase.rs index e979a2f72..aa844ad3c 100644 --- a/src/geometry/narrow_phase.rs +++ b/src/geometry/narrow_phase.rs @@ -268,6 +268,7 @@ impl NarrowPhase { // } /// Maintain the narrow-phase internal state by taking collider removal into account. + #[profiling::function] pub fn handle_user_changes( &mut self, mut islands: Option<&mut IslandManager>, @@ -321,6 +322,7 @@ impl NarrowPhase { ); } + #[profiling::function] pub(crate) fn remove_collider( &mut self, intersection_graph_id: ColliderGraphIndex, @@ -412,6 +414,7 @@ impl NarrowPhase { } } + #[profiling::function] pub(crate) fn handle_user_changes_on_colliders( &mut self, mut islands: Option<&mut IslandManager>, @@ -513,6 +516,7 @@ impl NarrowPhase { } } + #[profiling::function] fn remove_pair( &mut self, islands: Option<&mut IslandManager>, @@ -584,6 +588,7 @@ impl NarrowPhase { } } + #[profiling::function] fn add_pair(&mut self, colliders: &ColliderSet, pair: &ColliderPair) { if let (Some(co1), Some(co2)) = (colliders.get(pair.collider1), colliders.get(pair.collider2)) @@ -660,6 +665,7 @@ impl NarrowPhase { } } + #[profiling::function] pub(crate) fn register_pairs( &mut self, mut islands: Option<&mut IslandManager>, @@ -687,6 +693,7 @@ impl NarrowPhase { } } + #[profiling::function] pub(crate) fn compute_intersections( &mut self, bodies: &RigidBodySet, @@ -785,6 +792,7 @@ impl NarrowPhase { }); } + #[profiling::function] pub(crate) fn compute_contacts( &mut self, prediction_distance: Real, diff --git a/src/pipeline/debug_render_pipeline/debug_render_pipeline.rs b/src/pipeline/debug_render_pipeline/debug_render_pipeline.rs index f2e23cd3d..4d1a21eb5 100644 --- a/src/pipeline/debug_render_pipeline/debug_render_pipeline.rs +++ b/src/pipeline/debug_render_pipeline/debug_render_pipeline.rs @@ -85,6 +85,7 @@ impl DebugRenderPipeline { } /// Render the scene. + #[profiling::function] pub fn render( &mut self, backend: &mut impl DebugRenderBackend, @@ -101,6 +102,7 @@ impl DebugRenderPipeline { } /// Render contact. + #[profiling::function] pub fn render_contacts( &mut self, backend: &mut impl DebugRenderBackend, @@ -167,6 +169,7 @@ impl DebugRenderPipeline { } /// Render only the joints from the scene. + #[profiling::function] pub fn render_joints( &mut self, backend: &mut impl DebugRenderBackend, @@ -249,6 +252,7 @@ impl DebugRenderPipeline { } /// Render only the rigid-bodies from the scene. + #[profiling::function] pub fn render_rigid_bodies( &mut self, backend: &mut impl DebugRenderBackend, @@ -288,6 +292,7 @@ impl DebugRenderPipeline { } /// Render only the colliders from the scene. + #[profiling::function] pub fn render_colliders( &mut self, backend: &mut impl DebugRenderBackend, @@ -351,6 +356,7 @@ impl DebugRenderPipeline { } #[cfg(feature = "dim2")] + #[profiling::function] fn render_shape( &mut self, object: DebugRenderObject, @@ -458,6 +464,7 @@ impl DebugRenderPipeline { } #[cfg(feature = "dim3")] + #[profiling::function] fn render_shape( &mut self, object: DebugRenderObject, diff --git a/src/pipeline/query_pipeline/mod.rs b/src/pipeline/query_pipeline/mod.rs index cd4ee4956..6d41f4f31 100644 --- a/src/pipeline/query_pipeline/mod.rs +++ b/src/pipeline/query_pipeline/mod.rs @@ -312,6 +312,7 @@ impl QueryPipeline { /// Update the query pipeline incrementally, avoiding a complete rebuild of its /// internal data-structure. + #[profiling::function] pub fn update_incremental( &mut self, colliders: &ColliderSet, @@ -353,6 +354,7 @@ impl QueryPipeline { /// volume generator. /// /// See [`generators`] for available generators. + #[profiling::function] pub fn update_with_generator(&mut self, mode: impl QbvhDataGenerator) { self.qbvh.clear_and_rebuild(mode, self.dilation_factor); } @@ -368,6 +370,7 @@ impl QueryPipeline { /// it starts inside of a shape. If this `false` then the ray will hit the shape's boundary /// even if its starts inside of it. /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. + #[profiling::function] pub fn cast_ray( &self, bodies: &RigidBodySet, @@ -395,6 +398,7 @@ impl QueryPipeline { /// it starts inside of a shape. If this `false` then the ray will hit the shape's boundary /// even if its starts inside of it. /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. + #[profiling::function] pub fn cast_ray_and_get_normal( &self, bodies: &RigidBodySet, @@ -429,6 +433,7 @@ impl QueryPipeline { /// * `callback`: function executed on each collider for which a ray intersection has been found. /// There is no guarantees on the order the results will be yielded. If this callback returns `false`, /// this method will exit early, ignore any further raycast. + #[profiling::function] pub fn intersections_with_ray<'a>( &self, bodies: &'a RigidBodySet, @@ -465,6 +470,7 @@ impl QueryPipeline { /// * `shape_pos` - The position of the shape used for the intersection test. /// * `shape` - The shape used for the intersection test. /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. + #[profiling::function] pub fn intersection_with_shape( &self, bodies: &RigidBodySet, @@ -501,6 +507,7 @@ impl QueryPipeline { /// (if the point is located inside of an hollow shape, it is projected on the shape's /// boundary). /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. + #[profiling::function] pub fn project_point( &self, bodies: &RigidBodySet, @@ -526,6 +533,7 @@ impl QueryPipeline { /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. /// * `callback` - A function called with each collider with a shape /// containing the `point`. + #[profiling::function] pub fn intersections_with_point( &self, bodies: &RigidBodySet, @@ -562,6 +570,7 @@ impl QueryPipeline { /// (if the point is located inside of an hollow shape, it is projected on the shape's /// boundary). /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. + #[profiling::function] pub fn project_point_and_get_feature( &self, bodies: &RigidBodySet, @@ -578,6 +587,7 @@ impl QueryPipeline { } /// Finds all handles of all the colliders with an [`Aabb`] intersecting the given [`Aabb`]. + #[profiling::function] pub fn colliders_with_aabb_intersecting_aabb( &self, aabb: &Aabb, @@ -604,6 +614,7 @@ impl QueryPipeline { /// the shape is penetrating another shape at its starting point **and** its trajectory is such /// that it’s on a path to exit that penetration state. /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. + #[profiling::function] pub fn cast_shape( &self, bodies: &RigidBodySet, @@ -645,6 +656,7 @@ impl QueryPipeline { /// that normal) then the nonlinear shape-casting will attempt to find another impact, /// at a time `> start_time` that could result in tunnelling. /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. + #[profiling::function] pub fn nonlinear_cast_shape( &self, bodies: &RigidBodySet, @@ -680,6 +692,7 @@ impl QueryPipeline { /// * `shape` - The shape to test. /// * `filter`: set of rules used to determine which collider is taken into account by this scene query. /// * `callback` - A function called with the handles of each collider intersecting the `shape`. + #[profiling::function] pub fn intersections_with_shape( &self, bodies: &RigidBodySet, diff --git a/src_testbed/box2d_backend.rs b/src_testbed/box2d_backend.rs index b9bc97ed9..bd6aa1371 100644 --- a/src_testbed/box2d_backend.rs +++ b/src_testbed/box2d_backend.rs @@ -28,6 +28,7 @@ pub struct Box2dWorld { } impl Box2dWorld { + #[profiling::function] pub fn from_rapier( gravity: Vector2, bodies: &RigidBodySet, @@ -221,6 +222,7 @@ impl Box2dWorld { } } + #[profiling::function] pub fn step(&mut self, counters: &mut Counters, params: &IntegrationParameters) { counters.step_started(); self.world @@ -228,6 +230,7 @@ impl Box2dWorld { counters.step_completed(); } + #[profiling::function] pub fn sync(&self, bodies: &mut RigidBodySet, colliders: &mut ColliderSet) { for (handle, body) in bodies.iter_mut() { if let Some(pb2_handle) = self.rapier2box2d.get(&handle) { diff --git a/src_testbed/harness/mod.rs b/src_testbed/harness/mod.rs index 9c414726d..734625b4c 100644 --- a/src_testbed/harness/mod.rs +++ b/src_testbed/harness/mod.rs @@ -206,6 +206,7 @@ impl Harness { self.step_with_graphics(None); } + #[profiling::function] pub fn step_with_graphics(&mut self, mut graphics: Option<&mut TestbedGraphics>) { #[cfg(feature = "parallel")] { diff --git a/src_testbed/physics/mod.rs b/src_testbed/physics/mod.rs index 3c69f6e8d..b08d7f57d 100644 --- a/src_testbed/physics/mod.rs +++ b/src_testbed/physics/mod.rs @@ -54,6 +54,7 @@ impl PhysicsSnapshot { }) } + #[profiling::function] pub fn restore(&self) -> bincode::Result { Ok(DeserializedPhysicsSnapshot { timestep_id: self.timestep_id, diff --git a/src_testbed/physx_backend.rs b/src_testbed/physx_backend.rs index 71f8f9dc0..ae7761513 100644 --- a/src_testbed/physx_backend.rs +++ b/src_testbed/physx_backend.rs @@ -147,6 +147,7 @@ impl Drop for PhysxWorld { } impl PhysxWorld { + #[profiling::function] pub fn from_rapier( gravity: Vector3, integration_parameters: &IntegrationParameters, diff --git a/src_testbed/testbed.rs b/src_testbed/testbed.rs index 7b2f0fdcd..660267eb0 100644 --- a/src_testbed/testbed.rs +++ b/src_testbed/testbed.rs @@ -1552,6 +1552,7 @@ fn update_testbed( if state.running == RunMode::Step { state.running = RunMode::Stop; } + profiling::finish_frame!(); } fn clear( From 3bd798f68bd90bd3e6210ffc52b6f93004b7bcea Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Tue, 1 Oct 2024 12:18:35 +0200 Subject: [PATCH 2/9] add optional puffin viewer within rapier testbed, enabled on examples --- crates/rapier_testbed2d-f64/Cargo.toml | 4 +++- crates/rapier_testbed2d/Cargo.toml | 4 +++- crates/rapier_testbed3d-f64/Cargo.toml | 4 +++- crates/rapier_testbed3d/Cargo.toml | 4 +++- examples2d/Cargo.toml | 1 + examples3d/Cargo.toml | 2 +- src_testbed/testbed.rs | 3 +++ src_testbed/ui.rs | 5 +++++ 8 files changed, 22 insertions(+), 5 deletions(-) diff --git a/crates/rapier_testbed2d-f64/Cargo.toml b/crates/rapier_testbed2d-f64/Cargo.toml index 84a0473ef..d0cf62eb6 100644 --- a/crates/rapier_testbed2d-f64/Cargo.toml +++ b/crates/rapier_testbed2d-f64/Cargo.toml @@ -34,9 +34,10 @@ default = ["dim2"] dim2 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["wrapped2d"] +profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] [package.metadata.docs.rs] -features = ["parallel", "other-backends"] +features = ["parallel", "profiling"] [dependencies] nalgebra = { version = "0.33", features = ["rand", "glam027"] } @@ -56,6 +57,7 @@ bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" profiling = "1.0" +puffin_egui = { version = "0.29", optional = true } # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/crates/rapier_testbed2d/Cargo.toml b/crates/rapier_testbed2d/Cargo.toml index ac7a0b554..5ffa3afc3 100644 --- a/crates/rapier_testbed2d/Cargo.toml +++ b/crates/rapier_testbed2d/Cargo.toml @@ -34,9 +34,10 @@ default = ["dim2"] dim2 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["wrapped2d"] +profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] [package.metadata.docs.rs] -features = ["parallel", "other-backends"] +features = ["parallel", "other-backends", "profiling"] [dependencies] nalgebra = { version = "0.33", features = ["rand", "glam027"] } @@ -56,6 +57,7 @@ bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" profiling = "1.0" +puffin_egui = { version = "0.29", optional = true } # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/crates/rapier_testbed3d-f64/Cargo.toml b/crates/rapier_testbed3d-f64/Cargo.toml index d16989b2a..89734cfa2 100644 --- a/crates/rapier_testbed3d-f64/Cargo.toml +++ b/crates/rapier_testbed3d-f64/Cargo.toml @@ -36,9 +36,10 @@ rust.unexpected_cfgs = { level = "warn", check-cfg = [ default = ["dim3"] dim3 = [] parallel = ["rapier/parallel", "num_cpus"] +profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] [package.metadata.docs.rs] -features = ["parallel"] +features = ["parallel", "profiling"] [dependencies] nalgebra = { version = "0.33", features = ["rand", "glam027"] } @@ -58,6 +59,7 @@ bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" profiling = "1.0" +puffin_egui = { version = "0.29", optional = true } # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/crates/rapier_testbed3d/Cargo.toml b/crates/rapier_testbed3d/Cargo.toml index e213b073b..0d0b28e8d 100644 --- a/crates/rapier_testbed3d/Cargo.toml +++ b/crates/rapier_testbed3d/Cargo.toml @@ -34,9 +34,10 @@ default = ["dim3"] dim3 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["physx", "physx-sys", "glam"] +profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] [package.metadata.docs.rs] -features = ["parallel", "other-backends"] +features = ["parallel", "other-backends", "profiling"] [dependencies] nalgebra = { version = "0.33", features = ["rand", "glam027"] } @@ -59,6 +60,7 @@ bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" profiling = "1.0" +puffin_egui = { version = "0.29", optional = true } # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/examples2d/Cargo.toml b/examples2d/Cargo.toml index 771d9d51e..dc214b3bf 100644 --- a/examples2d/Cargo.toml +++ b/examples2d/Cargo.toml @@ -20,6 +20,7 @@ usvg = "0.14" [dependencies.rapier_testbed2d] path = "../crates/rapier_testbed2d" +features = ["profiling"] [dependencies.rapier2d] path = "../crates/rapier2d" diff --git a/examples3d/Cargo.toml b/examples3d/Cargo.toml index 4f09fad43..96ce0e074 100644 --- a/examples3d/Cargo.toml +++ b/examples3d/Cargo.toml @@ -23,6 +23,7 @@ bincode = "1" [dependencies.rapier_testbed3d] path = "../crates/rapier_testbed3d" +features = ["profiling"] [dependencies.rapier3d] path = "../crates/rapier3d" @@ -42,4 +43,3 @@ path = "./harness_capsules3.rs" #[lib] #crate-type = ["cdylib", "rlib"] #path = "./all_examples3_wasm.rs" - diff --git a/src_testbed/testbed.rs b/src_testbed/testbed.rs index 660267eb0..3873934eb 100644 --- a/src_testbed/testbed.rs +++ b/src_testbed/testbed.rs @@ -249,6 +249,9 @@ impl TestbedApp { } pub fn run_with_init(mut self, mut init: impl FnMut(&mut App)) { + #[cfg(feature = "profiling")] + puffin_egui::puffin::set_scopes_on(true); + let mut args = env::args(); let mut benchmark_mode = false; diff --git a/src_testbed/ui.rs b/src_testbed/ui.rs index b27ea7a6e..762bf1905 100644 --- a/src_testbed/ui.rs +++ b/src_testbed/ui.rs @@ -89,6 +89,11 @@ pub fn update_ui( profiling_ui(ui, &harness.physics.pipeline.counters); }); }); + #[cfg(feature = "profiling")] + ui.collapsing( + "Profiling", |ui| { + puffin_egui::profiler_ui(ui); + }); ui.collapsing("Serialization infos", |ui| { ui.horizontal_wrapped(|ui| { ui.label(serialization_string( From 28daad303557a14d77d77f1f9a9eb78cd8ee9314 Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Mon, 4 Nov 2024 10:24:21 +0100 Subject: [PATCH 3/9] fix some compilation --- crates/rapier_testbed2d-f64/Cargo.toml | 2 +- crates/rapier_testbed3d-f64/Cargo.toml | 2 +- examples3d-f64/all_examples3-f64.rs | 1 + src_testbed/graphics.rs | 2 +- src_testbed/objects/node.rs | 4 ++-- 5 files changed, 6 insertions(+), 5 deletions(-) diff --git a/crates/rapier_testbed2d-f64/Cargo.toml b/crates/rapier_testbed2d-f64/Cargo.toml index d0cf62eb6..8546d8643 100644 --- a/crates/rapier_testbed2d-f64/Cargo.toml +++ b/crates/rapier_testbed2d-f64/Cargo.toml @@ -20,7 +20,7 @@ edition = "2021" maintenance = { status = "actively-developed" } [lib] -name = "rapier_testbed2d" +name = "rapier_testbed2d_f64" path = "../../src_testbed/lib.rs" required-features = ["dim2"] diff --git a/crates/rapier_testbed3d-f64/Cargo.toml b/crates/rapier_testbed3d-f64/Cargo.toml index 89734cfa2..537263563 100644 --- a/crates/rapier_testbed3d-f64/Cargo.toml +++ b/crates/rapier_testbed3d-f64/Cargo.toml @@ -20,7 +20,7 @@ edition = "2021" maintenance = { status = "actively-developed" } [lib] -name = "rapier_testbed3d" +name = "rapier_testbed3d_f64" path = "../../src_testbed/lib.rs" required-features = ["dim3"] diff --git a/examples3d-f64/all_examples3-f64.rs b/examples3d-f64/all_examples3-f64.rs index f2d5ec481..3bece18c4 100644 --- a/examples3d-f64/all_examples3-f64.rs +++ b/examples3d-f64/all_examples3-f64.rs @@ -3,6 +3,7 @@ #[cfg(target_arch = "wasm32")] use wasm_bindgen::prelude::*; extern crate rapier3d_f64 as rapier3d; +extern crate rapier_testbed3d_f64 as rapier_testbed3d; use inflector::Inflector; diff --git a/src_testbed/graphics.rs b/src_testbed/graphics.rs index 226be4d9a..c09c97148 100644 --- a/src_testbed/graphics.rs +++ b/src_testbed/graphics.rs @@ -18,7 +18,7 @@ use rand_pcg::Pcg32; use std::collections::HashMap; #[cfg(feature = "dim2")] -pub type BevyMaterial = ColorMaterial; +pub type BevyMaterial = bevy_sprite::ColorMaterial; #[cfg(feature = "dim3")] pub type BevyMaterial = StandardMaterial; diff --git a/src_testbed/objects/node.rs b/src_testbed/objects/node.rs index a5f7d5106..5926eb7b8 100644 --- a/src_testbed/objects/node.rs +++ b/src_testbed/objects/node.rs @@ -43,7 +43,7 @@ impl EntityWithGraphics { } #[cfg(feature = "dim2")] - let selection_material = ColorMaterial { + let selection_material = bevy_sprite::ColorMaterial { color: Color::from(Srgba::rgb(1.0, 0.0, 0.0)), texture: None, }; @@ -109,7 +109,7 @@ impl EntityWithGraphics { } #[cfg(feature = "dim2")] - let material = ColorMaterial { + let material = bevy_sprite::ColorMaterial { color: bevy_color, texture: None, }; From 843a711b021a5e9e313bfecacfbf9f10fdf55b1e Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Mon, 4 Nov 2024 10:31:40 +0100 Subject: [PATCH 4/9] pr feedback: remove/ignore vscode files --- .gitignore | 3 +- .vscode/launch.json | 326 ------------------------------------------ .vscode/settings.json | 6 - .vscode/tasks.json | 288 ------------------------------------- 4 files changed, 2 insertions(+), 621 deletions(-) delete mode 100644 .vscode/launch.json delete mode 100644 .vscode/settings.json delete mode 100644 .vscode/tasks.json diff --git a/.gitignore b/.gitignore index db22dde05..27351d5f7 100644 --- a/.gitignore +++ b/.gitignore @@ -6,4 +6,5 @@ target .DS_Store package-lock.json **/*.csv -.history \ No newline at end of file +.history +.vscode/ \ No newline at end of file diff --git a/.vscode/launch.json b/.vscode/launch.json deleted file mode 100644 index 3f328c530..000000000 --- a/.vscode/launch.json +++ /dev/null @@ -1,326 +0,0 @@ -{ - // Use IntelliSense to learn about possible attributes. - // Hover to view descriptions of existing attributes. - // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 - "version": "0.2.0", - "configurations": [ - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in library 'rapier2d'", - "cargo": { - "args": [ - "test", - "--no-run", - "--lib", - "--package=rapier2d" - ], - "filter": { - "name": "rapier2d", - "kind": "lib" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in library 'rapier2d_f64'", - "cargo": { - "args": [ - "test", - "--no-run", - "--lib", - "--package=rapier2d-f64" - ], - "filter": { - "name": "rapier2d_f64", - "kind": "lib" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in library 'rapier_testbed2d'", - "cargo": { - "args": [ - "test", - "--no-run", - "--lib", - "--package=rapier_testbed2d" - ], - "filter": { - "name": "rapier_testbed2d", - "kind": "lib" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug executable 'all_examples2'", - "cargo": { - "args": [ - "build", - "--bin=all_examples2", - "--package=rapier-examples-2d" - ], - "filter": { - "name": "all_examples2", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in executable 'all_examples2'", - "cargo": { - "args": [ - "test", - "--no-run", - "--bin=all_examples2", - "--package=rapier-examples-2d" - ], - "filter": { - "name": "all_examples2", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug executable 'all_benchmarks2'", - "cargo": { - "args": [ - "build", - "--bin=all_benchmarks2", - "--package=rapier-benchmarks-2d" - ], - "filter": { - "name": "all_benchmarks2", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in executable 'all_benchmarks2'", - "cargo": { - "args": [ - "test", - "--no-run", - "--bin=all_benchmarks2", - "--package=rapier-benchmarks-2d" - ], - "filter": { - "name": "all_benchmarks2", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in library 'rapier3d'", - "cargo": { - "args": [ - "test", - "--no-run", - "--lib", - "--package=rapier3d" - ], - "filter": { - "name": "rapier3d", - "kind": "lib" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in library 'rapier3d_f64'", - "cargo": { - "args": [ - "test", - "--no-run", - "--lib", - "--package=rapier3d-f64" - ], - "filter": { - "name": "rapier3d_f64", - "kind": "lib" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in library 'rapier_testbed3d'", - "cargo": { - "args": [ - "test", - "--no-run", - "--lib", - "--package=rapier_testbed3d" - ], - "filter": { - "name": "rapier_testbed3d", - "kind": "lib" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug executable 'all_examples3'", - "cargo": { - "args": [ - "build", - "--bin=all_examples3", - "--package=rapier-examples-3d" - ], - "filter": { - "name": "all_examples3", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in executable 'all_examples3'", - "cargo": { - "args": [ - "test", - "--no-run", - "--bin=all_examples3", - "--package=rapier-examples-3d" - ], - "filter": { - "name": "all_examples3", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Run 'all_examples3'", - "cargo": { - "args": [ - "run", - "--release", - "--bin=all_examples3", - "--package=rapier-examples-3d" - ], - "filter": { - "name": "all_examples3", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug executable 'harness_capsules3'", - "cargo": { - "args": [ - "build", - "--bin=harness_capsules3", - "--package=rapier-examples-3d" - ], - "filter": { - "name": "harness_capsules3", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in executable 'harness_capsules3'", - "cargo": { - "args": [ - "test", - "--no-run", - "--bin=harness_capsules3", - "--package=rapier-examples-3d" - ], - "filter": { - "name": "harness_capsules3", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug executable 'all_benchmarks3'", - "cargo": { - "args": [ - "build", - "--bin=all_benchmarks3", - "--package=rapier-benchmarks-3d" - ], - "filter": { - "name": "all_benchmarks3", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - }, - { - "type": "lldb", - "request": "launch", - "name": "Debug unit tests in executable 'all_benchmarks3'", - "cargo": { - "args": [ - "test", - "--no-run", - "--bin=all_benchmarks3", - "--package=rapier-benchmarks-3d" - ], - "filter": { - "name": "all_benchmarks3", - "kind": "bin" - } - }, - "args": [], - "cwd": "${workspaceFolder}" - } - ] -} \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json deleted file mode 100644 index 22f0f9768..000000000 --- a/.vscode/settings.json +++ /dev/null @@ -1,6 +0,0 @@ -{ - "rust-analyzer.cargo.features": [ - "simd-stable", - "dim3" - ] -} \ No newline at end of file diff --git a/.vscode/tasks.json b/.vscode/tasks.json deleted file mode 100644 index d103f9710..000000000 --- a/.vscode/tasks.json +++ /dev/null @@ -1,288 +0,0 @@ -{ - // See https://go.microsoft.com/fwlink/?LinkId=733558 - // for the documentation about the tasks.json format - "version": "2.0.0", - "options": { - "env": { - "RUST_BACKTRACE": "1" - } - }, - "tasks": [ - { - "label": "πŸš€ run 3d", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples3", - "--release", - "--features", - "other-backends", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸš€ run 3d βˆ’ πŸ’Œ deterministic", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples3", - "--release", - "--features", - "enhanced-determinism", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸš€ run 3d βˆ’ 🌈 simd", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples3", - "--release", - "--features", - "simd-stable,other-backends", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸš€ run 3d βˆ’ 🌈 simd πŸͺ’ parallel", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples3", - "--release", - "--features", - "simd-stable,other-backends,parallel", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸš€ run 2d", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples2", - "--release", - "--features", - "other-backends", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸš€ run 2d βˆ’ 🌈 simd", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples2", - "--release", - "--features", - "simd-stable,other-backends", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸš€ run 2d βˆ’ 🌈 simd πŸͺ’ parallel", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples2", - "--release", - "--features", - "simd-stable,other-backends,parallel", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "⏱ bench 3d", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_benchmarks3", - "--release", - "--features", - "other-backends", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "⏱ bench 3d βˆ’ 🌈 simd", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_benchmarks3", - "--release", - "--features", - "simd-stable,other-backends", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "⏱ bench 3d βˆ’ 🌈 simd πŸͺ’ parallel", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_benchmarks3", - "--release", - "--features", - "simd-stable,other-backends,parallel", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "⏱ bench 2d", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_benchmarks2", - "--release", - "--features", - "other-backends", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "⏱ bench 2d βˆ’ 🌈 simd", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_benchmarks2", - "--release", - "--features", - "simd-stable,other-backends", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "⏱ bench 2d βˆ’ 🌈 simd πŸͺ’ parallel", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_benchmarks2", - "--release", - "--features", - "simd-stable,other-backends,parallel", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸͺ² debug 3d", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples3", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸͺ² debug 3d βˆ’ 🌈 simd", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples3", - "--features", - "simd-stable", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸͺ² debug 3d βˆ’ 🌈 simd πŸͺ’ parallel", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples3", - "--features", - "simd-stable,parallel", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸͺ² debug 3d βˆ’ πŸ’Œ deterministic", - "type": "shell", - "command": "cargo", - "args": [ - "run", - "--bin", - "all_examples3", - "--features", - "enhanced-determinism", - "--", - "--pause" - ], - "group": "build" - }, - { - "label": "πŸ›  tests", - "type": "shell", - "command": "cargo", - "args": [ - "test" - ], - "group": "build" - }, - ] -] -} \ No newline at end of file From 711a0bb87e9e1b936ccaa150f869f8a582239133 Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Mon, 4 Nov 2024 17:28:06 +0100 Subject: [PATCH 5/9] less profiled functions + default highlight for profiling --- Cargo.toml | 4 +++ crates/rapier3d-urdf/Cargo.toml | 1 - crates/rapier_testbed3d-f64/Cargo.toml | 2 +- .../multibody_joint/multibody_joint_set.rs | 1 - .../broad_phase_multi_sap.rs | 1 - .../broad_phase_multi_sap/sap_axis.rs | 1 - .../broad_phase_multi_sap/sap_layer.rs | 1 - src/geometry/narrow_phase.rs | 1 - src_testbed/testbed.rs | 11 +++++-- src_testbed/ui.rs | 33 ++++++++++++++++--- 10 files changed, 42 insertions(+), 14 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index 479779858..39564da53 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -37,6 +37,10 @@ resolver = "2" #parry3d = { git = "https://github.com/dimforge/parry", branch = "master" } #parry2d-f64 = { git = "https://github.com/dimforge/parry", branch = "master" } #parry3d-f64 = { git = "https://github.com/dimforge/parry", branch = "master" } +# puffin_egui = { version = "0.29", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } +puffin_egui = { optional = true, path = "../puffin/puffin_egui" } +puffin = { optional = true, path = "../puffin/puffin" } + [profile.release] #debug = true diff --git a/crates/rapier3d-urdf/Cargo.toml b/crates/rapier3d-urdf/Cargo.toml index 24cb7bc38..59df04684 100644 --- a/crates/rapier3d-urdf/Cargo.toml +++ b/crates/rapier3d-urdf/Cargo.toml @@ -27,7 +27,6 @@ anyhow = "1" bitflags = "2" # NOTE: we are not using the (more recent) urdf-rs crate because of https://github.com/openrr/urdf-rs/issues/94 xurdf = "0.2" -profiling = "1.0" rapier3d = { version = "0.22", path = "../rapier3d" } rapier3d-stl = { version = "0.3.0", path = "../rapier3d-stl", optional = true } diff --git a/crates/rapier_testbed3d-f64/Cargo.toml b/crates/rapier_testbed3d-f64/Cargo.toml index 537263563..9d645c72c 100644 --- a/crates/rapier_testbed3d-f64/Cargo.toml +++ b/crates/rapier_testbed3d-f64/Cargo.toml @@ -59,7 +59,7 @@ bevy_core_pipeline = "0.14" bevy_pbr = "0.14" bevy_sprite = "0.14" profiling = "1.0" -puffin_egui = { version = "0.29", optional = true } +puffin_egui = { version = "0.29", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } # Dependencies for native only. [target.'cfg(not(target_arch = "wasm32"))'.dependencies] diff --git a/src/dynamics/joint/multibody_joint/multibody_joint_set.rs b/src/dynamics/joint/multibody_joint/multibody_joint_set.rs index ac00874ac..d31572913 100644 --- a/src/dynamics/joint/multibody_joint/multibody_joint_set.rs +++ b/src/dynamics/joint/multibody_joint/multibody_joint_set.rs @@ -433,7 +433,6 @@ impl MultibodyJointSet { /// Iterate through the handles of all the rigid-bodies attached to this rigid-body /// by a multibody_joint. - #[profiling::function] pub fn attached_bodies( &self, body: RigidBodyHandle, diff --git a/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs b/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs index 64409c14c..197ebaf64 100644 --- a/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs +++ b/src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs @@ -363,7 +363,6 @@ impl BroadPhaseMultiSap { } } - #[profiling::function] fn handle_modified_collider( &mut self, prediction_distance: Real, diff --git a/src/geometry/broad_phase_multi_sap/sap_axis.rs b/src/geometry/broad_phase_multi_sap/sap_axis.rs index 4e61c8bbb..60dddd6bc 100644 --- a/src/geometry/broad_phase_multi_sap/sap_axis.rs +++ b/src/geometry/broad_phase_multi_sap/sap_axis.rs @@ -223,7 +223,6 @@ impl SAPAxis { num_subproper_proxies_deleted } - #[profiling::function] pub fn update_endpoints( &mut self, dim: usize, diff --git a/src/geometry/broad_phase_multi_sap/sap_layer.rs b/src/geometry/broad_phase_multi_sap/sap_layer.rs index d63ea522a..cadb5f162 100644 --- a/src/geometry/broad_phase_multi_sap/sap_layer.rs +++ b/src/geometry/broad_phase_multi_sap/sap_layer.rs @@ -222,7 +222,6 @@ impl SAPLayer { } } - #[profiling::function] pub fn preupdate_collider( &mut self, proxy_id: u32, diff --git a/src/geometry/narrow_phase.rs b/src/geometry/narrow_phase.rs index aa844ad3c..908f83ead 100644 --- a/src/geometry/narrow_phase.rs +++ b/src/geometry/narrow_phase.rs @@ -665,7 +665,6 @@ impl NarrowPhase { } } - #[profiling::function] pub(crate) fn register_pairs( &mut self, mut islands: Option<&mut IslandManager>, diff --git a/src_testbed/testbed.rs b/src_testbed/testbed.rs index 3873934eb..fa7f731d4 100644 --- a/src_testbed/testbed.rs +++ b/src_testbed/testbed.rs @@ -888,6 +888,10 @@ impl<'a, 'b, 'c, 'd, 'e, 'f> Testbed<'a, 'b, 'c, 'd, 'e, 'f> { } fn handle_common_events(&mut self, events: &ButtonInput) { + // C can be used to write within profiling filter. + if events.pressed(KeyCode::ControlLeft) || events.pressed(KeyCode::ControlRight) { + return; + } for key in events.get_just_released() { match *key { KeyCode::KeyT => { @@ -1187,6 +1191,8 @@ fn update_testbed( ), keys: Res>, ) { + profiling::finish_frame!(); + let meshes = &mut *meshes; let materials = &mut *materials; @@ -1213,7 +1219,9 @@ fn update_testbed( plugins: &mut plugins, }; - testbed.handle_common_events(&keys); + if !ui_context.ctx_mut().wants_keyboard_input() { + testbed.handle_common_events(&keys); + } testbed.update_character_controller(&keys); #[cfg(feature = "dim3")] { @@ -1555,7 +1563,6 @@ fn update_testbed( if state.running == RunMode::Step { state.running = RunMode::Stop; } - profiling::finish_frame!(); } fn clear( diff --git a/src_testbed/ui.rs b/src_testbed/ui.rs index 762bf1905..3b22cd476 100644 --- a/src_testbed/ui.rs +++ b/src_testbed/ui.rs @@ -2,6 +2,7 @@ use rapier::control::CharacterLength; use rapier::counters::Counters; use rapier::math::Real; use std::num::NonZeroUsize; +use std::sync::Once; use crate::debug_render::DebugRenderPipelineResource; use crate::harness::Harness; @@ -21,6 +22,33 @@ pub fn update_ui( harness: &mut Harness, debug_render: &mut DebugRenderPipelineResource, ) { + #[cfg(feature = "profiling")] + { + let window = egui::Window::new("Profiling"); + let window = window.default_open(false); + static START: Once = Once::new(); + + fn set_default_rapier_filter() { + let mut profile_ui = puffin_egui::PROFILE_UI.lock(); + profile_ui + .profiler_ui + .flamegraph_options + .scope_name_filter + .set_filter("Harness::step_with_graphics".to_string()); + } + START.call_once(|| { + set_default_rapier_filter(); + }); + + window.show(ui_context.ctx_mut(), |ui| { + //profile_ui.profiler_ui.flamegraph_options. + if ui.button("πŸ” Rapier filter").clicked() { + set_default_rapier_filter(); + } + puffin_egui::profiler_ui(ui); + }); + } + egui::Window::new("Parameters").show(ui_context.ctx_mut(), |ui| { if state.backend_names.len() > 1 && !state.example_names.is_empty() { let mut changed = false; @@ -89,11 +117,6 @@ pub fn update_ui( profiling_ui(ui, &harness.physics.pipeline.counters); }); }); - #[cfg(feature = "profiling")] - ui.collapsing( - "Profiling", |ui| { - puffin_egui::profiler_ui(ui); - }); ui.collapsing("Serialization infos", |ui| { ui.horizontal_wrapped(|ui| { ui.label(serialization_string( From 8cb75113e05da279f751faf1720063c0e8ffef52 Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Fri, 15 Nov 2024 12:41:25 +0100 Subject: [PATCH 6/9] use git rather than local path for patch dependencies --- Cargo.toml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index 39564da53..f81e94e2a 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -37,9 +37,10 @@ resolver = "2" #parry3d = { git = "https://github.com/dimforge/parry", branch = "master" } #parry2d-f64 = { git = "https://github.com/dimforge/parry", branch = "master" } #parry3d-f64 = { git = "https://github.com/dimforge/parry", branch = "master" } -# puffin_egui = { version = "0.29", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } -puffin_egui = { optional = true, path = "../puffin/puffin_egui" } -puffin = { optional = true, path = "../puffin/puffin" } +puffin_egui = { version = "0.29", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } +puffin = { version = "0.19", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } +# puffin_egui = { optional = true, path = "../puffin/puffin_egui" } +# puffin = { optional = true, path = "../puffin/puffin" } [profile.release] From 988cba6800c6401cc3c1e1cdd00b41e21a647bc6 Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Fri, 15 Nov 2024 15:31:21 +0100 Subject: [PATCH 7/9] hide rapier testbed profiling highlight behind an unstable feature --- Cargo.toml | 8 ++--- crates/rapier_testbed2d-f64/Cargo.toml | 1 + crates/rapier_testbed2d/Cargo.toml | 1 + crates/rapier_testbed3d-f64/Cargo.toml | 1 + crates/rapier_testbed3d/Cargo.toml | 1 + src_testbed/ui.rs | 41 +++++++++++++++----------- 6 files changed, 32 insertions(+), 21 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index a74c32fc7..d2e7441e2 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -37,11 +37,11 @@ resolver = "2" #parry3d = { git = "https://github.com/dimforge/parry", branch = "master" } #parry2d-f64 = { git = "https://github.com/dimforge/parry", branch = "master" } #parry3d-f64 = { git = "https://github.com/dimforge/parry", branch = "master" } -puffin_egui = { version = "0.29", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } -puffin = { version = "0.19", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } -# puffin_egui = { optional = true, path = "../puffin/puffin_egui" } -# puffin = { optional = true, path = "../puffin/puffin" } +# # For feature unstable-puffin-pr-235 +# puffin_egui = { version = "0.29", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } +# puffin = { version = "0.19", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } +# # [profile.release] #debug = true diff --git a/crates/rapier_testbed2d-f64/Cargo.toml b/crates/rapier_testbed2d-f64/Cargo.toml index 8546d8643..a036947e5 100644 --- a/crates/rapier_testbed2d-f64/Cargo.toml +++ b/crates/rapier_testbed2d-f64/Cargo.toml @@ -35,6 +35,7 @@ dim2 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["wrapped2d"] profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] +unstable-puffin-pr-235 = [] [package.metadata.docs.rs] features = ["parallel", "profiling"] diff --git a/crates/rapier_testbed2d/Cargo.toml b/crates/rapier_testbed2d/Cargo.toml index 5ffa3afc3..65568694c 100644 --- a/crates/rapier_testbed2d/Cargo.toml +++ b/crates/rapier_testbed2d/Cargo.toml @@ -35,6 +35,7 @@ dim2 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["wrapped2d"] profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] +unstable-puffin-pr-235 = [] [package.metadata.docs.rs] features = ["parallel", "other-backends", "profiling"] diff --git a/crates/rapier_testbed3d-f64/Cargo.toml b/crates/rapier_testbed3d-f64/Cargo.toml index 9d645c72c..04a28cc96 100644 --- a/crates/rapier_testbed3d-f64/Cargo.toml +++ b/crates/rapier_testbed3d-f64/Cargo.toml @@ -37,6 +37,7 @@ default = ["dim3"] dim3 = [] parallel = ["rapier/parallel", "num_cpus"] profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] +unstable-puffin-pr-235 = [] [package.metadata.docs.rs] features = ["parallel", "profiling"] diff --git a/crates/rapier_testbed3d/Cargo.toml b/crates/rapier_testbed3d/Cargo.toml index 0d0b28e8d..082af75ab 100644 --- a/crates/rapier_testbed3d/Cargo.toml +++ b/crates/rapier_testbed3d/Cargo.toml @@ -35,6 +35,7 @@ dim3 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["physx", "physx-sys", "glam"] profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] +unstable-puffin-pr-235 = [] [package.metadata.docs.rs] features = ["parallel", "other-backends", "profiling"] diff --git a/src_testbed/ui.rs b/src_testbed/ui.rs index f2f9f9856..8e543afd8 100644 --- a/src_testbed/ui.rs +++ b/src_testbed/ui.rs @@ -23,28 +23,35 @@ pub fn update_ui( ) { #[cfg(feature = "profiling")] { - use std::sync::Once; let window = egui::Window::new("Profiling"); let window = window.default_open(false); - static START: Once = Once::new(); - - fn set_default_rapier_filter() { - let mut profile_ui = puffin_egui::PROFILE_UI.lock(); - profile_ui - .profiler_ui - .flamegraph_options - .scope_name_filter - .set_filter("Harness::step_with_graphics".to_string()); + + #[cfg(feature = "unstable-puffin-pr-235")] + { + use std::sync::Once; + static START: Once = Once::new(); + + fn set_default_rapier_filter() { + let mut profile_ui = puffin_egui::PROFILE_UI.lock(); + profile_ui + .profiler_ui + .flamegraph_options + .scope_name_filter + .set_filter("Harness::step_with_graphics".to_string()); + } + START.call_once(|| { + set_default_rapier_filter(); + }); + window.show(ui_context.ctx_mut(), |ui| { + if ui.button("πŸ” Rapier filter").clicked() { + set_default_rapier_filter(); + } + puffin_egui::profiler_ui(ui); + }); } - START.call_once(|| { - set_default_rapier_filter(); - }); + #[cfg(not(feature = "unstable-puffin-pr-235"))] window.show(ui_context.ctx_mut(), |ui| { - //profile_ui.profiler_ui.flamegraph_options. - if ui.button("πŸ” Rapier filter").clicked() { - set_default_rapier_filter(); - } puffin_egui::profiler_ui(ui); }); } From 6a53e594d408dc5ee50304e75576f9083818e623 Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Tue, 19 Nov 2024 15:46:10 +0100 Subject: [PATCH 8/9] made an issue for unstable-puffin-pr-235 + commented it to find it again --- Cargo.toml | 1 + crates/rapier_testbed2d-f64/Cargo.toml | 1 + crates/rapier_testbed2d/Cargo.toml | 1 + crates/rapier_testbed3d-f64/Cargo.toml | 1 + crates/rapier_testbed3d/Cargo.toml | 1 + 5 files changed, 5 insertions(+) diff --git a/Cargo.toml b/Cargo.toml index d2e7441e2..e8824ced5 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -39,6 +39,7 @@ resolver = "2" #parry3d-f64 = { git = "https://github.com/dimforge/parry", branch = "master" } # # For feature unstable-puffin-pr-235 +# # See https://github.com/dimforge/rapier/issues/760. # puffin_egui = { version = "0.29", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } # puffin = { version = "0.19", optional = true, git = "https://github.com/Vrixyz/puffin.git", branch = "expose_ui_options" } # # diff --git a/crates/rapier_testbed2d-f64/Cargo.toml b/crates/rapier_testbed2d-f64/Cargo.toml index a036947e5..fab895872 100644 --- a/crates/rapier_testbed2d-f64/Cargo.toml +++ b/crates/rapier_testbed2d-f64/Cargo.toml @@ -35,6 +35,7 @@ dim2 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["wrapped2d"] profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] +# See https://github.com/dimforge/rapier/issues/760. unstable-puffin-pr-235 = [] [package.metadata.docs.rs] diff --git a/crates/rapier_testbed2d/Cargo.toml b/crates/rapier_testbed2d/Cargo.toml index 65568694c..b95966f3d 100644 --- a/crates/rapier_testbed2d/Cargo.toml +++ b/crates/rapier_testbed2d/Cargo.toml @@ -35,6 +35,7 @@ dim2 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["wrapped2d"] profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] +# See https://github.com/dimforge/rapier/issues/760. unstable-puffin-pr-235 = [] [package.metadata.docs.rs] diff --git a/crates/rapier_testbed3d-f64/Cargo.toml b/crates/rapier_testbed3d-f64/Cargo.toml index 04a28cc96..97d1a5420 100644 --- a/crates/rapier_testbed3d-f64/Cargo.toml +++ b/crates/rapier_testbed3d-f64/Cargo.toml @@ -37,6 +37,7 @@ default = ["dim3"] dim3 = [] parallel = ["rapier/parallel", "num_cpus"] profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] +# See https://github.com/dimforge/rapier/issues/760. unstable-puffin-pr-235 = [] [package.metadata.docs.rs] diff --git a/crates/rapier_testbed3d/Cargo.toml b/crates/rapier_testbed3d/Cargo.toml index 082af75ab..2b536abd1 100644 --- a/crates/rapier_testbed3d/Cargo.toml +++ b/crates/rapier_testbed3d/Cargo.toml @@ -35,6 +35,7 @@ dim3 = [] parallel = ["rapier/parallel", "num_cpus"] other-backends = ["physx", "physx-sys", "glam"] profiling = ["dep:puffin_egui", "profiling/profile-with-puffin"] +# See https://github.com/dimforge/rapier/issues/760. unstable-puffin-pr-235 = [] [package.metadata.docs.rs] From ca6f71c9f6584894f4be40625ba3036ea3caacb9 Mon Sep 17 00:00:00 2001 From: Thierry Berger Date: Tue, 19 Nov 2024 16:11:30 +0100 Subject: [PATCH 9/9] add changelog for profiling --- CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index f377c9889..248e4021a 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -11,6 +11,8 @@ ### Added - `RigidBodySet` and `ColliderSet` have a new constructor `with_capacity`. +- Use `profiling` crate to provide helpful profiling information in different tools. + - The testbeds have been updated to use `puffin_egui` ### Modified