aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorThierry Berger <contact@thierryberger.com>2024-11-19 16:33:26 +0100
committerGitHub <noreply@github.com>2024-11-19 16:33:26 +0100
commit510237cc29ebc667a8c158ef0340b7d1aa669a72 (patch)
tree772daf3fac2e463eba254900001fce5a659f2f92 /src
parentff79f4c67478f8c8045464cac22f9e57388cd4a0 (diff)
downloadrapier-510237cc29ebc667a8c158ef0340b7d1aa669a72.tar.gz
rapier-510237cc29ebc667a8c158ef0340b7d1aa669a72.tar.bz2
rapier-510237cc29ebc667a8c158ef0340b7d1aa669a72.zip
Profiling support (#743)
Diffstat (limited to 'src')
-rw-r--r--src/control/character_controller.rs5
-rw-r--r--src/control/ray_cast_vehicle_controller.rs3
-rw-r--r--src/dynamics/ccd/ccd_solver.rs2
-rw-r--r--src/dynamics/ccd/toi_entry.rs1
-rw-r--r--src/dynamics/joint/impulse_joint/impulse_joint_set.rs3
-rw-r--r--src/dynamics/joint/multibody_joint/multibody.rs2
-rw-r--r--src/dynamics/joint/multibody_joint/multibody_ik.rs2
-rw-r--r--src/dynamics/joint/multibody_joint/multibody_joint.rs1
-rw-r--r--src/dynamics/joint/multibody_joint/multibody_joint_set.rs6
-rw-r--r--src/dynamics/rigid_body.rs3
-rw-r--r--src/dynamics/rigid_body_components.rs1
-rw-r--r--src/dynamics/rigid_body_set.rs1
-rw-r--r--src/dynamics/solver/contact_constraint/contact_constraints_set.rs4
-rw-r--r--src/dynamics/solver/contact_constraint/generic_one_body_constraint.rs1
-rw-r--r--src/dynamics/solver/interaction_groups.rs1
-rw-r--r--src/dynamics/solver/island_solver.rs1
-rw-r--r--src/dynamics/solver/joint_constraint/joint_constraints_set.rs2
-rw-r--r--src/dynamics/solver/joint_constraint/joint_velocity_constraint.rs1
-rw-r--r--src/dynamics/solver/parallel_island_solver.rs1
-rw-r--r--src/dynamics/solver/velocity_solver.rs2
-rw-r--r--src/geometry/broad_phase_multi_sap/broad_phase_multi_sap.rs5
-rw-r--r--src/geometry/broad_phase_multi_sap/sap_axis.rs1
-rw-r--r--src/geometry/broad_phase_multi_sap/sap_layer.rs4
-rw-r--r--src/geometry/broad_phase_multi_sap/sap_region.rs1
-rw-r--r--src/geometry/contact_pair.rs1
-rw-r--r--src/geometry/interaction_graph.rs2
-rw-r--r--src/geometry/mesh_converter.rs1
-rw-r--r--src/geometry/narrow_phase.rs7
-rw-r--r--src/pipeline/debug_render_pipeline/debug_render_pipeline.rs7
-rw-r--r--src/pipeline/query_pipeline/mod.rs13
30 files changed, 85 insertions, 0 deletions
diff --git a/src/control/character_controller.rs b/src/control/character_controller.rs
index 0b086fb..ba0baeb 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,
@@ -430,6 +431,7 @@ impl KinematicCharacterController {
self.offset.eval(up_extends) + 0.05
}
+ #[profiling::function]
fn detect_grounded_status_and_apply_friction(
&self,
dt: Real,
@@ -657,6 +659,7 @@ impl KinematicCharacterController {
Vector2::new(side_extent, up_extent)
}
+ #[profiling::function]
fn handle_stairs(
&self,
bodies: &RigidBodySet,
@@ -817,6 +820,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,
@@ -846,6 +850,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 98b6339..eaa506b 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 e9ecfb8..0f97cfc 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 82b4532..a85e107 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<QD: ?Sized + QueryDispatcher>(
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 8f47e0e..093a372 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<ImpulseJoint> {
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 f05ce75..cb25624 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 b5e0de6..6923eec 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<Real>,
desired_movement: &SpacialVector<Real>,
@@ -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 179b061..4785c38 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 de1748c..d315729 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,
@@ -441,6 +446,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 8522d4d..60f403e 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<Real>, 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<Real>, 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 6bc2949..e451510 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 3145300..1261e4a 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 4d2b40d..7b046b6 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<Real>],
@@ -465,6 +466,7 @@ impl ContactConstraintsSet {
}
}
+ #[profiling::function]
pub fn solve_restitution_wo_bias(
&mut self,
solver_vels: &mut [SolverVel<Real>],
@@ -477,6 +479,7 @@ impl ContactConstraintsSet {
}
}
+ #[profiling::function]
pub fn solve_friction(
&mut self,
solver_vels: &mut [SolverVel<Real>],
@@ -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 e254995..6873407 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<Real>,
diff --git a/src/dynamics/solver/interaction_groups.rs b/src/dynamics/solver/interaction_groups.rs
index 1e834e6..13d6655 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 f9c84a5..b7c44df 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 64c1e83..1436538 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<Real>],
@@ -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 60c42d3..61a8821 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<N: SimdRealCopy, const LANES: usize> {
}
impl<N: SimdRealCopy, const LANES: usize> JointTwoBodyConstraint<N, LANES> {
+ #[profiling::function]
pub fn solve_generic(
&mut self,
solver_vel1: &mut SolverVel<N>,
diff --git a/src/dynamics/solver/parallel_island_solver.rs b/src/dynamics/solver/parallel_island_solver.rs
index 218d2af..4cfa2d2 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 a4e03b2..bd6ac2c 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 cd5ac28..197ebaf 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() {
@@ -473,6 +475,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 +505,7 @@ impl BroadPhaseMultiSap {
}
}
+ #[profiling::function]
fn update_layers_and_find_pairs(&mut self, out_events: &mut Vec<BroadPhasePairEvent>) {
if self.layers.is_empty() {
return;
@@ -579,6 +583,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 f1afdee..60dddd6 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,
diff --git a/src/geometry/broad_phase_multi_sap/sap_layer.rs b/src/geometry/broad_phase_multi_sap/sap_layer.rs
index 2620798..cadb5f1 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,
@@ -273,6 +276,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 f54b4ae..7c876c5 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 3d4e955..3f569b2 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 de2948b..4fb5054 100644
--- a/src/geometry/interaction_graph.rs
+++ b/src/geometry/interaction_graph.rs
@@ -96,6 +96,7 @@ impl<N: Copy, E> InteractionGraph<N, E> {
}
/// 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<N: Copy, E> InteractionGraph<N, E> {
}
/// 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 a4c8861..cfa1391 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<Point<Real>>,
diff --git a/src/geometry/narrow_phase.rs b/src/geometry/narrow_phase.rs
index e979a2f..908f83e 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))
@@ -687,6 +692,7 @@ impl NarrowPhase {
}
}
+ #[profiling::function]
pub(crate) fn compute_intersections(
&mut self,
bodies: &RigidBodySet,
@@ -785,6 +791,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 f2e23cd..4d1a21e 100644
--- a/