aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorCrozet Sébastien <developer@crozet.re>2021-04-30 11:37:58 +0200
committerCrozet Sébastien <developer@crozet.re>2021-04-30 11:37:58 +0200
commit2dfbd9ae92c139e306afc87994adac82489f30eb (patch)
treec5b9c5e6fcb5561421e2b4b9d99f28e4c83c745e
parentac8ec8e3517c8d9baf8219c04ce907028d70901b (diff)
downloadrapier-2dfbd9ae92c139e306afc87994adac82489f30eb.tar.gz
rapier-2dfbd9ae92c139e306afc87994adac82489f30eb.tar.bz2
rapier-2dfbd9ae92c139e306afc87994adac82489f30eb.zip
Add comments.
-rw-r--r--examples3d/all_examples3.rs5
-rw-r--r--examples3d/debug_shape_modification3.rs123
-rw-r--r--examples3d/primitives3.rs2
-rw-r--r--src/data/arena.rs12
-rw-r--r--src/data/component_set.rs17
-rw-r--r--src/dynamics/island_manager.rs6
-rw-r--r--src/dynamics/joint/joint_set.rs4
-rw-r--r--src/dynamics/rigid_body.rs137
-rw-r--r--src/dynamics/rigid_body_components.rs172
-rw-r--r--src/dynamics/rigid_body_set.rs10
-rw-r--r--src/geometry/collider.rs32
-rw-r--r--src/geometry/collider_components.rs66
-rw-r--r--src/geometry/collider_set.rs4
-rw-r--r--src/lib.rs2
-rw-r--r--src/pipeline/physics_pipeline.rs6
-rw-r--r--src_testbed/physx_backend.rs6
16 files changed, 440 insertions, 164 deletions
diff --git a/examples3d/all_examples3.rs b/examples3d/all_examples3.rs
index 2611a2f..8031814 100644
--- a/examples3d/all_examples3.rs
+++ b/examples3d/all_examples3.rs
@@ -25,6 +25,7 @@ mod debug_friction3;
mod debug_infinite_fall3;
mod debug_prismatic3;
mod debug_rollback3;
+mod debug_shape_modification3;
mod debug_triangle3;
mod debug_trimesh3;
mod domino3;
@@ -112,6 +113,10 @@ pub fn main() {
("(Debug) infinite fall", debug_infinite_fall3::init_world),
("(Debug) prismatic", debug_prismatic3::init_world),
("(Debug) rollback", debug_rollback3::init_world),
+ (
+ "(Debug) shape modification",
+ debug_shape_modification3::init_world,
+ ),
];
// Lexicographic sort, with stress tests moved at the end of the list.
diff --git a/examples3d/debug_shape_modification3.rs b/examples3d/debug_shape_modification3.rs
new file mode 100644
index 0000000..7ec06dd
--- /dev/null
+++ b/examples3d/debug_shape_modification3.rs
@@ -0,0 +1,123 @@
+use na::{Isometry3, Point3, Vector3};
+use rapier3d::dynamics::{JointSet, RigidBodyBuilder, RigidBodySet};
+use rapier3d::geometry::{ColliderBuilder, ColliderSet, SharedShape};
+use rapier_testbed3d::Testbed;
+
+pub fn init_world(testbed: &mut Testbed) {
+ /*
+ * World
+ */
+ let mut bodies = RigidBodySet::new();
+ let mut colliders = ColliderSet::new();
+ let joints = JointSet::new();
+ /*
+ * Ground.
+ */
+ let ground_size = 20.0;
+ let ground_height = 0.1;
+
+ let rigid_body = RigidBodyBuilder::new_static()
+ .translation(0.0, -ground_height, 0.0)
+ .build();
+ let ground_handle = bodies.insert(rigid_body);
+ let collider = ColliderBuilder::cuboid(ground_size, ground_height, ground_size)
+ .friction(0.15)
+ // .restitution(0.5)
+ .build();
+ colliders.insert(collider, ground_handle, &mut bodies);
+
+ /*
+ * Rolling ball
+ */
+ let ball_rad = 0.1;
+ let rb = RigidBodyBuilder::new_dynamic()
+ .translation(0.0, 0.2, 0.0)
+ .linvel(10.0, 0.0, 0.0)
+ .build();
+ let ball_handle = bodies.insert(rb);
+ let collider = ColliderBuilder::ball(ball_rad).density(100.0).build();
+ let ball_coll_handle = colliders.insert(collider, ball_handle, &mut bodies);
+
+ let mut linvel = Vector3::zeros();
+ let mut angvel = Vector3::zeros();
+ let mut pos = Isometry3::identity();
+ let mut step = 0;
+ let snapped_frame = 51;
+
+ testbed.add_callback(move |_, _, physics, _, _| {
+ step += 1;
+
+ // Snap the ball velocity or restore it.
+ let ball = physics.bodies.get_mut(ball_handle).unwrap();
+
+ if step == snapped_frame {
+ linvel = *ball.linvel();
+ angvel = *ball.angvel();
+ pos = *ball.position();
+ }
+
+ if step == 100 {
+ ball.set_linvel(linvel, true);
+ ball.set_angvel(angvel, true);
+ ball.set_position(pos, true);
+ step = snapped_frame;
+ }
+
+ let ball_coll = physics.colliders.get_mut(ball_coll_handle).unwrap();
+ ball_coll.set_shape(SharedShape::ball(ball_rad * step as f32 * 2.0));
+ });
+
+ /*
+ * Create the primitives
+ */
+ let num = 8;
+ let rad = 1.0;
+
+ let shiftx = rad * 2.0 + rad;
+ let shifty = rad * 2.0 + rad;
+ let shiftz = rad * 2.0 + rad;
+ let centerx = shiftx * (num / 2) as f32;
+ let centery = shifty / 2.0;
+ let centerz = shiftz * (num / 2) as f32;
+
+ let mut offset = -(num as f32) * (rad * 2.0 + rad) * 0.5;
+
+ for j in 0usize..20 {
+ for i in 0..num {
+ for k in 0usize..num {
+ let x = i as f32 * shiftx - centerx + offset + 5.0;
+ let y = j as f32 * shifty + centery + 3.0;
+ let z = k as f32 * shiftz - centerz + offset;
+
+ // Build the rigid body.
+ let rigid_body = RigidBodyBuilder::new_dynamic().translation(x, y, z).build();
+ let handle = bodies.insert(rigid_body);
+
+ let collider = match j % 5 {
+ 0 => ColliderBuilder::cuboid(rad, rad, rad).build(),
+ 1 => ColliderBuilder::ball(rad).build(),
+ // Rounded cylinders are much more efficient that cylinder, even if the
+ // rounding margin is small.
+ 2 => ColliderBuilder::round_cylinder(rad, rad, rad / 10.0).build(),
+ 3 => ColliderBuilder::cone(rad, rad).build(),
+ _ => ColliderBuilder::capsule_y(rad, rad).build(),
+ };
+
+ colliders.insert(collider, handle, &mut bodies);
+ }
+ }
+
+ offset -= 0.05 * rad * (num as f32 - 1.0);
+ }
+
+ /*
+ * Set up the testbed.
+ */
+ testbed.set_world(bodies, colliders, joints);
+ testbed.look_at(Point3::new(10.0, 10.0, 10.0), Point3::origin());
+}
+
+fn main() {
+ let testbed = Testbed::from_builders(0, vec![("Boxes", init_world)]);
+ testbed.run()
+}
diff --git a/examples3d/primitives3.rs b/examples3d/primitives3.rs
index db15341..2711ba9 100644
--- a/examples3d/primitives3.rs
+++ b/examples3d/primitives3.rs
@@ -25,7 +25,7 @@ pub fn init_world(testbed: &mut Testbed) {
colliders.insert(collider, handle, &mut bodies);
/*
- * Create the cubes
+ * Create the primitives
*/
let num = 8;
let rad = 1.0;
diff --git a/src/data/arena.rs b/src/data/arena.rs
index bc7176d..c7cbf07 100644
--- a/src/data/arena.rs
+++ b/src/data/arena.rs
@@ -770,13 +770,13 @@ impl<T> Arena<T> {
/// other kinds of bit-efficient indexing.
///
/// You should use the `get` method instead most of the time.
- pub fn get_unknown_gen(&self, i: usize) -> Option<(&T, Index)> {
- match self.items.get(i) {
+ pub fn get_unknown_gen(&self, i: u32) -> Option<(&T, Index)> {
+ match self.items.get(i as usize) {
Some(Entry::Occupied { generation, value }) => Some((
value,
Index {
generation: *generation,
- index: i as u32,
+ index: i,
},
)),
_ => None,
@@ -793,13 +793,13 @@ impl<T> Arena<T> {
/// other kinds of bit-efficient indexing.
///
/// You should use the `get_mut` method instead most of the time.
- pub fn get_unknown_gen_mut(&mut self, i: usize) -> Option<(&mut T, Index)> {
- match self.items.get_mut(i) {
+ pub fn get_unknown_gen_mut(&mut self, i: u32) -> Option<(&mut T, Index)> {
+ match self.items.get_mut(i as usize) {
Some(Entry::Occupied { generation, value }) => Some((
value,
Index {
generation: *generation,
- index: i as u32,
+ index: i,
},
)),
_ => None,
diff --git a/src/data/component_set.rs b/src/data/component_set.rs
index ca7df67..6e0461c 100644
--- a/src/data/component_set.rs
+++ b/src/data/component_set.rs
@@ -5,30 +5,47 @@ use crate::data::Index;
// fn get(&self, handle: Index) -> Option<&T>;
// }
+/// A set of optional elements of type `T`.
pub trait ComponentSetOption<T>: Sync {
+ /// Get the element associated to the given `handle`, if there is one.
fn get(&self, handle: Index) -> Option<&T>;
}
+/// A set of elements of type `T`.
pub trait ComponentSet<T>: ComponentSetOption<T> {
+ /// The estimated number of elements in this set.
+ ///
+ /// This value is typically used for preallocating some arrays for
+ /// better performances.
fn size_hint(&self) -> usize;
// TODO ECS: remove this, its only needed by the query pipeline update
// which should only take the modified colliders into account.
+ /// Iterate through all the elements on this set.
fn for_each(&self, f: impl FnMut(Index, &T));
+ /// Get the element associated to the given `handle`.
fn index(&self, handle: Index) -> &T {
self.get(handle).unwrap()
}
}
+/// A set of mutable elements of type `T`.
pub trait ComponentSetMut<T>: ComponentSet<T> {
+ /// Applies the given closure to the element associated to the given `handle`.
+ ///
+ /// Return `None` if the element doesn't exist.
fn map_mut_internal<Result>(
&mut self,
handle: crate::data::Index,
f: impl FnOnce(&mut T) -> Result,
) -> Option<Result>;
+
+ /// Set the value of this element.
fn set_internal(&mut self, handle: crate::data::Index, val: T);
}
+/// Helper trait to address multiple elements at once.
pub trait BundleSet<'a, T> {
+ /// Access multiple elements from this set.
fn index_bundle(&'a self, handle: Index) -> T;
}
diff --git a/src/dynamics/island_manager.rs b/src/dynamics/island_manager.rs
index 551e5a4..b79cdb2 100644
--- a/src/dynamics/island_manager.rs
+++ b/src/dynamics/island_manager.rs
@@ -6,6 +6,8 @@ use crate::dynamics::{
use crate::geometry::{ColliderParent, InteractionGraph, NarrowPhase};
use crate::math::Real;
+/// Structure responsible for maintaining the set of active rigid-bodies, and
+/// putting non-moving rigid-bodies to sleep to save computation times.
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
pub struct IslandManager {
pub(crate) active_dynamic_set: Vec<RigidBodyHandle>,
@@ -19,6 +21,7 @@ pub struct IslandManager {
}
impl IslandManager {
+ /// Creates a new empty island manager.
pub fn new() -> Self {
Self {
active_dynamic_set: vec![],
@@ -34,6 +37,7 @@ impl IslandManager {
self.active_islands.len() - 1
}
+ /// Update this data-structure after one or multiple rigid-bodies have been removed for `bodies`.
pub fn cleanup_removed_rigid_bodies(
&mut self,
bodies: &mut impl ComponentSetMut<RigidBodyIds>,
@@ -59,7 +63,7 @@ impl IslandManager {
}
}
- pub fn rigid_body_removed(
+ pub(crate) fn rigid_body_removed(
&mut self,
removed_handle: RigidBodyHandle,
removed_ids: &RigidBodyIds,
diff --git a/src/dynamics/joint/joint_set.rs b/src/dynamics/joint/joint_set.rs
index 8e4d9b8..c316008 100644
--- a/src/dynamics/joint/joint_set.rs
+++ b/src/dynamics/joint/joint_set.rs
@@ -94,7 +94,7 @@ impl JointSet {
///
/// Using this is discouraged in favor of `self.get(handle)` which does not
/// suffer form the ABA problem.
- pub fn get_unknown_gen(&self, i: usize) -> Option<(&Joint, JointHandle)> {
+ pub fn get_unknown_gen(&self, i: u32) -> Option<(&Joint, JointHandle)> {
let (id, handle) = self.joint_ids.get_unknown_gen(i)?;
Some((
self.joint_graph.graph.edge_weight(*id)?,
@@ -111,7 +111,7 @@ impl JointSet {
///
/// Using this is discouraged in favor of `self.get_mut(handle)` which does not
/// suffer form the ABA problem.
- pub fn get_unknown_gen_mut(&mut self, i: usize) -> Option<(&mut Joint, JointHandle)> {
+ pub fn get_unknown_gen_mut(&mut self, i: u32) -> Option<(&mut Joint, JointHandle)> {
let (id, handle) = self.joint_ids.get_unknown_gen(i)?;
Some((
self.joint_graph.graph.edge_weight_mut(*id)?,
diff --git a/src/dynamics/rigid_body.rs b/src/dynamics/rigid_body.rs
index 1bd1ba5..824ec92 100644
--- a/src/dynamics/rigid_body.rs
+++ b/src/dynamics/rigid_body.rs
@@ -7,8 +7,8 @@ use crate::geometry::{
Collider, ColliderHandle, ColliderMassProperties, ColliderParent, ColliderPosition,
ColliderShape,
};
-use crate::math::{AngVector, Isometry, Point, Real, Rotation, Translation, Vector};
-use crate::utils::{self, WAngularInertia, WCross};
+use crate::math::{AngVector, Isometry, Point, Real, Rotation, Vector};
+use crate::utils::{self, WCross};
use na::ComplexField;
use num::Zero;
@@ -18,21 +18,21 @@ use num::Zero;
/// To create a new rigid-body, use the `RigidBodyBuilder` structure.
#[derive(Debug, Clone)]
pub struct RigidBody {
- pub rb_pos: RigidBodyPosition, // TODO ECS: public only for initial tests with bevy_rapier.
- pub rb_mprops: RigidBodyMassProps, // TODO ECS: public only for initial tests with bevy_rapier.
- pub rb_vels: RigidBodyVelocity, // TODO ECS: public only for initial tests with bevy_rapier.
- pub rb_damping: RigidBodyDamping, // TODO ECS: public only for initial tests with bevy_rapier.
- pub rb_forces: RigidBodyForces, // TODO ECS: public only for initial tests with bevy_rapier.
- pub rb_ccd: RigidBodyCcd, // TODO ECS: public only for initial tests with bevy_rapier.
- pub rb_ids: RigidBodyIds, // TODO ECS: public only for initial tests with bevy_rapier.
- pub rb_colliders: RigidBodyColliders, // TODO ECS: public only for initial tests with bevy_rapier.
+ pub(crate) rb_pos: RigidBodyPosition,
+ pub(crate) rb_mprops: RigidBodyMassProps,
+ pub(crate) rb_vels: RigidBodyVelocity,
+ pub(crate) rb_damping: RigidBodyDamping,
+ pub(crate) rb_forces: RigidBodyForces,
+ pub(crate) rb_ccd: RigidBodyCcd,
+ pub(crate) rb_ids: RigidBodyIds,
+ pub(crate) rb_colliders: RigidBodyColliders,
/// Whether or not this rigid-body is sleeping.
- pub rb_activation: RigidBodyActivation, // TODO ECS: public only for initial tests with bevy_rapier.
- pub changes: RigidBodyChanges, // TODO ECS: public only for initial tests with bevy_rapier.
+ pub(crate) rb_activation: RigidBodyActivation,
+ pub(crate) changes: RigidBodyChanges,
/// The status of the body, governing how it is affected by external forces.
- pub rb_type: RigidBodyType, // TODO ECS: public only for initial tests with bevy_rapier
+ pub(crate) rb_type: RigidBodyType,
/// The dominance group this rigid-body is part of.
- pub rb_dominance: RigidBodyDominance,
+ pub(crate) rb_dominance: RigidBodyDominance,
/// User-defined data associated to this rigid-body.
pub user_data: u128,
}
@@ -61,61 +61,48 @@ impl RigidBody {
self.rb_ids = Default::default();
}
- pub fn user_data(&self) -> u128 {
- self.user_data
- }
-
- pub fn set_user_data(&mut self, data: u128) {
- self.user_data = data;
- }
-
- #[inline]
- pub fn rb_activation(&self) -> &RigidBodyActivation {
+ /// The activation status of this rigid-body.
+ pub fn activation(&self) -> &RigidBodyActivation {
&self.rb_activation
}
- #[inline]
+ /// Mutable reference to the activation status of this rigid-body.
pub fn activation_mut(&mut self) -> &mut RigidBodyActivation {
+ self.changes |= RigidBodyChanges::SLEEP;
&mut self.rb_activation
}
- #[inline]
- pub(crate) fn changes(&self) -> RigidBodyChanges {
- self.changes
- }
-
- #[inline]
- pub(crate) fn changes_mut_internal(&mut self) -> &mut RigidBodyChanges {
- &mut self.changes
- }
-
+ /// The linear damping coefficient of this rigid-body.
#[inline]
pub fn linear_damping(&self) -> Real {
self.rb_damping.linear_damping
}
+ /// Sets the linear damping coefficient of this rigid-body.
#[inline]
pub fn set_linear_damping(&mut self, damping: Real) {
self.rb_damping.linear_damping = damping;
}
+ /// The angular damping coefficient of this rigid-body.
#[inline]
pub fn angular_damping(&self) -> Real {
self.rb_damping.angular_damping
}
+ /// Sets the angular damping coefficient of this rigid-body.
#[inline]
pub fn set_angular_damping(&mut self, damping: Real) {
self.rb_damping.angular_damping = damping
}
- /// The status of this rigid-body.
- pub fn rb_type(&self) -> RigidBodyType {
+ /// The type of this rigid-body.
+ pub fn body_type(&self) -> RigidBodyType {
self.rb_type
}
- /// Sets the status of this rigid-body.
- pub fn set_rb_type(&mut self, status: RigidBodyType) {
+ /// Sets the type of this rigid-body.
+ pub fn set_body_type(&mut self, status: RigidBodyType) {
if status != self.rb_type {
self.changes.insert(RigidBodyChanges::TYPE);
self.rb_type = status;
@@ -336,22 +323,6 @@ impl RigidBody {
!self.rb_vels.linvel.is_zero() || !self.rb_vels.angvel.is_zero()
}
- /// Computes the predict position of this rigid-body after `dt` seconds, taking
- /// into account its velocities and external forces applied to it.
- pub fn predict_position_using_velocity_and_forces(&self, dt: Real) -> Isometry<Real> {
- let dlinvel = self.rb_forces.force * (self.rb_mprops.effective_inv_mass * dt);
- let dangvel = self
- .rb_mprops
- .effective_world_inv_inertia_sqrt
- .transform_vector(self.rb_forces.torque * dt);
- let linvel = self.rb_vels.linvel + dlinvel;
- let angvel = self.rb_vels.angvel + dangvel;
-
- let com = self.rb_pos.position * self.rb_mprops.mass_properties.local_com;
- let shift = Translation::from(com.coords);
- shift * Isometry::new(linvel * dt, angvel * dt) * shift.inverse() * self.rb_pos.position
- }
-
/// The linear velocity of this rigid-body.
pub fn linvel(&self) -> &Vector<Real> {
&self.rb_vels.linvel
@@ -567,30 +538,13 @@ impl RigidBody {
impl RigidBody {
/// The velocity of the given world-space point on this rigid-body.
pub fn velocity_at_point(&self, point: &Point<Real>) -> Vector<Real> {
- let dpt = point - self.rb_mprops.world_com;
- self.rb_vels.linvel + self.rb_vels.angvel.gcross(dpt)
+ self.rb_vels
+ .velocity_at_point(point, &self.rb_mprops.world_com)
}
/// The kinetic energy of this body.
pub fn kinetic_energy(&self) -> Real {
- let mut energy = (self.mass() * self.rb_vels.linvel.norm_squared()) / 2.0;
-
- #[cfg(feature = "dim2")]
- if !self.rb_mprops.effective_world_inv_inertia_sqrt.is_zero() {
- let inertia_sqrt = 1.0 / self.rb_mprops.effective_world_inv_inertia_sqrt;
- energy += (inertia_sqrt * self.rb_vels.angvel).powi(2) / 2.0;
- }
-
- #[cfg(feature = "dim3")]
- if !self.rb_mprops.effective_world_inv_inertia_sqrt.is_zero() {
- let inertia_sqrt = self
- .rb_mprops
- .effective_world_inv_inertia_sqrt
- .inverse_unchecked();
- energy += (inertia_sqrt * self.rb_vels.angvel).norm_squared() / 2.0;
- }
-
- energy
+ self.rb_vels.kinetic_energy(&self.rb_mprops)
}
/// The potential energy of this body in a gravity field.
@@ -894,39 +848,6 @@ impl RigidBodyBuilder {
self
}
- pub fn components(
- &self,
- ) -> (
- RigidBodyPosition,
- RigidBodyMassProps,
- RigidBodyVelocity,
- RigidBodyDamping,
- RigidBodyForces,
- RigidBodyCcd,
- RigidBodyIds,
- RigidBodyColliders,
- RigidBodyActivation,
- RigidBodyChanges,
- RigidBodyType,
- RigidBodyDominance,
- ) {
- let rb = self.build();
- (
- rb.rb_pos,
- rb.rb_mprops,
- rb.rb_vels,
- rb.rb_damping,
- rb.rb_forces,
- rb.rb_ccd,
- rb.rb_ids,
- rb.rb_colliders,
- rb.rb_activation,
- rb.changes,
- rb.rb_type,
- rb.rb_dominance,
- )
- }
-
/// Build a new rigid-body with the parameters configured with this builder.
pub fn build(&self) -> RigidBody {
let mut rb = RigidBody::new();
diff --git a/src/dynamics/rigid_body_components.rs b/src/dynamics/rigid_body_components.rs
index c87df1f..2a652f7 100644
--- a/src/dynamics/rigid_body_components.rs
+++ b/src/dynamics/rigid_body_components.rs
@@ -6,7 +6,7 @@ use crate::geometry::{
};
use crate::math::{AngVector, AngularInertia, Isometry, Point, Real, Translation, Vector};
use crate::parry::partitioning::IndexedData;
-use crate::utils::WDot;
+use crate::utils::{WCross, WDot};
use num::Zero;
/// The unique handle of a rigid body added to a `RigidBodySet`.
@@ -69,14 +69,17 @@ pub enum RigidBodyType {
}
impl RigidBodyType {
+ /// Is this rigid-body static (i.e. cannot move)?
pub fn is_static(self) -> bool {
self == RigidBodyType::Static
}
+ /// Is this rigid-body dynamic (i.e. can move and be affected by forces)?
pub fn is_dynamic(self) -> bool {
self == RigidBodyType::Dynamic
}
+ /// Is this rigid-body kinematic (i.e. can move but is unaffected by forces)?
pub fn is_kinematic(self) -> bool {
self == RigidBodyType::Kinematic
}
@@ -86,10 +89,15 @@ bitflags::bitflags! {
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
/// Flags describing how the rigid-body has been modified by the user.
pub struct RigidBodyChanges: u32 {
+ /// Flag indicating that any component of this rigid-body has been modified.
const MODIFIED = 1 << 0;
+ /// Flag indicating that the `RigidBodyPosition` component of this rigid-body has been modified.
const POSITION = 1 << 1;
+ /// Flag indicating that the `RigidBodyActivation` component of this rigid-body has been modified.
const SLEEP = 1 << 2;
+ /// Flag indicating that the `RigidBodyColliders` component of this rigid-body has been modified.
const COLLIDERS = 1 << 3;
+ /// Flag indicating that the `RigidBodyType` component of this rigid-body has been modified.
const TYPE = 1 << 4;
}
}
@@ -102,6 +110,7 @@ impl Default for RigidBodyChanges {
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
#[derive(Clone, Debug, Copy)]
+/// The position of this rigid-body.
pub struct RigidBodyPosition {
/// The world-space position of the rigid-body.
pub position: Isometry<Real>,
@@ -127,6 +136,8 @@ impl Default for RigidBodyPosition {
}
impl RigidBodyPosition {
+ /// Computes the velocity need to travel from `self.position` to `self.next_position` in
+ /// a time equal to `1.0 / inv_dt`.
#[must_use]
pub fn interpolate_velocity(&self, inv_dt: Real) -> RigidBodyVelocity {
let dpos = self.next_position * self.position.inverse();
@@ -143,6 +154,9 @@ impl RigidBodyPosition {
RigidBodyVelocity { linvel, angvel }
}
+ /// Compute new positions after integrating the given forces and velocities.
+ ///
+ /// This uses a symplectic Euler integration scheme.
#[must_use]
pub fn integrate_forces_and_velocities(
&self,
@@ -173,16 +187,23 @@ bitflags::bitflags! {
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
/// Flags affecting the behavior of the constraints solver for a given contact manifold.
pub struct RigidBodyMassPropsFlags: u8 {
+ /// Flag indicating that the rigid-body cannot translate along any direction.
const TRANSLATION_LOCKED = 1 << 0;
+ /// Flag indicating that the rigid-body cannot rotate along the `X` axis.
const ROTATION_LOCKED_X = 1 << 1;
+ /// Flag indicating that the rigid-body cannot rotate along the `X` axis.
const ROTATION_LOCKED_Y = 1 << 2;
+ /// Flag indicating that the rigid-body cannot rotate along the `X` axis.
const ROTATION_LOCKED_Z = 1 << 3;
+ /// Combination of flags indicating that the rigid-body cannot rotate along any axis.
const ROTATION_LOCKED = Self::ROTATION_LOCKED_X.bits | Self::ROTATION_LOCKED_Y.bits | Self::ROTATION_LOCKED_Z.bits;
}
}
+// TODO: split this into "LocalMassProps" and `WorldMassProps"?
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
#[derive(Clone, Debug, Copy)]
+/// The mass properties of this rigid-bodies.
pub struct RigidBodyMassProps {
/// Flags for locking rotation and translation.
pub flags: RigidBodyMassPropsFlags,
@@ -219,16 +240,20 @@ impl From<RigidBodyMassPropsFlags> for RigidBodyMassProps {
}
impl RigidBodyMassProps {
+ /// The mass of the rigid-body.
#[must_use]
- pub fn with_translations_locked(mut self) -> Self {
- self.flags |= RigidBodyMassPropsFlags::TRANSLATION_LOCKED;
- self
+ pub fn mass(&self) -> Real {
+ crate::utils::inv(self.mass_properties.inv_mass)
}
+ /// The effective mass (that takes the potential translation locking into account) of
+ /// this rigid-body.
+ #[must_use]
pub fn effective_mass(&self) -> Real {
crate::utils::inv(self.effective_inv_mass)
}
+ /// Update the world-space mass properties of `self`, taking into account the new position.
pub fn update_world_mass_properties(&mut self, position: &Isometry<Real>) {
self.world_com = self.mass_properties.world_com(&position);
self.effective_inv_mass = self.mass_properties.inv_mass;
@@ -286,6 +311,7 @@ impl RigidBodyMassProps {
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
#[derive(Clone, Debug, Copy)]
+/// The velocities of this rigid-body.
pub struct RigidBodyVelocity {
/// The linear velocity of the rigid-body.
pub linvel: Vector<Real>,
@@ -300,6 +326,7 @@ impl Default for RigidBodyVelocity {
}
impl RigidBodyVelocity {
+ /// Velocities set to zero.
#[must_use]
pub fn zero() -> Self {
Self {
@@ -308,11 +335,16 @@ impl RigidBodyVelocity {
}
}
+ /// The approximate kinetic energy of this rigid-body.
+ ///
+ /// This approximation does not take the rigid-body's mass and angular inertia
+ /// into account.
#[must_use]
pub fn pseudo_kinetic_energy(&self) -> Real {
self.linvel.norm_squared() + self.angvel.gdot(self.angvel)
}
+ /// Returns the update velocities after applying the given damping.
#[must_use]
pub fn apply_damping(&self, dt: Real, damping: &RigidBodyDamping) -> Self {
RigidBodyVelocity {
@@ -321,6 +353,15 @@ impl RigidBodyVelocity {
}
}
+ /// The velocity of the given world-space point on this rigid-body.
+ #[must_use]
+ pub fn velocity_at_point(&self, point: &Point<Real>, world_com: &Point<Real>) -> Vector<Real> {
+ let dpt = point - world_com;
+ self.linvel + self.angvel.gcross(dpt)
+ }
+
+ /// Integrate the velocities in `self` to compute obtain new positions when moving from the given
+ /// inital position `init_pos`.
#[must_use]
pub fn integrate(
&self,
@@ -336,14 +377,81 @@ impl RigidBodyVelocity {
result
}
+ /// Are these velocities exactly equal to zero?
#[must_use]
pub fn is_zero(&self) -> bool {
self.linvel.is_zero() && self.angvel.is_zero()
}
+
+ /// The kinetic energy of this rigid-body.
+ #[must_use]
+ pub fn kinetic_energy(&self, rb_mprops: &RigidBodyMassProps) -> Real {
+ let mut energy = (rb_mprops.mass() * self.linvel.norm_squared()) / 2.0;
+
+ #[cfg(feature = "dim2")]
+ if !rb_mprops.effective_world_inv_inertia_sqrt.is_zero() {
+ let inertia_sqrt = 1.0 / rb_mprops.effective_world_inv_inertia_sqrt;
+ energy += (inertia_sqrt * self.angvel).powi(2) / 2.0;
+ }
+
+ #[cfg(feature = "dim3")]
+ if !rb_mprops.effective_world_inv_inertia_sqrt.is_zero() {
+ let inertia_sqrt = rb_mprops
+ .effective_world_inv_inertia_sqrt
+ .inverse_unchecked();
+ energy += (inertia_sqrt * self.angvel).norm_squared() / 2.0;
+ }
+
+ energy
+ }
+
+ /// 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.
+ pub fn apply_impulse(&mut self, rb_mprops: &RigidBodyMassProps, impulse: Vector<Real>) {
+ self.linvel += impulse * rb_mprops.effective_inv_mass;
+ }
+
+ /// Applies an angular impulse at the center-of-mass of this rigid-body.
+ /// The impulse is applied right away, changing the angular velocity.
+ /// This does nothing on non-dynamic bodies.
+ #[cfg(feature = "dim2")]
+ pub fn apply_torque_impulse(&mut self, rb_mprops: &RigidBodyMassProps, torque_impulse: Real) {
+ self.angvel += rb_mprops.effective_world_inv_inertia_sqrt
+ * (rb_mprops.effective_world_inv_inertia_sqrt * torque_impulse);
+ }
+
+ /// Applies an angular impulse at the center-of-mass of this rigid-body.
+ /// The impulse is applied right away, changing the angular velocity.
+ /// This does nothing on non-dynamic bodies.
+ #[cfg(feature = "dim3")]
+ pub fn apply_torque_impulse(
+ &mut self,
+ rb_mprops: &RigidBodyMassProps,
+ torque_impulse: Vector<Real>,
+ ) {
+ self.angvel += rb_mprops.effective_world_inv_inertia_sqrt
+ * (rb_mprops.effective_world_inv_inertia_sqrt * torque_impulse);
+ }
+
+ /// Applies an impulse at the given world-space point of this rigid-body.
+ /// The impulse is applied right away, changing the linear and/or angular velocities.
+ /// This does nothing on non-dynamic bodies.
+ pub fn apply_impulse_at_point(
+ &mut self,
+ rb_mprops: &RigidBodyMassProps,
+ impulse: Vector<Real>,
+ point: Point<Real>,
+ ) {
+ let torque_impulse = (point - rb_mprops.world_com).gcross(impulse);
+ self.apply_impulse(rb_mprops, impulse);
+ self.apply_torque_impulse(rb_mprops, torque_impulse);
+ }
}
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
#[derive(Clone, Debug, Copy)]
+/// Damping factors to progressively slow down a rigid-body.
pub struct RigidBodyDamping {
/// Damping factor for gradually slowing down the translational motion of the rigid-body.
pub linear_damping: Real,
@@ -362,11 +470,14 @@ impl Default for RigidBodyDamping {
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
#[derive(Clone, Debug, Copy)]
+/// The user-defined external forces applied to this rigid-body.
pub struct RigidBodyForces {
/// Accumulation of external forces (only for dynamic bodies).
pub force: Vector<Real>,
/// Accumulation of external torques (only for dynamic bodies).
pub torque: AngVector<Real>,
+ /// Gravity is multiplied by this scaling factor before it's
+ /// applied to this rigid-body.
pub gravity_scale: Real,
}
@@ -381,6 +492,7 @@ impl Default for RigidBodyForces {
}
impl RigidBodyForces {
+ /// Integrate these forces to compute new velocities.
#[must_use]
pub fn integrate(
&self,
@@ -398,17 +510,41 @@ impl RigidBodyForces {
}
}
- pub fn add_linear_acceleration(&mut self, gravity: &Vector<Real>, mass: Real) {
+ /// Adds to `self` the gravitational force that would result in a gravitational acceleration
+ /// equal to `gravity`.
+ pub fn add_gravity_acceleration(&mut self, gravity: &Vector<Real>, mass: Real) {
self.force += gravity * self.gravity_scale * mass;
}
+
+ /// Applies a force at the given world-space point of the rigid-body with the given mass properties.
+ pub fn apply_force_at_point(
+ &mut self,
+ rb_mprops: &RigidBodyMassProps,
+ force: Vector<Real>,
+ point: Point<Real>,
+ ) {
+ self.force += force;
+ self.torque += (point - rb_mprops.world_com).gcross(force);