aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorSébastien Crozet <developer@crozet.re>2021-02-04 18:20:27 +0100
committerGitHub <noreply@github.com>2021-02-04 18:20:27 +0100
commita272f4ce9eb812bd14114fe95ab614bc8dddfce5 (patch)
tree216e07441b294f4424c49d92d1e74e1d94772cbb /src
parenta0230408252c9e3f06d4cee4c45831922df0143e (diff)
parent85bc81d4fce29bf628d31cb978aa482e564aab90 (diff)
downloadrapier-a272f4ce9eb812bd14114fe95ab614bc8dddfce5.tar.gz
rapier-a272f4ce9eb812bd14114fe95ab614bc8dddfce5.tar.bz2
rapier-a272f4ce9eb812bd14114fe95ab614bc8dddfce5.zip
Merge pull request #104 from EmbarkStudios/clippy-fixes
Make clippy a bit happier
Diffstat (limited to 'src')
-rw-r--r--src/dynamics/joint/joint_set.rs5
-rw-r--r--src/dynamics/rigid_body.rs2
-rw-r--r--src/dynamics/rigid_body_set.rs5
-rw-r--r--src/dynamics/solver/joint_constraint/prismatic_velocity_constraint.rs4
-rw-r--r--src/dynamics/solver/joint_constraint/prismatic_velocity_constraint_wide.rs4
-rw-r--r--src/dynamics/solver/joint_constraint/revolute_position_constraint.rs4
-rw-r--r--src/dynamics/solver/joint_constraint/revolute_velocity_constraint.rs4
-rw-r--r--src/dynamics/solver/joint_constraint/revolute_velocity_constraint_wide.rs4
-rw-r--r--src/geometry/broad_phase_multi_sap.rs6
-rw-r--r--src/geometry/collider.rs12
-rw-r--r--src/geometry/collider_set.rs5
-rw-r--r--src/geometry/interaction_graph.rs4
-rw-r--r--src/geometry/narrow_phase.rs18
-rw-r--r--src/lib.rs2
-rw-r--r--src/pipeline/physics_pipeline.rs2
15 files changed, 48 insertions, 33 deletions
diff --git a/src/dynamics/joint/joint_set.rs b/src/dynamics/joint/joint_set.rs
index a87532a..ed3e69a 100644
--- a/src/dynamics/joint/joint_set.rs
+++ b/src/dynamics/joint/joint_set.rs
@@ -55,6 +55,11 @@ impl JointSet {
self.joint_graph.graph.edges.len()
}
+ /// `true` if there are no joints in this set.
+ pub fn is_empty(&self) -> bool {
+ self.joint_graph.graph.edges.is_empty()
+ }
+
/// Retrieve the joint graph where edges are joints and nodes are rigid body handles.
pub fn joint_graph(&self) -> &InteractionGraph<RigidBodyHandle, Joint> {
&self.joint_graph
diff --git a/src/dynamics/rigid_body.rs b/src/dynamics/rigid_body.rs
index d42de30..73b8969 100644
--- a/src/dynamics/rigid_body.rs
+++ b/src/dynamics/rigid_body.rs
@@ -304,7 +304,7 @@ impl RigidBody {
}
fn integrate_velocity(&self, dt: Real) -> Isometry<Real> {
- let com = &self.position * self.mass_properties.local_com;
+ let com = self.position * self.mass_properties.local_com;
let shift = Translation::from(com.coords);
shift * Isometry::new(self.linvel * dt, self.angvel * dt) * shift.inverse()
}
diff --git a/src/dynamics/rigid_body_set.rs b/src/dynamics/rigid_body_set.rs
index 36cf4d3..79d5827 100644
--- a/src/dynamics/rigid_body_set.rs
+++ b/src/dynamics/rigid_body_set.rs
@@ -106,6 +106,11 @@ impl RigidBodySet {
self.bodies.len()
}
+ /// `true` if there are no rigid bodies in this set.
+ pub fn is_empty(&self) -> bool {
+ self.bodies.is_empty()
+ }
+
/// Is the given body handle valid?
pub fn contains(&self, handle: RigidBodyHandle) -> bool {
self.bodies.contains(handle.0)
diff --git a/src/dynamics/solver/joint_constraint/prismatic_velocity_constraint.rs b/src/dynamics/solver/joint_constraint/prismatic_velocity_constraint.rs
index d1943fc..a361a37 100644
--- a/src/dynamics/solver/joint_constraint/prismatic_velocity_constraint.rs
+++ b/src/dynamics/solver/joint_constraint/prismatic_velocity_constraint.rs
@@ -84,7 +84,7 @@ impl PrismaticVelocityConstraint {
// .into_inner();
// #[cfg(feature = "dim3")]
// let r21 = Rotation::rotation_between_axis(&axis1, &axis2)
- // .unwrap_or(Rotation::identity())
+ // .unwrap_or_else(Rotation::identity)
// .to_rotation_matrix()
// .into_inner();
// let basis2 = r21 * basis1;
@@ -380,7 +380,7 @@ impl PrismaticVelocityGroundConstraint {
// .into_inner();
// #[cfg(feature = "dim3")]
// let r21 = Rotation::rotation_between_axis(&axis1, &axis2)
- // .unwrap_or(Rotation::identity())
+ // .unwrap_or_else(Rotation::identity)
// .to_rotation_matrix()
// .into_inner();
// let basis2 = r21 * basis1;
diff --git a/src/dynamics/solver/joint_constraint/prismatic_velocity_constraint_wide.rs b/src/dynamics/solver/joint_constraint/prismatic_velocity_constraint_wide.rs
index f24cfa5..77a6fe7 100644
--- a/src/dynamics/solver/joint_constraint/prismatic_velocity_constraint_wide.rs
+++ b/src/dynamics/solver/joint_constraint/prismatic_velocity_constraint_wide.rs
@@ -124,7 +124,7 @@ impl WPrismaticVelocityConstraint {
// .into_inner();
// #[cfg(feature = "dim3")]
// let r21 = Rotation::rotation_between_axis(&axis1, &axis2)
- // .unwrap_or(Rotation::identity())
+ // .unwrap_or_else(Rotation::identity)
// .to_rotation_matrix()
// .into_inner();
// let basis2 = r21 * basis1;
@@ -483,7 +483,7 @@ impl WPrismaticVelocityGroundConstraint {
// .into_inner();
// #[cfg(feature = "dim3")]
// let r21 = Rotation::rotation_between_axis(&axis1, &axis2)
- // .unwrap_or(Rotation::identity())
+ // .unwrap_or_else(Rotation::identity)
// .to_rotation_matrix()
// .into_inner();
// let basis2 = r21 * basis1;
diff --git a/src/dynamics/solver/joint_constraint/revolute_position_constraint.rs b/src/dynamics/solver/joint_constraint/revolute_position_constraint.rs
index 19dd451..afc23f3 100644
--- a/src/dynamics/solver/joint_constraint/revolute_position_constraint.rs
+++ b/src/dynamics/solver/joint_constraint/revolute_position_constraint.rs
@@ -56,7 +56,7 @@ impl RevolutePositionConstraint {
let axis1 = position1 * self.local_axis1;
let axis2 = position2 * self.local_axis2;
let delta_rot =
- Rotation::rotation_between_axis(&axis1, &axis2).unwrap_or(Rotation::identity());
+ Rotation::rotation_between_axis(&axis1, &axis2).unwrap_or_else(Rotation::identity);
let ang_error = delta_rot.scaled_axis() * params.joint_erp;
let ang_impulse = self.ang_inv_lhs.transform_vector(ang_error);
@@ -129,7 +129,7 @@ impl RevolutePositionGroundConstraint {
let delta_rot =
Rotation::scaled_rotation_between_axis(&axis2, &self.axis1, params.joint_erp)
- .unwrap_or(Rotation::identity());
+ .unwrap_or_else(Rotation::identity);
position2.rotation = delta_rot * position2.rotation;
let anchor2 = position2 * self.local_anchor2;
diff --git a/src/dynamics/solver/joint_constraint/revolute_velocity_constraint.rs b/src/dynamics/solver/joint_constraint/revolute_velocity_constraint.rs
index 38f56d9..6270a8e 100644
--- a/src/dynamics/solver/joint_constraint/revolute_velocity_constraint.rs
+++ b/src/dynamics/solver/joint_constraint/revolute_velocity_constraint.rs
@@ -46,7 +46,7 @@ impl RevoluteVelocityConstraint {
]);
// let r21 = Rotation::rotation_between_axis(&axis1, &axis2)
- // .unwrap_or(Rotation::identity())
+ // .unwrap_or_else(Rotation::identity)
// .to_rotation_matrix()
// .into_inner();
// let basis2 = r21 * basis1;
@@ -208,7 +208,7 @@ impl RevoluteVelocityGroundConstraint {
};
// let r21 = Rotation::rotation_between_axis(&axis1, &axis2)
- // .unwrap_or(Rotation::identity())
+ // .unwrap_or_else(Rotation::identity)
// .to_rotation_matrix()
// .into_inner();
// let basis2 = /*r21 * */ basis1;
diff --git a/src/dynamics/solver/joint_constraint/revolute_velocity_constraint_wide.rs b/src/dynamics/solver/joint_constraint/revolute_velocity_constraint_wide.rs
index 822c2ac..047763d 100644
--- a/src/dynamics/solver/joint_constraint/revolute_velocity_constraint_wide.rs
+++ b/src/dynamics/solver/joint_constraint/revolute_velocity_constraint_wide.rs
@@ -73,7 +73,7 @@ impl WRevoluteVelocityConstraint {
Matrix3x2::from_columns(&[position1 * local_basis1[0], position1 * local_basis1[1]]);
// let r21 = Rotation::rotation_between_axis(&axis1, &axis2)
- // .unwrap_or(Rotation::identity())
+ // .unwrap_or_else(Rotation::identity)
// .to_rotation_matrix()
// .into_inner();
// let basis2 = r21 * basis1;
@@ -290,7 +290,7 @@ impl WRevoluteVelocityGroundConstraint {
let anchor2 = position2 * local_anchor2;
// let r21 = Rotation::rotation_between_axis(&axis1, &axis2)
- // .unwrap_or(Rotation::identity())
+ // .unwrap_or_else(Rotation::identity)
// .to_rotation_matrix()
// .into_inner();
// let basis2 = /*r21 * */ basis1;
diff --git a/src/geometry/broad_phase_multi_sap.rs b/src/geometry/broad_phase_multi_sap.rs
index b0a274d..1b780c3 100644
--- a/src/geometry/broad_phase_multi_sap.rs
+++ b/src/geometry/broad_phase_multi_sap.rs
@@ -569,16 +569,16 @@ impl BroadPhase {
self.removed_colliders = Some(colliders.removed_colliders.subscribe());
}
- let mut cursor = self.removed_colliders.take().unwrap();
+ let cursor = self.removed_colliders.take().unwrap();
for collider in colliders.removed_colliders.read(&cursor) {
self.remove_collider(collider.proxy_index);
}
- colliders.removed_colliders.ack(&mut cursor);
+ colliders.removed_colliders.ack(&cursor);
self.removed_colliders = Some(cursor);
}
- fn remove_collider<'a>(&mut self, proxy_index: usize) {
+ fn remove_collider(&mut self, proxy_index: usize) {
if proxy_index == crate::INVALID_USIZE {
// This collider has not been added to the broad-phase yet.
return;
diff --git a/src/geometry/collider.rs b/src/geometry/collider.rs
index fa2da68..ce263f8 100644
--- a/src/geometry/collider.rs
+++ b/src/geometry/collider.rs
@@ -361,14 +361,14 @@ 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))
+ SharedShape::convex_hull(points).map(Self::new)
}
/// 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))
+ SharedShape::round_convex_hull(points, border_radius).map(Self::new)
}
/// Creates a new collider builder that is a convex polygon formed by the
@@ -376,7 +376,7 @@ impl ColliderBuilder {
/// computed).
#[cfg(feature = "dim2")]
pub fn convex_polyline(points: Vec<Point<Real>>) -> Option<Self> {
- SharedShape::convex_polyline(points).map(|cp| Self::new(cp))
+ SharedShape::convex_polyline(points).map(Self::new)
}
/// Creates a new collider builder that is a round convex polygon formed by the
@@ -384,7 +384,7 @@ impl ColliderBuilder {
/// 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))
+ SharedShape::round_convex_polyline(points, border_radius).map(Self::new)
}
/// Creates a new collider builder that is a convex polyhedron formed by the
@@ -392,7 +392,7 @@ impl ColliderBuilder {
/// 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))
+ SharedShape::convex_mesh(points, indices).map(Self::new)
}
/// Creates a new collider builder that is a round convex polyhedron formed by the
@@ -404,7 +404,7 @@ impl ColliderBuilder {
indices: &[[u32; 3]],
border_radius: Real,
) -> Option<Self> {
- SharedShape::round_convex_mesh(points, indices, border_radius).map(|cp| Self::new(cp))
+ SharedShape::round_convex_mesh(points, indices, border_radius).map(Self::new)
}
/// Initializes a collider builder with a heightfield shape defined by its set of height and a scale
diff --git a/src/geometry/collider_set.rs b/src/geometry/collider_set.rs
index 3ceb297..f087bad 100644
--- a/src/geometry/collider_set.rs
+++ b/src/geometry/collider_set.rs
@@ -80,6 +80,11 @@ impl ColliderSet {
self.colliders.len()
}
+ /// `true` if there are no colliders in this set.
+ pub fn is_empty(&self) -> bool {
+ self.colliders.is_empty()
+ }
+
/// Is this collider handle valid?
pub fn contains(&self, handle: ColliderHandle) -> bool {
self.colliders.contains(handle.0)
diff --git a/src/geometry/interaction_graph.rs b/src/geometry/interaction_graph.rs
index 657050c..e2cc218 100644
--- a/src/geometry/interaction_graph.rs
+++ b/src/geometry/interaction_graph.rs
@@ -120,9 +120,9 @@ impl<N: Copy, E> InteractionGraph<N, E> {
/// All the interaction involving the collision object with graph index `id`.
pub fn interactions_with(&self, id: ColliderGraphIndex) -> impl Iterator<Item = (N, N, &E)> {
- self.graph.edges(id).filter_map(move |e| {
+ self.graph.edges(id).map(move |e| {
let endpoints = self.graph.edge_endpoints(e.id()).unwrap();
- Some((self.graph[endpoints.0], self.graph[endpoints.1], e.weight()))
+ (self.graph[endpoints.0], self.graph[endpoints.1], e.weight())
})
}
diff --git a/src/geometry/narrow_phase.rs b/src/geometry/narrow_phase.rs
index c462689..7525a68 100644
--- a/src/geometry/narrow_phase.rs
+++ b/src/geometry/narrow_phase.rs
@@ -90,10 +90,10 @@ impl NarrowPhase {
}
/// All the intersections involving the given collider.
- pub fn intersections_with<'a>(
- &'a self,
+ pub fn intersections_with(
+ &self,
collider: ColliderHandle,
- ) -> Option<impl Iterator<Item = (ColliderHandle, ColliderHandle, bool)> + 'a> {
+ ) -> Option<impl Iterator<Item = (ColliderHandle, ColliderHandle, bool)> + '_> {
let id = self.graph_indices.get(collider.0)?;
Some(
self.intersection_graph
@@ -141,9 +141,9 @@ impl NarrowPhase {
}
/// All the intersection pairs maintained by this narrow-phase.
- pub fn intersection_pairs<'a>(
- &'a self,
- ) -> impl Iterator<Item = (ColliderHandle, ColliderHandle, bool)> + 'a {
+ pub fn intersection_pairs(
+ &self,
+ ) -> impl Iterator<Item = (ColliderHandle, ColliderHandle, bool)> + '_ {
self.intersection_graph
.interactions_with_endpoints()
.map(|e| (e.0, e.1, *e.2))
@@ -161,7 +161,7 @@ impl NarrowPhase {
self.removed_colliders = Some(colliders.removed_colliders.subscribe());
}
- let mut cursor = self.removed_colliders.take().unwrap();
+ let cursor = self.removed_colliders.take().unwrap();
// TODO: avoid these hash-maps.
// They are necessary to handle the swap-remove done internally
@@ -196,11 +196,11 @@ impl NarrowPhase {
i += 1;
}
- colliders.removed_colliders.ack(&mut cursor);
+ colliders.removed_colliders.ack(&cursor);
self.removed_colliders = Some(cursor);
}
- pub(crate) fn remove_collider<'a>(
+ pub(crate) fn remove_collider(
&mut self,
intersection_graph_id: ColliderGraphIndex,
contact_graph_id: ColliderGraphIndex,
diff --git a/src/lib.rs b/src/lib.rs
index e63b0d4..564a758 100644
--- a/src/lib.rs
+++ b/src/lib.rs
@@ -126,7 +126,7 @@ 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 const VERSION: &str = env!("CARGO_PKG_VERSION");
pub mod counters;
pub mod data;
diff --git a/src/pipeline/physics_pipeline.rs b/src/pipeline/physics_pipeline.rs
index b5f123d..80d7833 100644
--- a/src/pipeline/physics_pipeline.rs
+++ b/src/pipeline/physics_pipeline.rs
@@ -162,7 +162,7 @@ impl PhysicsPipeline {
self.counters.stages.solver_time.start();
if self.solvers.len() < bodies.num_islands() {
self.solvers
- .resize_with(bodies.num_islands(), || IslandSolver::new());
+ .resize_with(bodies.num_islands(), IslandSolver::new);
}
#[cfg(not(feature = "parallel"))]