Skip to content

Commit

Permalink
profiling support
Browse files Browse the repository at this point in the history
  • Loading branch information
Vrixyz committed Sep 27, 2024
1 parent 9e1113c commit 0d33293
Show file tree
Hide file tree
Showing 46 changed files with 123 additions and 7 deletions.
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
{
"rust-analyzer.cargo.features": [
"simd-stable"
"simd-stable",
"dim3"
]
}
1 change: 1 addition & 0 deletions crates/rapier2d-f64/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ bitflags = "2"
log = "0.4"
ordered-float = "4"
thiserror = "1"
profiling = "1.0"

[dev-dependencies]
bincode = "1"
Expand Down
1 change: 1 addition & 0 deletions crates/rapier2d/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ bitflags = "2"
log = "0.4"
ordered-float = "4"
thiserror = "1"
profiling = "1.0"

[dev-dependencies]
bincode = "1"
Expand Down
1 change: 1 addition & 0 deletions crates/rapier3d-f64/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ bitflags = "2"
log = "0.4"
ordered-float = "4"
thiserror = "1"
profiling = "1.0"

[dev-dependencies]
bincode = "1"
Expand Down
9 changes: 8 additions & 1 deletion crates/rapier3d-stl/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,20 @@ 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"

[dependencies]
thiserror = "1.0.61"
stl_io = "0.7"
profiling = "1.0"

rapier3d = { version = "0.22", path = "../rapier3d" }
9 changes: 8 additions & 1 deletion crates/rapier3d-urdf/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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 }
1 change: 1 addition & 0 deletions crates/rapier3d/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ bitflags = "2"
log = "0.4"
ordered-float = "4"
thiserror = "1"
profiling = "1.0"

[dev-dependencies]
bincode = "1"
Expand Down
2 changes: 1 addition & 1 deletion crates/rapier_testbed2d-f64/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -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]
Expand Down
2 changes: 1 addition & 1 deletion crates/rapier_testbed2d/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -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]
Expand Down
2 changes: 1 addition & 1 deletion crates/rapier_testbed3d-f64/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -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]
Expand Down
2 changes: 1 addition & 1 deletion crates/rapier_testbed3d/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -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]
Expand Down
5 changes: 5 additions & 0 deletions src/control/character_controller.rs
Original file line number Diff line number Diff line change
Expand Up @@ -211,6 +211,7 @@ impl KinematicCharacterController {
}

/// Computes the possible movement for a shape.
#[profiling::function]
pub fn move_shape(
&self,
dt: Real,
Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -629,6 +631,7 @@ impl KinematicCharacterController {
Vector2::new(side_extent, up_extent)
}

#[profiling::function]
fn handle_stairs(
&self,
bodies: &RigidBodySet,
Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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,
Expand Down
3 changes: 3 additions & 0 deletions src/control/ray_cast_vehicle_controller.rs
Original file line number Diff line number Diff line change
Expand Up @@ -321,6 +321,7 @@ impl DynamicRayCastVehicleController {
wheel.wheel_axle_ws = chassis_transform * wheel.axle_cs;
}

#[profiling::function]
fn ray_cast(
&mut self,
bodies: &RigidBodySet,
Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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();

Expand Down
2 changes: 2 additions & 0 deletions src/dynamics/ccd/ccd_solver.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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,
Expand Down
1 change: 1 addition & 0 deletions src/dynamics/ccd/toi_entry.rs
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ impl TOIEntry {
}
}

#[profiling::function]
pub fn try_from_colliders<QD: ?Sized + QueryDispatcher>(
query_dispatcher: &QD,
ch1: ColliderHandle,
Expand Down
3 changes: 3 additions & 0 deletions src/dynamics/joint/impulse_joint/impulse_joint_set.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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)?;
Expand Down Expand Up @@ -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,
Expand Down
2 changes: 2 additions & 0 deletions src/dynamics/joint/multibody_joint/multibody.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -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,
Expand Down
2 changes: 2 additions & 0 deletions src/dynamics/joint/multibody_joint/multibody_ik.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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>,
Expand All @@ -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,
Expand Down
1 change: 1 addition & 0 deletions src/dynamics/joint/multibody_joint/multibody_joint.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
7 changes: 7 additions & 0 deletions src/dynamics/joint/multibody_joint/multibody_joint_set.rs
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,7 @@ impl MultibodyJointSet {
}

/// Inserts a new multibody_joint into this set.
#[profiling::function]
fn do_insert(
&mut self,
body1: RigidBodyHandle,
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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.
Expand All @@ -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() {
Expand Down Expand Up @@ -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,
Expand All @@ -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,
Expand All @@ -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,
Expand Down
3 changes: 3 additions & 0 deletions src/dynamics/rigid_body.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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
Expand All @@ -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
Expand Down
1 change: 1 addition & 0 deletions src/dynamics/rigid_body_components.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
1 change: 1 addition & 0 deletions src/dynamics/rigid_body_set.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
Loading

0 comments on commit 0d33293

Please sign in to comment.