aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorCrozet Sébastien <developer@crozet.re>2021-01-27 14:20:14 +0100
committerCrozet Sébastien <developer@crozet.re>2021-01-27 14:20:14 +0100
commit8ff2bcc3ec666805aceedaa477bde89f2a577d1c (patch)
tree5cb00c1003e75924b7ac9ad6dbbd509052a3def2
parenta3324f85131215613b7a8acb60d9ee9517cc803d (diff)
downloadrapier-8ff2bcc3ec666805aceedaa477bde89f2a577d1c.tar.gz
rapier-8ff2bcc3ec666805aceedaa477bde89f2a577d1c.tar.bz2
rapier-8ff2bcc3ec666805aceedaa477bde89f2a577d1c.zip
Add all the missing docs.
-rw-r--r--src/dynamics/joint/joint_set.rs2
-rw-r--r--src/dynamics/rigid_body_set.rs3
-rw-r--r--src/geometry/collider.rs18
-rw-r--r--src/geometry/collider_set.rs2
-rw-r--r--src/geometry/contact_pair.rs16
-rw-r--r--src/geometry/mod.rs2
-rw-r--r--src/lib.rs11
-rw-r--r--src/pipeline/query_pipeline.rs86
8 files changed, 133 insertions, 7 deletions
diff --git a/src/dynamics/joint/joint_set.rs b/src/dynamics/joint/joint_set.rs
index 50c88a2..a87532a 100644
--- a/src/dynamics/joint/joint_set.rs
+++ b/src/dynamics/joint/joint_set.rs
@@ -12,10 +12,12 @@ use crate::dynamics::{JointParams, RigidBodyHandle, RigidBodySet};
pub struct JointHandle(pub(crate) crate::data::arena::Index);
impl JointHandle {
+ /// Converts this handle into its (index, generation) components.
pub fn into_raw_parts(self) -> (usize, u64) {
self.0.into_raw_parts()
}
+ /// Reconstructs an handle from its (index, generation) components.
pub fn from_raw_parts(id: usize, generation: u64) -> Self {
Self(crate::data::arena::Index::from_raw_parts(id, generation))
}
diff --git a/src/dynamics/rigid_body_set.rs b/src/dynamics/rigid_body_set.rs
index dda2f42..36cf4d3 100644
--- a/src/dynamics/rigid_body_set.rs
+++ b/src/dynamics/rigid_body_set.rs
@@ -14,10 +14,12 @@ use std::ops::{Index, IndexMut};
pub struct RigidBodyHandle(pub(crate) crate::data::arena::Index);
impl RigidBodyHandle {
+ /// Converts this handle into its (index, generation) components.
pub fn into_raw_parts(self) -> (usize, u64) {
self.0.into_raw_parts()
}
+ /// Reconstructs an handle from its (index, generation) components.
pub fn from_raw_parts(id: usize, generation: u64) -> Self {
Self(crate::data::arena::Index::from_raw_parts(id, generation))
}
@@ -52,6 +54,7 @@ pub struct BodyPair {
}
impl BodyPair {
+ /// Builds a new pair of rigid-body handles.
pub fn new(body1: RigidBodyHandle, body2: RigidBodyHandle) -> Self {
BodyPair { body1, body2 }
}
diff --git a/src/geometry/collider.rs b/src/geometry/collider.rs
index 8924a3d..fa2da68 100644
--- a/src/geometry/collider.rs
+++ b/src/geometry/collider.rs
@@ -191,6 +191,7 @@ impl ColliderBuilder {
self.density.unwrap_or(default_density)
}
+ /// Initialize a new collider builder with a compound shape.
pub fn compound(shapes: Vec<(Isometry<Real>, SharedShape)>) -> Self {
Self::new(SharedShape::compound(shapes))
}
@@ -357,29 +358,46 @@ impl ColliderBuilder {
))
}
+ /// Initializes a new collider builder with a 2D convex polygon or 3D convex polyhedron
+ /// obtained after computing the convex-hull of the given points.
pub fn convex_hull(points: &[Point<Real>]) -> Option<Self> {
SharedShape::convex_hull(points).map(|cp| Self::new(cp))
}
+ /// Initializes a new collider builder with a round 2D convex polygon or 3D convex polyhedron
+ /// obtained after computing the convex-hull of the given points. The shape is dilated
+ /// by a sphere of radius `border_radius`.
pub fn round_convex_hull(points: &[Point<Real>], border_radius: Real) -> Option<Self> {
SharedShape::round_convex_hull(points, border_radius).map(|cp| Self::new(cp))
}
+ /// Creates a new collider builder that is a convex polygon formed by the
+ /// given polyline assumed to be convex (no convex-hull will be automatically
+ /// computed).
#[cfg(feature = "dim2")]
pub fn convex_polyline(points: Vec<Point<Real>>) -> Option<Self> {
SharedShape::convex_polyline(points).map(|cp| Self::new(cp))
}
+ /// Creates a new collider builder that is a round convex polygon formed by the
+ /// given polyline assumed to be convex (no convex-hull will be automatically
+ /// computed). The polygon shape is dilated by a sphere of radius `border_radius`.
#[cfg(feature = "dim2")]
pub fn round_convex_polyline(points: Vec<Point<Real>>, border_radius: Real) -> Option<Self> {
SharedShape::round_convex_polyline(points, border_radius).map(|cp| Self::new(cp))
}
+ /// Creates a new collider builder that is a convex polyhedron formed by the
+ /// given triangle-mesh assumed to be convex (no convex-hull will be automatically
+ /// computed).
#[cfg(feature = "dim3")]
pub fn convex_mesh(points: Vec<Point<Real>>, indices: &[[u32; 3]]) -> Option<Self> {
SharedShape::convex_mesh(points, indices).map(|cp| Self::new(cp))
}
+ /// Creates a new collider builder that is a round convex polyhedron formed by the
+ /// given triangle-mesh assumed to be convex (no convex-hull will be automatically
+ /// computed). The triangle mesh shape is dilated by a sphere of radius `border_radius`.
#[cfg(feature = "dim3")]
pub fn round_convex_mesh(
points: Vec<Point<Real>>,
diff --git a/src/geometry/collider_set.rs b/src/geometry/collider_set.rs
index b40c7f3..3ceb297 100644
--- a/src/geometry/collider_set.rs
+++ b/src/geometry/collider_set.rs
@@ -12,10 +12,12 @@ use std::ops::{Index, IndexMut};
pub struct ColliderHandle(pub(crate) crate::data::arena::Index);
impl ColliderHandle {
+ /// Converts this handle into its (index, generation) components.
pub fn into_raw_parts(self) -> (usize, u64) {
self.0.into_raw_parts()
}
+ /// Reconstructs an handle from its (index, generation) components.
pub fn from_raw_parts(id: usize, generation: u64) -> Self {
Self(crate::data::arena::Index::from_raw_parts(id, generation))
}
diff --git a/src/geometry/contact_pair.rs b/src/geometry/contact_pair.rs
index cbb012a..f6c4989 100644
--- a/src/geometry/contact_pair.rs
+++ b/src/geometry/contact_pair.rs
@@ -62,6 +62,7 @@ pub struct ContactPair {
///
/// All contact manifold contain themselves contact points between the colliders.
pub manifolds: Vec<ContactManifold>,
+ /// Is there any active contact in this contact pair?
pub has_any_active_contact: bool,
pub(crate) workspace: Option<ContactManifoldsWorkspace>,
}
@@ -95,18 +96,31 @@ pub struct ContactManifoldData {
// contact preparation method.
/// Flags used to control some aspects of the constraints solver for this contact manifold.
pub solver_flags: SolverFlags,
+ /// The world-space contact normal shared by all the contact in this contact manifold.
pub normal: Vector<Real>,
+ /// The contacts that will be seen by the constraints solver for computing forces.
pub solver_contacts: Vec<SolverContact>,
}
+/// A contact seen by the constraints solver for computing forces.
#[derive(Copy, Clone, Debug)]
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
pub struct SolverContact {
+ /// The world-space contact point.
pub point: Point<Real>,
+ /// The distance between the two original contacts points along the contact normal.
+ /// If negative, this is measures the penetration depth.
pub dist: Real,
+ /// The effective friction coefficient at this contact point.
pub friction: Real,
+ /// The effective restitution coefficient at this contact point.
pub restitution: Real,
+ /// The artificially add relative velocity at the contact point.
+ /// This is set to zero by default. Set to a non-zero value to
+ /// simulate, e.g., conveyor belts.
pub surface_velocity: Vector<Real>,
+ /// Associated contact data used to warm-start the constraints
+ /// solver.
pub data: ContactData,
}
@@ -132,6 +146,8 @@ impl ContactManifoldData {
}
}
+ /// Number of actives contacts, i.e., contacts that will be seen by
+ /// the constraints solver.
#[inline]
pub fn num_active_contacts(&self) -> usize {
self.solver_contacts.len()
diff --git a/src/geometry/mod.rs b/src/geometry/mod.rs
index d1c4161..861763e 100644
--- a/src/geometry/mod.rs
+++ b/src/geometry/mod.rs
@@ -14,7 +14,9 @@ pub use self::pair_filter::{ContactPairFilter, IntersectionPairFilter, PairFilte
pub use parry::query::TrackedContact;
+/// A contact between two colliders.
pub type Contact = parry::query::TrackedContact<ContactData>;
+/// A contact manifold between two colliders.
pub type ContactManifold = parry::query::ContactManifold<ContactManifoldData, ContactData>;
/// A segment shape.
pub type Segment = parry::shape::Segment;
diff --git a/src/lib.rs b/src/lib.rs
index 08be61a..e63b0d4 100644
--- a/src/lib.rs
+++ b/src/lib.rs
@@ -8,8 +8,7 @@
//! - The ability to run a perfectly deterministic simulation on different machine, as long as they
//! are compliant with the IEEE 754-2008 floating point standard.
-// FIXME: deny that
-#![allow(missing_docs)]
+#![warn(missing_docs)]
#[cfg(all(feature = "dim2", feature = "f32"))]
pub extern crate parry2d as parry;
@@ -126,6 +125,7 @@ pub(crate) const INVALID_U32: u32 = u32::MAX;
pub(crate) const INVALID_U64: u64 = u64::MAX;
pub(crate) const INVALID_USIZE: usize = INVALID_U32 as usize;
+/// The string version of Rapier.
pub const VERSION: &'static str = env!("CARGO_PKG_VERSION");
pub mod counters;
@@ -135,10 +135,17 @@ pub mod geometry;
pub mod pipeline;
pub mod utils;
+/// Elementary mathematical entities (vectors, matrices, isometries, etc).
pub mod math {
pub use parry::math::*;
+ /// Max number of pairs of contact points from the same
+ /// contact manifold that can be solved as part of a
+ /// single contact constraint.
#[cfg(feature = "dim2")]
pub const MAX_MANIFOLD_POINTS: usize = 2;
+ /// Max number of pairs of contact points from the same
+ /// contact manifold that can be solved as part of a
+ /// single contact constraint.
#[cfg(feature = "dim3")]
pub const MAX_MANIFOLD_POINTS: usize = 4;
}
diff --git a/src/pipeline/query_pipeline.rs b/src/pipeline/query_pipeline.rs
index 145dd87..8cc6a60 100644
--- a/src/pipeline/query_pipeline.rs
+++ b/src/pipeline/query_pipeline.rs
@@ -92,6 +92,10 @@ impl QueryPipeline {
}
}
+ /// Initializes an empty query pipeline with a custom `QueryDispatcher`.
+ ///
+ /// Use this constructor in order to use a custom `QueryDispatcher` that is
+ /// awary of your own user-defined shapes.
pub fn with_query_dispatcher<D>(d: D) -> Self
where
D: 'static + QueryDispatcher,
@@ -215,7 +219,14 @@ impl QueryPipeline {
self.quadtree.traverse_depth_first(&mut visitor);
}
- /// Find up to one collider intersecting the given shape.
+ /// Gets the handle of up to one collider intersecting the given shape.
+ ///
+ /// # Parameters
+ /// * `colliders` - The set of colliders taking part in this pipeline.
+ /// * `shape_pos` - The position of the shape used for the intersection test.
+ /// * `shape` - The shape used for the intersection test.
+ /// * `groups` - The bit groups and filter associated to the ray, in order to only
+ /// hit the colliders with collision groups compatible with the ray's group.
pub fn intersection_with_shape(
&self,
colliders: &ColliderSet,
@@ -236,7 +247,18 @@ impl QueryPipeline {
.map(|h| (h.1 .0))
}
- /// Projects a point on the scene.
+ /// Find the projection of a point on the closest collider.
+ ///
+ /// # Parameters
+ /// * `colliders` - The set of colliders taking part in this pipeline.
+ /// * `point` - The point to project.
+ /// * `solid` - If this is set to `true` then the collider shapes are considered to
+ /// be plain (if the point is located inside of a plain shape, its projection is the point
+ /// itself). If it is set to `false` the collider shapes are considered to be hollow
+ /// (if the point is located inside of an hollow shape, it is projected on the shape's
+ /// boundary).
+ /// * `groups` - The bit groups and filter associated to the point to project, in order to only
+ /// project on colliders with collision groups compatible with the ray's group.
pub fn project_point(
&self,
colliders: &ColliderSet,
@@ -253,7 +275,15 @@ impl QueryPipeline {
.map(|h| (h.1 .1, h.1 .0))
}
- /// Gets all the colliders containing the given point.
+ /// Find all the colliders containing the given point.
+ ///
+ /// # Parameters
+ /// * `colliders` - The set of colliders taking part in this pipeline.
+ /// * `point` - The point used for the containment test.
+ /// * `groups` - The bit groups and filter associated to the point to test, in order to only
+ /// test on colliders with collision groups compatible with the ray's group.
+ /// * `callback` - A function called with each collider with a shape
+ /// containing the `point`.
pub fn intersections_with_point<'a>(
&self,
colliders: &'a ColliderSet,
@@ -278,7 +308,20 @@ impl QueryPipeline {
self.quadtree.traverse_depth_first(&mut visitor);
}
- /// Projects a point on the scene and get
+ /// Find the projection of a point on the closest collider.
+ ///
+ /// The results include the ID of the feature hit by the point.
+ ///
+ /// # Parameters
+ /// * `colliders` - The set of colliders taking part in this pipeline.
+ /// * `point` - The point to project.
+ /// * `solid` - If this is set to `true` then the collider shapes are considered to
+ /// be plain (if the point is located inside of a plain shape, its projection is the point
+ /// itself). If it is set to `false` the collider shapes are considered to be hollow
+ /// (if the point is located inside of an hollow shape, it is projected on the shape's
+ /// boundary).
+ /// * `groups` - The bit groups and filter associated to the point to project, in order to only
+ /// project on colliders with collision groups compatible with the ray's group.
pub fn project_point_and_get_feature(
&self,
colliders: &ColliderSet,
@@ -293,6 +336,20 @@ impl QueryPipeline {
.map(|h| (h.1 .1 .0, h.1 .0, h.1 .1 .1))
}
+ /// Casts a shape at a constant linear velocity and retrieve the first collider it hits.
+ ///
+ /// This is similar to ray-casting except that we are casting a whole shape instead of
+ /// just a point (the ray origin).
+ ///
+ /// # Parameters
+ /// * `colliders` - The set of colliders taking part in this pipeline.
+ /// * `shape_pos` - The initial position of the shape to cast.
+ /// * `shape_vel` - The constant velocity of the shape to cast (i.e. the cast direction).
+ /// * `shape` - The shape to cast.
+ /// * `max_toi` - The maximum time-of-impact that can be reported by this cast. This effectively
+ /// limits the distance traveled by the shape to `shapeVel.norm() * maxToi`.
+ /// * `groups` - The bit groups and filter associated to the shape to cast, in order to only
+ /// test on colliders with collision groups compatible with this group.
pub fn cast_shape<'a>(
&self,
colliders: &'a ColliderSet,
@@ -316,6 +373,16 @@ impl QueryPipeline {
self.quadtree.traverse_best_first(&mut visitor).map(|h| h.1)
}
+ /// Casts a shape with an arbitrary continuous motion and retrieve the first collider it hits.
+ ///
+ /// # Parameters
+ /// * `colliders` - The set of colliders taking part in this pipeline.
+ /// * `shape_motion` - The motion of the shape.
+ /// * `shape` - The shape to cast.
+ /// * `max_toi` - The maximum time-of-impact that can be reported by this cast. This effectively
+ /// limits the distance traveled by the shape to `shapeVel.norm() * maxToi`.
+ /// * `groups` - The bit groups and filter associated to the shape to cast, in order to only
+ /// test on colliders with collision groups compatible with this group.
pub fn nonlinear_cast_shape(
&self,
colliders: &ColliderSet,
@@ -337,7 +404,16 @@ impl QueryPipeline {
self.quadtree.traverse_best_first(&mut visitor).map(|h| h.1)
}
- /// Gets all the colliders containing the given shape.
+ /// Retrieve all the colliders intersecting the given shape.
+ ///
+ /// # Parameters
+ /// * `colliders` - The set of colliders taking part in this pipeline.
+ /// * `shapePos` - The position of the shape to test.
+ /// * `shapeRot` - The orientation of the shape to test.
+ /// * `shape` - The shape to test.
+ /// * `groups` - The bit groups and filter associated to the shape to test, in order to only
+ /// test on colliders with collision groups compatible with this group.
+ /// * `callback` - A function called with the handles of each collider intersecting the `shape`.
pub fn intersections_with_shape<'a>(
&self,
colliders: &'a ColliderSet,