aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorSébastien Crozet <sebcrozet@dimforge.com>2024-01-27 16:49:53 +0100
committerSébastien Crozet <sebastien@crozet.re>2024-01-27 17:13:08 +0100
commitda92e5c2837b27433286cf0dd9d887fd44dda254 (patch)
tree00428ce290288f5c64e53dee13d88ffdde4df0ca /src
parentaef873f20e7a1ee66b9d4c066884fa794048587b (diff)
downloadrapier-da92e5c2837b27433286cf0dd9d887fd44dda254.tar.gz
rapier-da92e5c2837b27433286cf0dd9d887fd44dda254.tar.bz2
rapier-da92e5c2837b27433286cf0dd9d887fd44dda254.zip
Fix clippy and enable clippy on CI
Diffstat (limited to 'src')
-rw-r--r--src/control/ray_cast_vehicle_controller.rs10
-rw-r--r--src/data/arena.rs2
-rw-r--r--src/data/pubsub.rs3
-rw-r--r--src/dynamics/ccd/ccd_solver.rs45
-rw-r--r--src/dynamics/ccd/toi_entry.rs6
-rw-r--r--src/dynamics/coefficient_combine_rule.rs9
-rw-r--r--src/dynamics/integration_parameters.rs3
-rw-r--r--src/dynamics/island_manager.rs2
-rw-r--r--src/dynamics/joint/fixed_joint.rs12
-rw-r--r--src/dynamics/joint/generic_joint.rs8
-rw-r--r--src/dynamics/joint/impulse_joint/impulse_joint_set.rs6
-rw-r--r--src/dynamics/joint/motor_model.rs9
-rw-r--r--src/dynamics/joint/multibody_joint/multibody.rs21
-rw-r--r--src/dynamics/joint/multibody_joint/multibody_joint_set.rs12
-rw-r--r--src/dynamics/joint/prismatic_joint.rs12
-rw-r--r--src/dynamics/joint/revolute_joint.rs14
-rw-r--r--src/dynamics/joint/rope_joint.rs12
-rw-r--r--src/dynamics/joint/spherical_joint.rs12
-rw-r--r--src/dynamics/joint/spring_joint.rs12
-rw-r--r--src/dynamics/rigid_body.rs58
-rw-r--r--src/dynamics/rigid_body_components.rs34
-rw-r--r--src/dynamics/rigid_body_set.rs2
-rw-r--r--src/dynamics/solver/contact_constraint/contact_constraints_set.rs16
-rw-r--r--src/dynamics/solver/contact_constraint/generic_one_body_constraint.rs4
-rw-r--r--src/dynamics/solver/contact_constraint/generic_two_body_constraint.rs12
-rw-r--r--src/dynamics/solver/contact_constraint/generic_two_body_constraint_element.rs20
-rw-r--r--src/dynamics/solver/contact_constraint/one_body_constraint.rs6
-rw-r--r--src/dynamics/solver/contact_constraint/one_body_constraint_element.rs4
-rw-r--r--src/dynamics/solver/contact_constraint/one_body_constraint_simd.rs12
-rw-r--r--src/dynamics/solver/contact_constraint/two_body_constraint.rs8
-rw-r--r--src/dynamics/solver/contact_constraint/two_body_constraint_element.rs4
-rw-r--r--src/dynamics/solver/contact_constraint/two_body_constraint_simd.rs24
-rw-r--r--src/dynamics/solver/interaction_groups.rs6
-rw-r--r--src/dynamics/solver/joint_constraint/joint_constraints_set.rs12
-rw-r--r--src/dynamics/solver/joint_constraint/joint_generic_constraint_builder.rs1
-rw-r--r--src/dynamics/solver/joint_constraint/joint_velocity_constraint.rs48
-rw-r--r--src/dynamics/solver/mod.rs14
-rw-r--r--src/dynamics/solver/velocity_solver.rs6
-rw-r--r--src/geometry/broad_phase_multi_sap/broad_phase.rs5
-rw-r--r--src/geometry/broad_phase_multi_sap/mod.rs12
-rw-r--r--src/geometry/broad_phase_multi_sap/sap_axis.rs5
-rw-r--r--src/geometry/broad_phase_multi_sap/sap_proxy.rs13
-rw-r--r--src/geometry/broad_phase_multi_sap/sap_region.rs1
-rw-r--r--src/geometry/collider.rs11
-rw-r--r--src/geometry/collider_set.rs4
-rw-r--r--src/geometry/interaction_groups.rs2
-rw-r--r--src/geometry/narrow_phase.rs62
-rw-r--r--src/lib.rs3
-rw-r--r--src/pipeline/collision_pipeline.rs2
-rw-r--r--src/pipeline/debug_render_pipeline/debug_render_backend.rs10
-rw-r--r--src/pipeline/debug_render_pipeline/debug_render_pipeline.rs9
-rw-r--r--src/pipeline/debug_render_pipeline/mod.rs2
-rw-r--r--src/pipeline/debug_render_pipeline/outlines.rs1
-rw-r--r--src/pipeline/physics_hooks.rs2
-rw-r--r--src/pipeline/physics_pipeline.rs13
-rw-r--r--src/pipeline/query_pipeline.rs9
-rw-r--r--src/pipeline/user_changes.rs14
-rw-r--r--src/utils.rs2
58 files changed, 306 insertions, 377 deletions
diff --git a/src/control/ray_cast_vehicle_controller.rs b/src/control/ray_cast_vehicle_controller.rs
index 30979e1..00b11eb 100644
--- a/src/control/ray_cast_vehicle_controller.rs
+++ b/src/control/ray_cast_vehicle_controller.rs
@@ -582,7 +582,7 @@ impl DynamicRayCastVehicleController {
wheel.side_impulse = resolve_single_bilateral(
&bodies[self.chassis],
&wheel.raycast_info.contact_point_ws,
- &ground_body,
+ ground_body,
&wheel.raycast_info.contact_point_ws,
&self.axle[i],
);
@@ -664,11 +664,9 @@ impl DynamicRayCastVehicleController {
if sliding {
for wheel in &mut self.wheels {
- if wheel.side_impulse != 0.0 {
- if wheel.skid_info < 1.0 {
- wheel.forward_impulse *= wheel.skid_info;
- wheel.side_impulse *= wheel.skid_info;
- }
+ if wheel.side_impulse != 0.0 && wheel.skid_info < 1.0 {
+ wheel.forward_impulse *= wheel.skid_info;
+ wheel.side_impulse *= wheel.skid_info;
}
}
}
diff --git a/src/data/arena.rs b/src/data/arena.rs
index 3332539..57653da 100644
--- a/src/data/arena.rs
+++ b/src/data/arena.rs
@@ -269,7 +269,7 @@ impl<T> Arena<T> {
self.free_list_head = next_free;
self.len += 1;
Some(Index {
- index: i as u32,
+ index: i,
generation: self.generation,
})
}
diff --git a/src/data/pubsub.rs b/src/data/pubsub.rs
index 8c5f41c..619521e 100644
--- a/src/data/pubsub.rs
+++ b/src/data/pubsub.rs
@@ -106,8 +106,7 @@ impl<T> PubSub<T> {
/// Read the i-th message not yet read by the given subsciber.
pub fn read_ith(&self, sub: &Subscription<T>, i: usize) -> Option<&T> {
let cursor = &self.cursors[sub.id as usize];
- self.messages
- .get(cursor.next(self.deleted_messages) as usize + i)
+ self.messages.get(cursor.next(self.deleted_messages) + i)
}
/// Get the messages not yet read by the given subscriber.
diff --git a/src/dynamics/ccd/ccd_solver.rs b/src/dynamics/ccd/ccd_solver.rs
index 9b06a80..79c4495 100644
--- a/src/dynamics/ccd/ccd_solver.rs
+++ b/src/dynamics/ccd/ccd_solver.rs
@@ -52,32 +52,27 @@ impl CCDSolver {
///
/// The `impacts` should be the result of a previous call to `self.predict_next_impacts`.
pub fn clamp_motions(&self, dt: Real, bodies: &mut RigidBodySet, impacts: &PredictedImpacts) {
- match impacts {
- PredictedImpacts::Impacts(tois) => {
- for (handle, toi) in tois {
- let rb = bodies.index_mut_internal(*handle);
- let local_com = &rb.mprops.local_mprops.local_com;
-
- let min_toi = (rb.ccd.ccd_thickness
- * 0.15
- * crate::utils::inv(rb.ccd.max_point_velocity(&rb.integrated_vels)))
- .min(dt);
- // println!(
- // "Min toi: {}, Toi: {}, thick: {}, max_vel: {}",
- // min_toi,
- // toi,
- // rb.ccd.ccd_thickness,
- // rb.ccd.max_point_velocity(&rb.integrated_vels)
- // );
- let new_pos = rb.integrated_vels.integrate(
- toi.max(min_toi),
- &rb.pos.position,
- &local_com,
- );
- rb.pos.next_position = new_pos;
- }
+ if let PredictedImpacts::Impacts(tois) = impacts {
+ for (handle, toi) in tois {
+ let rb = bodies.index_mut_internal(*handle);
+ let local_com = &rb.mprops.local_mprops.local_com;
+
+ let min_toi = (rb.ccd.ccd_thickness
+ * 0.15
+ * crate::utils::inv(rb.ccd.max_point_velocity(&rb.integrated_vels)))
+ .min(dt);
+ // println!(
+ // "Min toi: {}, Toi: {}, thick: {}, max_vel: {}",
+ // min_toi,
+ // toi,
+ // rb.ccd.ccd_thickness,
+ // rb.ccd.max_point_velocity(&rb.integrated_vels)
+ // );
+ let new_pos =
+ rb.integrated_vels
+ .integrate(toi.max(min_toi), &rb.pos.position, local_com);
+ rb.pos.next_position = new_pos;
}
- _ => {}
}
}
diff --git a/src/dynamics/ccd/toi_entry.rs b/src/dynamics/ccd/toi_entry.rs
index 6f5a47d..719f3c5 100644
--- a/src/dynamics/ccd/toi_entry.rs
+++ b/src/dynamics/ccd/toi_entry.rs
@@ -169,13 +169,15 @@ impl TOIEntry {
impl PartialOrd for TOIEntry {
fn partial_cmp(&self, other: &Self) -> Option<std::cmp::Ordering> {
- (-self.toi).partial_cmp(&(-other.toi))
+ Some(self.cmp(other))
}
}
impl Ord for TOIEntry {
fn cmp(&self, other: &Self) -> std::cmp::Ordering {
- self.partial_cmp(other).unwrap()
+ (-self.toi)
+ .partial_cmp(&(-other.toi))
+ .unwrap_or(std::cmp::Ordering::Equal)
}
}
diff --git a/src/dynamics/coefficient_combine_rule.rs b/src/dynamics/coefficient_combine_rule.rs
index 1016d09..9f99b7d 100644
--- a/src/dynamics/coefficient_combine_rule.rs
+++ b/src/dynamics/coefficient_combine_rule.rs
@@ -7,10 +7,11 @@ use crate::math::Real;
/// Each collider has its combination rule of type
/// `CoefficientCombineRule`. And the rule
/// actually used is given by `max(first_combine_rule as usize, second_combine_rule as usize)`.
-#[derive(Copy, Clone, Debug, PartialEq, Eq)]
+#[derive(Default, Copy, Clone, Debug, PartialEq, Eq)]
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
pub enum CoefficientCombineRule {
/// The two coefficients are averaged.
+ #[default]
Average = 0,
/// The smallest coefficient is chosen.
Min,
@@ -20,12 +21,6 @@ pub enum CoefficientCombineRule {
Max,
}
-impl Default for CoefficientCombineRule {
- fn default() -> Self {
- CoefficientCombineRule::Average
- }
-}
-
impl CoefficientCombineRule {
pub(crate) fn combine(coeff1: Real, coeff2: Real, rule_value1: u8, rule_value2: u8) -> Real {
let effective_rule = rule_value1.max(rule_value2);
diff --git a/src/dynamics/integration_parameters.rs b/src/dynamics/integration_parameters.rs
index bcb823b..13b3fde 100644
--- a/src/dynamics/integration_parameters.rs
+++ b/src/dynamics/integration_parameters.rs
@@ -71,8 +71,7 @@ impl IntegrationParameters {
/// NOTE: this resets [`Self::erp`], [`Self::damping_ratio`], [`Self::joint_erp`],
/// [`Self::joint_damping_ratio`] to their former default values.
pub fn switch_to_standard_pgs_solver(&mut self) {
- self.num_internal_pgs_iterations =
- self.num_solver_iterations.get() * self.num_internal_pgs_iterations;
+ self.num_internal_pgs_iterations *= self.num_solver_iterations.get();
self.num_solver_iterations = NonZeroUsize::new(1).unwrap();
self.erp = 0.8;
self.damping_ratio = 0.25;
diff --git a/src/dynamics/island_manager.rs b/src/dynamics/island_manager.rs
index 92b9a3e..8f18941 100644
--- a/src/dynamics/island_manager.rs
+++ b/src/dynamics/island_manager.rs
@@ -134,7 +134,7 @@ impl IslandManager {
}
#[inline(always)]
- pub(crate) fn iter_active_bodies<'a>(&'a self) -> impl Iterator<Item = RigidBodyHandle> + 'a {
+ pub(crate) fn iter_active_bodies(&self) -> impl Iterator<Item = RigidBodyHandle> + '_ {
self.active_dynamic_set
.iter()
.copied()
diff --git a/src/dynamics/joint/fixed_joint.rs b/src/dynamics/joint/fixed_joint.rs
index 75c8228..2bb2f64 100644
--- a/src/dynamics/joint/fixed_joint.rs
+++ b/src/dynamics/joint/fixed_joint.rs
@@ -84,9 +84,9 @@ impl FixedJoint {
}
}
-impl Into<GenericJoint> for FixedJoint {
- fn into(self) -> GenericJoint {
- self.data
+impl From<FixedJoint> for GenericJoint {
+ fn from(val: FixedJoint) -> GenericJoint {
+ val.data
}
}
@@ -143,8 +143,8 @@ impl FixedJointBuilder {
}
}
-impl Into<GenericJoint> for FixedJointBuilder {
- fn into(self) -> GenericJoint {
- self.0.into()
+impl From<FixedJointBuilder> for GenericJoint {
+ fn from(val: FixedJointBuilder) -> GenericJoint {
+ val.0.into()
}
}
diff --git a/src/dynamics/joint/generic_joint.rs b/src/dynamics/joint/generic_joint.rs
index 83e27be..76a7fe1 100644
--- a/src/dynamics/joint/generic_joint.rs
+++ b/src/dynamics/joint/generic_joint.rs
@@ -1,3 +1,5 @@
+#![allow(clippy::bad_bit_mask)] // Clippy will complain about the bitmasks due to JointAxesMask::FREE_FIXED_AXES being 0.
+
use crate::dynamics::solver::MotorParameters;
use crate::dynamics::{FixedJoint, MotorModel, PrismaticJoint, RevoluteJoint, RopeJoint};
use crate::math::{Isometry, Point, Real, Rotation, UnitVector, Vector, SPATIAL_DIM};
@@ -704,8 +706,8 @@ impl GenericJointBuilder {
}
}
-impl Into<GenericJoint> for GenericJointBuilder {
- fn into(self) -> GenericJoint {
- self.0
+impl From<GenericJointBuilder> for GenericJoint {
+ fn from(val: GenericJointBuilder) -> GenericJoint {
+ val.0
}
}
diff --git a/src/dynamics/joint/impulse_joint/impulse_joint_set.rs b/src/dynamics/joint/impulse_joint/impulse_joint_set.rs
index 67f8949..3f9835e 100644
--- a/src/dynamics/joint/impulse_joint/impulse_joint_set.rs
+++ b/src/dynamics/joint/impulse_joint/impulse_joint_set.rs
@@ -105,8 +105,8 @@ impl ImpulseJointSet {
}
/// Iterates through all the impulse joints attached to the given rigid-body.
- pub fn map_attached_joints_mut<'a>(
- &'a mut self,
+ pub fn map_attached_joints_mut(
+ &mut self,
body: RigidBodyHandle,
mut f: impl FnMut(RigidBodyHandle, RigidBodyHandle, ImpulseJointHandle, &mut ImpulseJoint),
) {
@@ -282,7 +282,7 @@ impl ImpulseJointSet {
&self,
islands: &IslandManager,
bodies: &RigidBodySet,
- out: &mut Vec<Vec<JointIndex>>,
+ out: &mut [Vec<JointIndex>],
) {
for out_island in &mut out[..islands.num_islands()] {
out_island.clear();
diff --git a/src/dynamics/joint/motor_model.rs b/src/dynamics/joint/motor_model.rs
index e8ffffa..74b8dd3 100644
--- a/src/dynamics/joint/motor_model.rs
+++ b/src/dynamics/joint/motor_model.rs
@@ -1,23 +1,18 @@
use crate::math::Real;
/// The spring-like model used for constraints resolution.
-#[derive(Copy, Clone, Debug, PartialEq, Eq)]
+#[derive(Default, Copy, Clone, Debug, PartialEq, Eq)]
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
pub enum MotorModel {
/// The solved spring-like equation is:
/// `acceleration = stiffness * (pos - target_pos) + damping * (vel - target_vel)`
+ #[default]
AccelerationBased,
/// The solved spring-like equation is:
/// `force = stiffness * (pos - target_pos) + damping * (vel - target_vel)`
ForceBased,
}
-impl Default for MotorModel {
- fn default() -> Self {
- MotorModel::AccelerationBased
- }
-}
-
impl MotorModel {
/// Combines the coefficients used for solving the spring equation.
///
diff --git a/src/dynamics/joint/multibody_joint/multibody.rs b/src/dynamics/joint/multibody_joint/multibody.rs
index c65a6ff..617d447 100644
--- a/src/dynamics/joint/multibody_joint/multibody.rs
+++ b/src/dynamics/joint/multibody_joint/multibody.rs
@@ -127,8 +127,9 @@ impl Multibody {
let mut link_id2new_id = vec![usize::MAX; self.links.len()];
for (i, mut link) in self.links.0.into_iter().enumerate() {
- let is_new_root = (!joint_only && (i == 0 || link.parent_internal_id == to_remove))
- || (joint_only && (i == 0 || i == to_remove));
+ let is_new_root = i == 0
+ || !joint_only && link.parent_internal_id == to_remove
+ || joint_only && i == to_remove;
if !joint_only && i == to_remove {
continue;
@@ -492,7 +493,7 @@ impl Multibody {
parent_to_world = parent_link.local_to_world;
let (link_j, parent_j) = self.body_jacobians.index_mut_const(i, parent_id);
- link_j.copy_from(&parent_j);
+ link_j.copy_from(parent_j);
{
let mut link_j_v = link_j.fixed_rows_mut::<DIM>(0);
@@ -602,12 +603,12 @@ impl Multibody {
let (coriolis_v, parent_coriolis_v) = self.coriolis_v.index_mut2(i, parent_id);
let (coriolis_w, parent_coriolis_w) = self.coriolis_w.index_mut2(i, parent_id);
- coriolis_v.copy_from(&parent_coriolis_v);
- coriolis_w.copy_from(&parent_coriolis_w);
+ coriolis_v.copy_from(parent_coriolis_v);
+ coriolis_w.copy_from(parent_coriolis_w);
// [c1 - c0].gcross() * (JDot + JDot/u * qdot)"
let shift_cross_tr = link.shift02.gcross_matrix_tr();
- coriolis_v.gemm(1.0, &shift_cross_tr, &parent_coriolis_w, 1.0);
+ coriolis_v.gemm(1.0, &shift_cross_tr, parent_coriolis_w, 1.0);
// JDot (but the 2.0 originates from the sum of two identical terms in JDot and JDot/u * gdot)
let dvel_cross = (rb.vels.angvel.gcross(link.shift02)
@@ -663,7 +664,7 @@ impl Multibody {
{
// [c3 - c2].gcross() * (JDot + JDot/u * qdot)
let shift_cross_tr = link.shift23.gcross_matrix_tr();
- coriolis_v.gemm(1.0, &shift_cross_tr, &coriolis_w, 1.0);
+ coriolis_v.gemm(1.0, &shift_cross_tr, coriolis_w, 1.0);
// JDot
let dvel_cross = rb.vels.angvel.gcross(link.shift23).gcross_matrix_tr();
@@ -696,16 +697,16 @@ impl Multibody {
{
let mut i_coriolis_dt_w = self.i_coriolis_dt.fixed_rows_mut::<ANG_DIM>(DIM);
// NOTE: this is just an axpy, but on row columns.
- i_coriolis_dt_w.zip_apply(&coriolis_w, |o, x| *o = x * dt * rb_inertia);
+ i_coriolis_dt_w.zip_apply(coriolis_w, |o, x| *o = x * dt * rb_inertia);
}
#[cfg(feature = "dim3")]
{
let mut i_coriolis_dt_w = self.i_coriolis_dt.fixed_rows_mut::<ANG_DIM>(DIM);
- i_coriolis_dt_w.gemm(dt, &rb_inertia, &coriolis_w, 0.0);
+ i_coriolis_dt_w.gemm(dt, &rb_inertia, coriolis_w, 0.0);
}
self.acc_augmented_mass
- .gemm_tr(1.0, &rb_j, &self.i_coriolis_dt, 1.0);
+ .gemm_tr(1.0, rb_j, &self.i_coriolis_dt, 1.0);
}
/*
diff --git a/src/dynamics/joint/multibody_joint/multibody_joint_set.rs b/src/dynamics/joint/multibody_joint/multibody_joint_set.rs
index 748de3b..fa0ffdb 100644
--- a/src/dynamics/joint/multibody_joint/multibody_joint_set.rs
+++ b/src/dynamics/joint/multibody_joint/multibody_joint_set.rs
@@ -393,10 +393,10 @@ impl MultibodyJointSet {
/// Iterate through the handles of all the rigid-bodies attached to this rigid-body
/// by a multibody_joint.
- pub fn attached_bodies<'a>(
- &'a self,
+ pub fn attached_bodies(
+ &self,
body: RigidBodyHandle,
- ) -> impl Iterator<Item = RigidBodyHandle> + 'a {
+ ) -> impl Iterator<Item = RigidBodyHandle> + '_ {
self.rb2mb
.get(body.0)
.into_iter()
@@ -406,10 +406,10 @@ impl MultibodyJointSet {
/// Iterate through the handles of all the rigid-bodies attached to this rigid-body
/// by an enabled multibody_joint.
- pub fn bodies_attached_with_enabled_joint<'a>(
- &'a self,
+ pub fn bodies_attached_with_enabled_joint(
+ &self,
body: RigidBodyHandle,
- ) -> impl Iterator<Item = RigidBodyHandle> + 'a {
+ ) -> impl Iterator<Item = RigidBodyHandle> + '_ {
self.attached_bodies(body).filter(move |other| {
if let Some((_, _, link)) = self.joint_between(body, *other) {
link.joint.data.is_enabled()
diff --git a/src/dynamics/joint/prismatic_joint.rs b/src/dynamics/joint/prismatic_joint.rs
index 1e7a016..d0f3a7d 100644
--- a/src/dynamics/joint/prismatic_joint.rs
+++ b/src/dynamics/joint/prismatic_joint.rs
@@ -152,9 +152,9 @@ impl PrismaticJoint {
}
}
-impl Into<GenericJoint> for PrismaticJoint {
- fn into(self) -> GenericJoint {
- self.data
+impl From<PrismaticJoint> for GenericJoint {
+ fn from(val: PrismaticJoint) -> GenericJoint {
+ val.data
}
}
@@ -263,8 +263,8 @@ impl PrismaticJointBuilder {
}
}
-impl Into<GenericJoint> for PrismaticJointBuilder {
- fn into(self) -> GenericJoint {
- self.0.into()
+impl From<PrismaticJointBuilder> for GenericJoint {
+ fn from(val: PrismaticJointBuilder) -> GenericJoint {
+ val.0.into()
}
}
diff --git a/src/dynamics/joint/revolute_joint.rs b/src/dynamics/joint/revolute_joint.rs
index 9400ba8..ba27351 100644
--- a/src/dynamics/joint/revolute_joint.rs
+++ b/src/dynamics/joint/revolute_joint.rs
@@ -17,6 +17,7 @@ pub struct RevoluteJoint {
impl RevoluteJoint {
/// Creates a new revolute joint allowing only relative rotations.
#[cfg(feature = "dim2")]
+ #[allow(clippy::new_without_default)] // For symmetry with 3D which can’t have a Default impl.
pub fn new() -> Self {
let data = GenericJointBuilder::new(JointAxesMask::LOCKED_REVOLUTE_AXES);
Self { data: data.build() }
@@ -137,9 +138,9 @@ impl RevoluteJoint {
}
}
-impl Into<GenericJoint> for RevoluteJoint {
- fn into(self) -> GenericJoint {
- self.data
+impl From<RevoluteJoint> for GenericJoint {
+ fn from(val: RevoluteJoint) -> GenericJoint {
+ val.data
}
}
@@ -153,6 +154,7 @@ pub struct RevoluteJointBuilder(pub RevoluteJoint);
impl RevoluteJointBuilder {
/// Creates a new revolute joint builder.
#[cfg(feature = "dim2")]
+ #[allow(clippy::new_without_default)] // For symmetry with 3D which can’t have a Default impl.
pub fn new() -> Self {
Self(RevoluteJoint::new())
}
@@