Fix clippy and enable clippy on CI
This commit is contained in:
committed by
Sébastien Crozet
parent
aef873f20e
commit
da92e5c283
@@ -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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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,
|
||||
})
|
||||
}
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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;
|
||||
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;
|
||||
}
|
||||
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;
|
||||
}
|
||||
_ => {}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -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)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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()
|
||||
|
||||
@@ -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()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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();
|
||||
|
||||
@@ -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.
|
||||
///
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
@@ -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()
|
||||
|
||||
@@ -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()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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())
|
||||
}
|
||||
@@ -241,8 +243,8 @@ impl RevoluteJointBuilder {
|
||||
}
|
||||
}
|
||||
|
||||
impl Into<GenericJoint> for RevoluteJointBuilder {
|
||||
fn into(self) -> GenericJoint {
|
||||
self.0.into()
|
||||
impl From<RevoluteJointBuilder> for GenericJoint {
|
||||
fn from(val: RevoluteJointBuilder) -> GenericJoint {
|
||||
val.0.into()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -134,9 +134,9 @@ impl RopeJoint {
|
||||
}
|
||||
}
|
||||
|
||||
impl Into<GenericJoint> for RopeJoint {
|
||||
fn into(self) -> GenericJoint {
|
||||
self.data
|
||||
impl From<RopeJoint> for GenericJoint {
|
||||
fn from(val: RopeJoint) -> GenericJoint {
|
||||
val.data
|
||||
}
|
||||
}
|
||||
|
||||
@@ -231,8 +231,8 @@ impl RopeJointBuilder {
|
||||
}
|
||||
}
|
||||
|
||||
impl Into<GenericJoint> for RopeJointBuilder {
|
||||
fn into(self) -> GenericJoint {
|
||||
self.0.into()
|
||||
impl From<RopeJointBuilder> for GenericJoint {
|
||||
fn from(val: RopeJointBuilder) -> GenericJoint {
|
||||
val.0.into()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -164,9 +164,9 @@ impl SphericalJoint {
|
||||
}
|
||||
}
|
||||
|
||||
impl Into<GenericJoint> for SphericalJoint {
|
||||
fn into(self) -> GenericJoint {
|
||||
self.data
|
||||
impl From<SphericalJoint> for GenericJoint {
|
||||
fn from(val: SphericalJoint) -> GenericJoint {
|
||||
val.data
|
||||
}
|
||||
}
|
||||
|
||||
@@ -288,8 +288,8 @@ impl SphericalJointBuilder {
|
||||
}
|
||||
}
|
||||
|
||||
impl Into<GenericJoint> for SphericalJointBuilder {
|
||||
fn into(self) -> GenericJoint {
|
||||
self.0.into()
|
||||
impl From<SphericalJointBuilder> for GenericJoint {
|
||||
fn from(val: SphericalJointBuilder) -> GenericJoint {
|
||||
val.0.into()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -94,9 +94,9 @@ impl SpringJoint {
|
||||
// }
|
||||
}
|
||||
|
||||
impl Into<GenericJoint> for SpringJoint {
|
||||
fn into(self) -> GenericJoint {
|
||||
self.data
|
||||
impl From<SpringJoint> for GenericJoint {
|
||||
fn from(val: SpringJoint) -> GenericJoint {
|
||||
val.data
|
||||
}
|
||||
}
|
||||
|
||||
@@ -165,8 +165,8 @@ impl SpringJointBuilder {
|
||||
}
|
||||
}
|
||||
|
||||
impl Into<GenericJoint> for SpringJointBuilder {
|
||||
fn into(self) -> GenericJoint {
|
||||
self.0.into()
|
||||
impl From<SpringJointBuilder> for GenericJoint {
|
||||
fn from(val: SpringJointBuilder) -> GenericJoint {
|
||||
val.0.into()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -300,16 +300,16 @@ impl RigidBody {
|
||||
wake_up: bool,
|
||||
) {
|
||||
#[cfg(feature = "dim2")]
|
||||
if self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_X) == !allow_translation_x
|
||||
&& self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_Y) == !allow_translation_y
|
||||
if self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_X) != allow_translation_x
|
||||
&& self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_Y) != allow_translation_y
|
||||
{
|
||||
// Nothing to change.
|
||||
return;
|
||||
}
|
||||
#[cfg(feature = "dim3")]
|
||||
if self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_X) == !allow_translation_x
|
||||
&& self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_Y) == !allow_translation_y
|
||||
&& self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_Z) == !allow_translation_z
|
||||
if self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_X) != allow_translation_x
|
||||
&& self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_Y) != allow_translation_y
|
||||
&& self.mprops.flags.contains(LockedAxes::TRANSLATION_LOCKED_Z) != allow_translation_z
|
||||
{
|
||||
// Nothing to change.
|
||||
return;
|
||||
@@ -850,13 +850,11 @@ impl RigidBody {
|
||||
///
|
||||
/// This does nothing on non-dynamic bodies.
|
||||
pub fn add_force(&mut self, force: Vector<Real>, wake_up: bool) {
|
||||
if !force.is_zero() {
|
||||
if self.body_type == RigidBodyType::Dynamic {
|
||||
self.forces.user_force += force;
|
||||
if !force.is_zero() && self.body_type == RigidBodyType::Dynamic {
|
||||
self.forces.user_force += force;
|
||||
|
||||
if wake_up {
|
||||
self.wake_up(true);
|
||||
}
|
||||
if wake_up {
|
||||
self.wake_up(true);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -866,13 +864,11 @@ impl RigidBody {
|
||||
/// This does nothing on non-dynamic bodies.
|
||||
#[cfg(feature = "dim2")]
|
||||
pub fn add_torque(&mut self, torque: Real, wake_up: bool) {
|
||||
if !torque.is_zero() {
|
||||
if self.body_type == RigidBodyType::Dynamic {
|
||||
self.forces.user_torque += torque;
|
||||
if !torque.is_zero() && self.body_type == RigidBodyType::Dynamic {
|
||||
self.forces.user_torque += torque;
|
||||
|
||||
if wake_up {
|
||||
self.wake_up(true);
|
||||
}
|
||||
if wake_up {
|
||||
self.wake_up(true);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -882,13 +878,11 @@ impl RigidBody {
|
||||
/// This does nothing on non-dynamic bodies.
|
||||
#[cfg(feature = "dim3")]
|
||||
pub fn add_torque(&mut self, torque: Vector<Real>, wake_up: bool) {
|
||||
if !torque.is_zero() {
|
||||
if self.body_type == RigidBodyType::Dynamic {
|
||||
self.forces.user_torque += torque;
|
||||
if !torque.is_zero() && self.body_type == RigidBodyType::Dynamic {
|
||||
self.forces.user_torque += torque;
|
||||
|
||||
if wake_up {
|
||||
self.wake_up(true);
|
||||
}
|
||||
if wake_up {
|
||||
self.wake_up(true);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -897,14 +891,12 @@ impl RigidBody {
|
||||
///
|
||||
/// This does nothing on non-dynamic bodies.
|
||||
pub fn add_force_at_point(&mut self, force: Vector<Real>, point: Point<Real>, wake_up: bool) {
|
||||
if !force.is_zero() {
|
||||
if self.body_type == RigidBodyType::Dynamic {
|
||||
self.forces.user_force += force;
|
||||
self.forces.user_torque += (point - self.mprops.world_com).gcross(force);
|
||||
if !force.is_zero() && self.body_type == RigidBodyType::Dynamic {
|
||||
self.forces.user_force += force;
|
||||
self.forces.user_torque += (point - self.mprops.world_com).gcross(force);
|
||||
|
||||
if wake_up {
|
||||
self.wake_up(true);
|
||||
}
|
||||
if wake_up {
|
||||
self.wake_up(true);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1379,8 +1371,8 @@ impl RigidBodyBuilder {
|
||||
}
|
||||
}
|
||||
|
||||
impl Into<RigidBody> for RigidBodyBuilder {
|
||||
fn into(self) -> RigidBody {
|
||||
self.build()
|
||||
impl From<RigidBodyBuilder> for RigidBody {
|
||||
fn from(val: RigidBodyBuilder) -> RigidBody {
|
||||
val.build()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -399,7 +399,7 @@ impl RigidBodyMassProps {
|
||||
|
||||
/// 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.local_mprops.world_com(&position);
|
||||
self.world_com = self.local_mprops.world_com(position);
|
||||
self.effective_inv_mass = Vector::repeat(self.local_mprops.inv_mass);
|
||||
self.effective_world_inv_inertia_sqrt =
|
||||
self.local_mprops.world_inv_inertia_sqrt(&position.rotation);
|
||||
@@ -707,7 +707,6 @@ impl std::ops::Add<RigidBodyVelocity> for RigidBodyVelocity {
|
||||
}
|
||||
|
||||
impl std::ops::AddAssign<RigidBodyVelocity> for RigidBodyVelocity {
|
||||
#[must_use]
|
||||
fn add_assign(&mut self, rhs: Self) {
|
||||
self.linvel += rhs.linvel;
|
||||
self.angvel += rhs.angvel;
|
||||
@@ -788,7 +787,7 @@ impl RigidBodyForces {
|
||||
gravity: &Vector<Real>,
|
||||
mass: &Vector<Real>,
|
||||
) {
|
||||
self.force = self.user_force + gravity.component_mul(&mass) * self.gravity_scale;
|
||||
self.force = self.user_force + gravity.component_mul(mass) * self.gravity_scale;
|
||||
self.torque = self.user_torque;
|
||||
}
|
||||
|
||||
@@ -877,7 +876,7 @@ impl RigidBodyCcd {
|
||||
}
|
||||
|
||||
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
|
||||
#[derive(Clone, Debug, Copy, PartialEq, Eq, Hash)]
|
||||
#[derive(Default, Clone, Debug, Copy, PartialEq, Eq, Hash)]
|
||||
/// Internal identifiers used by the physics engine.
|
||||
pub struct RigidBodyIds {
|
||||
pub(crate) active_island_id: usize,
|
||||
@@ -886,19 +885,8 @@ pub struct RigidBodyIds {
|
||||
pub(crate) active_set_timestamp: u32,
|
||||
}
|
||||
|
||||
impl Default for RigidBodyIds {
|
||||
fn default() -> Self {
|
||||
Self {
|
||||
active_island_id: 0,
|
||||
active_set_id: 0,
|
||||
active_set_offset: 0,
|
||||
active_set_timestamp: 0,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
|
||||
#[derive(Clone, Debug, PartialEq, Eq)]
|
||||
#[derive(Default, Clone, Debug, PartialEq, Eq)]
|
||||
/// The set of colliders attached to this rigid-bodies.
|
||||
///
|
||||
/// This should not be modified manually unless you really know what
|
||||
@@ -906,12 +894,6 @@ impl Default for RigidBodyIds {
|
||||
/// to a game engine using its component-based interface).
|
||||
pub struct RigidBodyColliders(pub Vec<ColliderHandle>);
|
||||
|
||||
impl Default for RigidBodyColliders {
|
||||
fn default() -> Self {
|
||||
Self(vec![])
|
||||
}
|
||||
}
|
||||
|
||||
impl RigidBodyColliders {
|
||||
/// Detach a collider from this rigid-body.
|
||||
pub fn detach_collider(
|
||||
@@ -987,16 +969,10 @@ impl RigidBodyColliders {
|
||||
}
|
||||
|
||||
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
|
||||
#[derive(Clone, Debug, Copy, PartialEq, Eq, PartialOrd, Ord, Hash)]
|
||||
#[derive(Default, Clone, Debug, Copy, PartialEq, Eq, PartialOrd, Ord, Hash)]
|
||||
/// The dominance groups of a rigid-body.
|
||||
pub struct RigidBodyDominance(pub i8);
|
||||
|
||||
impl Default for RigidBodyDominance {
|
||||
fn default() -> Self {
|
||||
RigidBodyDominance(0)
|
||||
}
|
||||
}
|
||||
|
||||
impl RigidBodyDominance {
|
||||
/// The actual dominance group of this rigid-body, after taking into account its type.
|
||||
pub fn effective_group(&self, status: &RigidBodyType) -> i16 {
|
||||
|
||||
@@ -44,7 +44,7 @@ impl RigidBodySet {
|
||||
}
|
||||
|
||||
pub(crate) fn take_modified(&mut self) -> Vec<RigidBodyHandle> {
|
||||
std::mem::replace(&mut self.modified_bodies, vec![])
|
||||
std::mem::take(&mut self.modified_bodies)
|
||||
}
|
||||
|
||||
/// The number of rigid bodies on this set.
|
||||
|
||||
@@ -192,7 +192,7 @@ impl ContactConstraintsSet {
|
||||
.interaction_groups
|
||||
.simd_interactions
|
||||
.chunks_exact(SIMD_WIDTH)
|
||||
.map(|i| ConstraintsCounts::from_contacts(&manifolds_all[i[0]]).num_constraints)
|
||||
.map(|i| ConstraintsCounts::from_contacts(manifolds_all[i[0]]).num_constraints)
|
||||
.sum();
|
||||
|
||||
unsafe {
|
||||
@@ -211,7 +211,7 @@ impl ContactConstraintsSet {
|
||||
.chunks_exact(SIMD_WIDTH)
|
||||
{
|
||||
let num_to_add =
|
||||
ConstraintsCounts::from_contacts(&manifolds_all[manifolds_i[0]]).num_constraints;
|
||||
ConstraintsCounts::from_contacts(manifolds_all[manifolds_i[0]]).num_constraints;
|
||||
let manifold_id = gather![|ii| manifolds_i[ii]];
|
||||
let manifolds = gather![|ii| &*manifolds_all[manifolds_i[ii]]];
|
||||
|
||||
@@ -238,7 +238,7 @@ impl ContactConstraintsSet {
|
||||
.interaction_groups
|
||||
.nongrouped_interactions
|
||||
.iter()
|
||||
.map(|i| ConstraintsCounts::from_contacts(&manifolds_all[*i]).num_constraints)
|
||||
.map(|i| ConstraintsCounts::from_contacts(manifolds_all[*i]).num_constraints)
|
||||
.sum();
|
||||
|
||||
unsafe {
|
||||
@@ -278,7 +278,7 @@ impl ContactConstraintsSet {
|
||||
let total_num_constraints = self
|
||||
.generic_two_body_interactions
|
||||
.iter()
|
||||
.map(|i| ConstraintsCounts::from_contacts(&manifolds_all[*i]).num_constraints)
|
||||
.map(|i| ConstraintsCounts::from_contacts(manifolds_all[*i]).num_constraints)
|
||||
.sum();
|
||||
|
||||
self.generic_velocity_constraints_builder.resize(
|
||||
@@ -321,7 +321,7 @@ impl ContactConstraintsSet {
|
||||
let total_num_constraints = self
|
||||
.generic_one_body_interactions
|
||||
.iter()
|
||||
.map(|i| ConstraintsCounts::from_contacts(&manifolds_all[*i]).num_constraints)
|
||||
.map(|i| ConstraintsCounts::from_contacts(manifolds_all[*i]).num_constraints)
|
||||
.sum();
|
||||
self.generic_velocity_one_body_constraints_builder.resize(
|
||||
total_num_constraints,
|
||||
@@ -362,7 +362,7 @@ impl ContactConstraintsSet {
|
||||
.one_body_interaction_groups
|
||||
.simd_interactions
|
||||
.chunks_exact(SIMD_WIDTH)
|
||||
.map(|i| ConstraintsCounts::from_contacts(&manifolds_all[i[0]]).num_constraints)
|
||||
.map(|i| ConstraintsCounts::from_contacts(manifolds_all[i[0]]).num_constraints)
|
||||
.sum();
|
||||
|
||||
unsafe {
|
||||
@@ -384,7 +384,7 @@ impl ContactConstraintsSet {
|
||||
.chunks_exact(SIMD_WIDTH)
|
||||
{
|
||||
let num_to_add =
|
||||
ConstraintsCounts::from_contacts(&manifolds_all[manifolds_i[0]]).num_constraints;
|
||||
ConstraintsCounts::from_contacts(manifolds_all[manifolds_i[0]]).num_constraints;
|
||||
let manifold_id = gather![|ii| manifolds_i[ii]];
|
||||
let manifolds = gather![|ii| &*manifolds_all[manifolds_i[ii]]];
|
||||
SimdOneBodyConstraintBuilder::generate(
|
||||
@@ -408,7 +408,7 @@ impl ContactConstraintsSet {
|
||||
.one_body_interaction_groups
|
||||
.nongrouped_interactions
|
||||
.iter()
|
||||
.map(|i| ConstraintsCounts::from_contacts(&manifolds_all[*i]).num_constraints)
|
||||
.map(|i| ConstraintsCounts::from_contacts(manifolds_all[*i]).num_constraints)
|
||||
.sum();
|
||||
|
||||
unsafe {
|
||||
|
||||
@@ -59,7 +59,7 @@ impl GenericOneBodyConstraintBuilder {
|
||||
|
||||
let rb1 = handle1
|
||||
.map(|h| SolverBody::from(&bodies[h]))
|
||||
.unwrap_or_else(SolverBody::default);
|
||||
.unwrap_or_default();
|
||||
|
||||
let rb2 = &bodies[handle2.unwrap()];
|
||||
let (vels2, mprops2) = (&rb2.vels, &rb2.mprops);
|
||||
@@ -265,7 +265,7 @@ impl GenericOneBodyConstraint {
|
||||
solve_restitution: bool,
|
||||
solve_friction: bool,
|
||||
) {
|
||||
let solver_vel2 = self.inner.solver_vel2 as usize;
|
||||
let solver_vel2 = self.inner.solver_vel2;
|
||||
|
||||
let elements = &mut self.inner.elements[..self.inner.num_contacts as usize];
|
||||
OneBodyConstraintElement::generic_solve_group(
|
||||
|
||||
@@ -382,15 +382,15 @@ impl GenericTwoBodyConstraint {
|
||||
solve_friction: bool,
|
||||
) {
|
||||
let mut solver_vel1 = if self.generic_constraint_mask & 0b01 == 0 {
|
||||
GenericRhs::SolverVel(solver_vels[self.inner.solver_vel1 as usize])
|
||||
GenericRhs::SolverVel(solver_vels[self.inner.solver_vel1])
|
||||
} else {
|
||||
GenericRhs::GenericId(self.inner.solver_vel1 as usize)
|
||||
GenericRhs::GenericId(self.inner.solver_vel1)
|
||||
};
|
||||
|
||||
let mut solver_vel2 = if self.generic_constraint_mask & 0b10 == 0 {
|
||||
GenericRhs::SolverVel(solver_vels[self.inner.solver_vel2 as usize])
|
||||
GenericRhs::SolverVel(solver_vels[self.inner.solver_vel2])
|
||||
} else {
|
||||
GenericRhs::GenericId(self.inner.solver_vel2 as usize)
|
||||
GenericRhs::GenericId(self.inner.solver_vel2)
|
||||
};
|
||||
|
||||
let elements = &mut self.inner.elements[..self.inner.num_contacts as usize];
|
||||
@@ -415,11 +415,11 @@ impl GenericTwoBodyConstraint {
|
||||
);
|
||||
|
||||
if let GenericRhs::SolverVel(solver_vel1) = solver_vel1 {
|
||||
solver_vels[self.inner.solver_vel1 as usize] = solver_vel1;
|
||||
solver_vels[self.inner.solver_vel1] = solver_vel1;
|
||||
}
|
||||
|
||||
if let GenericRhs::SolverVel(solver_vel2) = solver_vel2 {
|
||||
solver_vels[self.inner.solver_vel2 as usize] = solver_vel2;
|
||||
solver_vels[self.inner.solver_vel2] = solver_vel2;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -114,7 +114,7 @@ impl TwoBodyConstraintTangentPart<Real> {
|
||||
j_id1,
|
||||
ndofs1,
|
||||
jacobians,
|
||||
&tangents1[0],
|
||||
tangents1[0],
|
||||
&self.gcross1[0],
|
||||
solver_vels,
|
||||
) + solver_vel2.dvel(
|
||||
@@ -135,7 +135,7 @@ impl TwoBodyConstraintTangentPart<Real> {
|
||||
ndofs1,
|
||||
dlambda,
|
||||
jacobians,
|
||||
&tangents1[0],
|
||||
tangents1[0],
|
||||
&self.gcross1[0],
|
||||
solver_vels,
|
||||
im1,
|
||||
@@ -158,7 +158,7 @@ impl TwoBodyConstraintTangentPart<Real> {
|
||||
j_id1,
|
||||
ndofs1,
|
||||
jacobians,
|
||||
&tangents1[0],
|
||||
tangents1[0],
|
||||
&self.gcross1[0],
|
||||
solver_vels,
|
||||
) + solver_vel2.dvel(
|
||||
@@ -173,7 +173,7 @@ impl TwoBodyConstraintTangentPart<Real> {
|
||||
j_id1 + j_step,
|
||||
ndofs1,
|
||||
jacobians,
|
||||
&tangents1[1],
|
||||
tangents1[1],
|
||||
&self.gcross1[1],
|
||||
solver_vels,
|
||||
) + solver_vel2.dvel(
|
||||
@@ -199,7 +199,7 @@ impl TwoBodyConstraintTangentPart<Real> {
|
||||
ndofs1,
|
||||
dlambda[0],
|
||||
jacobians,
|
||||
&tangents1[0],
|
||||
tangents1[0],
|
||||
&self.gcross1[0],
|
||||
solver_vels,
|
||||
im1,
|
||||
@@ -209,7 +209,7 @@ impl TwoBodyConstraintTangentPart<Real> {
|
||||
ndofs1,
|
||||
dlambda[1],
|
||||
jacobians,
|
||||
&tangents1[1],
|
||||
tangents1[1],
|
||||
&self.gcross1[1],
|
||||
solver_vels,
|
||||
im1,
|
||||
@@ -258,7 +258,7 @@ impl TwoBodyConstraintNormalPart<Real> {
|
||||
let j_id1 = j_id1(j_id, ndofs1, ndofs2);
|
||||
let j_id2 = j_id2(j_id, ndofs1, ndofs2);
|
||||
|
||||
let dvel = solver_vel1.dvel(j_id1, ndofs1, jacobians, &dir1, &self.gcross1, solver_vels)
|
||||
let dvel = solver_vel1.dvel(j_id1, ndofs1, jacobians, dir1, &self.gcross1, solver_vels)
|
||||
+ solver_vel2.dvel(j_id2, ndofs2, jacobians, &-dir1, &self.gcross2, solver_vels)
|
||||
+ self.rhs;
|
||||
|
||||
@@ -271,7 +271,7 @@ impl TwoBodyConstraintNormalPart<Real> {
|
||||
ndofs1,
|
||||
dlambda,
|
||||
jacobians,
|
||||
&dir1,
|
||||
dir1,
|
||||
&self.gcross1,
|
||||
solver_vels,
|
||||
im1,
|
||||
@@ -323,7 +323,7 @@ impl TwoBodyConstraintElement<Real> {
|
||||
cfm_factor,
|
||||
nrm_j_id,
|
||||
jacobians,
|
||||
&dir1,
|
||||
dir1,
|
||||
im1,
|
||||
im2,
|
||||
ndofs1,
|
||||
@@ -339,7 +339,7 @@ impl TwoBodyConstraintElement<Real> {
|
||||
// Solve friction.
|
||||
if solve_friction {
|
||||
#[cfg(feature = "dim3")]
|
||||
let tangents1 = [tangent1, &dir1.cross(&tangent1)];
|
||||
let tangents1 = [tangent1, &dir1.cross(tangent1)];
|
||||
#[cfg(feature = "dim2")]
|
||||
let tangents1 = [&dir1.orthonormal_vector()];
|
||||
let mut tng_j_id = tangent_j_id(j_id, ndofs1, ndofs2);
|
||||
|
||||
@@ -76,7 +76,7 @@ impl OneBodyConstraintBuilder {
|
||||
|
||||
let rb1 = handle1
|
||||
.map(|h| SolverBody::from(&bodies[h]))
|
||||
.unwrap_or_else(SolverBody::default);
|
||||
.unwrap_or_default();
|
||||
|
||||
let rb2 = &bodies[handle2.unwrap()];
|
||||
let vels2 = &rb2.vels;
|
||||
@@ -334,7 +334,7 @@ impl OneBodyConstraint {
|
||||
solve_normal: bool,
|
||||
solve_friction: bool,
|
||||
) {
|
||||
let mut solver_vel2 = solver_vels[self.solver_vel2 as usize];
|
||||
let mut solver_vel2 = solver_vels[self.solver_vel2];
|
||||
|
||||
OneBodyConstraintElement::solve_group(
|
||||
self.cfm_factor,
|
||||
@@ -349,7 +349,7 @@ impl OneBodyConstraint {
|
||||
solve_friction,
|
||||
);
|
||||
|
||||
solver_vels[self.solver_vel2 as usize] = solver_vel2;
|
||||
solver_vels[self.solver_vel2] = solver_vel2;
|
||||
}
|
||||
|
||||
// FIXME: duplicated code. This is exactly the same as in the two-body velocity constraint.
|
||||
|
||||
@@ -204,7 +204,7 @@ impl<N: SimdRealCopy> OneBodyConstraintElement<N> {
|
||||
AngVector<N>: SimdDot<AngVector<N>, Result = N>,
|
||||
{
|
||||
#[cfg(feature = "dim3")]
|
||||
let tangents1 = [tangent1, &dir1.cross(&tangent1)];
|
||||
let tangents1 = [tangent1, &dir1.cross(tangent1)];
|
||||
#[cfg(feature = "dim2")]
|
||||
let tangents1 = [&dir1.orthonormal_vector()];
|
||||
|
||||
@@ -213,7 +213,7 @@ impl<N: SimdRealCopy> OneBodyConstraintElement<N> {
|
||||
for element in elements.iter_mut() {
|
||||
element
|
||||
.normal_part
|
||||
.solve(cfm_factor, &dir1, im2, solver_vel2);
|
||||
.solve(cfm_factor, dir1, im2, solver_vel2);
|
||||
let limit = limit * element.normal_part.impulse;
|
||||
let part = &mut element.tangent_part;
|
||||
part.apply_limit(tangents1, im2, limit, solver_vel2);
|
||||
|
||||
@@ -308,12 +308,8 @@ impl OneBodyConstraintSimd {
|
||||
solve_friction: bool,
|
||||
) {
|
||||
let mut solver_vel2 = SolverVel {
|
||||
linear: Vector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel2[ii] as usize].linear
|
||||
]),
|
||||
angular: AngVector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel2[ii] as usize].angular
|
||||
]),
|
||||
linear: Vector::from(gather![|ii| solver_vels[self.solver_vel2[ii]].linear]),
|
||||
angular: AngVector::from(gather![|ii| solver_vels[self.solver_vel2[ii]].angular]),
|
||||
};
|
||||
|
||||
OneBodyConstraintElement::solve_group(
|
||||
@@ -330,8 +326,8 @@ impl OneBodyConstraintSimd {
|
||||
);
|
||||
|
||||
for ii in 0..SIMD_WIDTH {
|
||||
solver_vels[self.solver_vel2[ii] as usize].linear = solver_vel2.linear.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii] as usize].angular = solver_vel2.angular.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii]].linear = solver_vel2.linear.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii]].angular = solver_vel2.angular.extract(ii);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -380,8 +380,8 @@ impl TwoBodyConstraint {
|
||||
solve_normal: bool,
|
||||
solve_friction: bool,
|
||||
) {
|
||||
let mut solver_vel1 = solver_vels[self.solver_vel1 as usize];
|
||||
let mut solver_vel2 = solver_vels[self.solver_vel2 as usize];
|
||||
let mut solver_vel1 = solver_vels[self.solver_vel1];
|
||||
let mut solver_vel2 = solver_vels[self.solver_vel2];
|
||||
|
||||
TwoBodyConstraintElement::solve_group(
|
||||
self.cfm_factor,
|
||||
@@ -398,8 +398,8 @@ impl TwoBodyConstraint {
|
||||
solve_friction,
|
||||
);
|
||||
|
||||
solver_vels[self.solver_vel1 as usize] = solver_vel1;
|
||||
solver_vels[self.solver_vel2 as usize] = solver_vel2;
|
||||
solver_vels[self.solver_vel1] = solver_vel1;
|
||||
solver_vels[self.solver_vel2] = solver_vel2;
|
||||
}
|
||||
|
||||
pub fn writeback_impulses(&self, manifolds_all: &mut [&mut ContactManifold]) {
|
||||
|
||||
@@ -243,7 +243,7 @@ impl<N: SimdRealCopy> TwoBodyConstraintElement<N> {
|
||||
AngVector<N>: SimdDot<AngVector<N>, Result = N>,
|
||||
{
|
||||
#[cfg(feature = "dim3")]
|
||||
let tangents1 = [tangent1, &dir1.cross(&tangent1)];
|
||||
let tangents1 = [tangent1, &dir1.cross(tangent1)];
|
||||
#[cfg(feature = "dim2")]
|
||||
let tangents1 = [&dir1.orthonormal_vector()];
|
||||
|
||||
@@ -252,7 +252,7 @@ impl<N: SimdRealCopy> TwoBodyConstraintElement<N> {
|
||||
for element in elements.iter_mut() {
|
||||
element
|
||||
.normal_part
|
||||
.solve(cfm_factor, &dir1, im1, im2, solver_vel1, solver_vel2);
|
||||
.solve(cfm_factor, dir1, im1, im2, solver_vel1, solver_vel2);
|
||||
let limit = limit * element.normal_part.impulse;
|
||||
let part = &mut element.tangent_part;
|
||||
part.apply_limit(tangents1, im1, im2, limit, solver_vel1, solver_vel2);
|
||||
|
||||
@@ -292,21 +292,13 @@ impl TwoBodyConstraintSimd {
|
||||
solve_friction: bool,
|
||||
) {
|
||||
let mut solver_vel1 = SolverVel {
|
||||
linear: Vector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel1[ii] as usize].linear
|
||||
]),
|
||||
angular: AngVector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel1[ii] as usize].angular
|
||||
]),
|
||||
linear: Vector::from(gather![|ii| solver_vels[self.solver_vel1[ii]].linear]),
|
||||
angular: AngVector::from(gather![|ii| solver_vels[self.solver_vel1[ii]].angular]),
|
||||
};
|
||||
|
||||
let mut solver_vel2 = SolverVel {
|
||||
linear: Vector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel2[ii] as usize].linear
|
||||
]),
|
||||
angular: AngVector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel2[ii] as usize].angular
|
||||
]),
|
||||
linear: Vector::from(gather![|ii| solver_vels[self.solver_vel2[ii]].linear]),
|
||||
angular: AngVector::from(gather![|ii| solver_vels[self.solver_vel2[ii]].angular]),
|
||||
};
|
||||
|
||||
TwoBodyConstraintElement::solve_group(
|
||||
@@ -325,12 +317,12 @@ impl TwoBodyConstraintSimd {
|
||||
);
|
||||
|
||||
for ii in 0..SIMD_WIDTH {
|
||||
solver_vels[self.solver_vel1[ii] as usize].linear = solver_vel1.linear.extract(ii);
|
||||
solver_vels[self.solver_vel1[ii] as usize].angular = solver_vel1.angular.extract(ii);
|
||||
solver_vels[self.solver_vel1[ii]].linear = solver_vel1.linear.extract(ii);
|
||||
solver_vels[self.solver_vel1[ii]].angular = solver_vel1.angular.extract(ii);
|
||||
}
|
||||
for ii in 0..SIMD_WIDTH {
|
||||
solver_vels[self.solver_vel2[ii] as usize].linear = solver_vel2.linear.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii] as usize].angular = solver_vel2.angular.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii]].linear = solver_vel2.linear.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii]].angular = solver_vel2.angular.extract(ii);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -25,7 +25,7 @@ impl<'a> PairInteraction for &'a mut ContactManifold {
|
||||
}
|
||||
|
||||
#[cfg(feature = "parallel")]
|
||||
impl<'a> PairInteraction for JointGraphEdge {
|
||||
impl PairInteraction for JointGraphEdge {
|
||||
fn body_pair(&self) -> (Option<RigidBodyHandle>, Option<RigidBodyHandle>) {
|
||||
(Some(self.weight.body1), Some(self.weight.body2))
|
||||
}
|
||||
@@ -470,11 +470,11 @@ impl InteractionGroups {
|
||||
(bucket.0)[SIMD_LAST_INDEX] = *interaction_i;
|
||||
self.simd_interactions.extend_from_slice(&bucket.0);
|
||||
bucket.1 = 0;
|
||||
occupied_mask = occupied_mask & (!target_mask_bit);
|
||||
occupied_mask &= !target_mask_bit;
|
||||
} else {
|
||||
(bucket.0)[bucket.1] = *interaction_i;
|
||||
bucket.1 += 1;
|
||||
occupied_mask = occupied_mask | target_mask_bit;
|
||||
occupied_mask |= target_mask_bit;
|
||||
}
|
||||
|
||||
// NOTE: fixed bodies don't transmit forces. Therefore they don't
|
||||
|
||||
@@ -399,7 +399,7 @@ impl JointConstraintsSet {
|
||||
) {
|
||||
for builder in &mut self.generic_velocity_constraints_builder {
|
||||
builder.update(
|
||||
¶ms,
|
||||
params,
|
||||
multibodies,
|
||||
solver_bodies,
|
||||
&mut self.generic_jacobians,
|
||||
@@ -409,7 +409,7 @@ impl JointConstraintsSet {
|
||||
|
||||
for builder in &mut self.generic_velocity_one_body_constraints_builder {
|
||||
builder.update(
|
||||
¶ms,
|
||||
params,
|
||||
multibodies,
|
||||
solver_bodies,
|
||||
&mut self.generic_jacobians,
|
||||
@@ -418,17 +418,17 @@ impl JointConstraintsSet {
|
||||
}
|
||||
|
||||
for builder in &mut self.velocity_constraints_builder {
|
||||
builder.update(¶ms, solver_bodies, &mut self.velocity_constraints);
|
||||
builder.update(params, solver_bodies, &mut self.velocity_constraints);
|
||||
}
|
||||
|
||||
#[cfg(feature = "simd-is-enabled")]
|
||||
for builder in &mut self.simd_velocity_constraints_builder {
|
||||
builder.update(¶ms, solver_bodies, &mut self.simd_velocity_constraints);
|
||||
builder.update(params, solver_bodies, &mut self.simd_velocity_constraints);
|
||||
}
|
||||
|
||||
for builder in &mut self.velocity_one_body_constraints_builder {
|
||||
builder.update(
|
||||
¶ms,
|
||||
params,
|
||||
solver_bodies,
|
||||
&mut self.velocity_one_body_constraints,
|
||||
);
|
||||
@@ -437,7 +437,7 @@ impl JointConstraintsSet {
|
||||
#[cfg(feature = "simd-is-enabled")]
|
||||
for builder in &mut self.simd_velocity_one_body_constraints_builder {
|
||||
builder.update(
|
||||
¶ms,
|
||||
params,
|
||||
solver_bodies,
|
||||
&mut self.simd_velocity_one_body_constraints,
|
||||
);
|
||||
|
||||
@@ -219,6 +219,7 @@ impl JointGenericTwoBodyConstraintBuilder {
|
||||
}
|
||||
|
||||
#[derive(Copy, Clone)]
|
||||
#[allow(clippy::large_enum_variant)]
|
||||
pub enum JointGenericOneBodyConstraintBuilder {
|
||||
Internal(JointGenericVelocityOneBodyInternalConstraintBuilder),
|
||||
External(JointGenericVelocityOneBodyExternalConstraintBuilder),
|
||||
|
||||
@@ -332,13 +332,13 @@ impl JointTwoBodyConstraint<Real, 1> {
|
||||
}
|
||||
|
||||
pub fn solve(&mut self, solver_vels: &mut [SolverVel<Real>]) {
|
||||
let mut solver_vel1 = solver_vels[self.solver_vel1[0] as usize];
|
||||
let mut solver_vel2 = solver_vels[self.solver_vel2[0] as usize];
|
||||
let mut solver_vel1 = solver_vels[self.solver_vel1[0]];
|
||||
let mut solver_vel2 = solver_vels[self.solver_vel2[0]];
|
||||
|
||||
self.solve_generic(&mut solver_vel1, &mut solver_vel2);
|
||||
|
||||
solver_vels[self.solver_vel1[0] as usize] = solver_vel1;
|
||||
solver_vels[self.solver_vel2[0] as usize] = solver_vel2;
|
||||
solver_vels[self.solver_vel1[0]] = solver_vel1;
|
||||
solver_vels[self.solver_vel2[0]] = solver_vel2;
|
||||
}
|
||||
|
||||
pub fn writeback_impulses(&self, joints_all: &mut [JointGraphEdge]) {
|
||||
@@ -399,29 +399,21 @@ impl JointTwoBodyConstraint<SimdReal, SIMD_WIDTH> {
|
||||
|
||||
pub fn solve(&mut self, solver_vels: &mut [SolverVel<Real>]) {
|
||||
let mut solver_vel1 = SolverVel {
|
||||
linear: Vector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel1[ii] as usize].linear
|
||||
]),
|
||||
angular: AngVector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel1[ii] as usize].angular
|
||||
]),
|
||||
linear: Vector::from(gather![|ii| solver_vels[self.solver_vel1[ii]].linear]),
|
||||
angular: AngVector::from(gather![|ii| solver_vels[self.solver_vel1[ii]].angular]),
|
||||
};
|
||||
let mut solver_vel2 = SolverVel {
|
||||
linear: Vector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel2[ii] as usize].linear
|
||||
]),
|
||||
angular: AngVector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel2[ii] as usize].angular
|
||||
]),
|
||||
linear: Vector::from(gather![|ii| solver_vels[self.solver_vel2[ii]].linear]),
|
||||
angular: AngVector::from(gather![|ii| solver_vels[self.solver_vel2[ii]].angular]),
|
||||
};
|
||||
|
||||
self.solve_generic(&mut solver_vel1, &mut solver_vel2);
|
||||
|
||||
for ii in 0..SIMD_WIDTH {
|
||||
solver_vels[self.solver_vel1[ii] as usize].linear = solver_vel1.linear.extract(ii);
|
||||
solver_vels[self.solver_vel1[ii] as usize].angular = solver_vel1.angular.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii] as usize].linear = solver_vel2.linear.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii] as usize].angular = solver_vel2.angular.extract(ii);
|
||||
solver_vels[self.solver_vel1[ii]].linear = solver_vel1.linear.extract(ii);
|
||||
solver_vels[self.solver_vel1[ii]].angular = solver_vel1.angular.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii]].linear = solver_vel2.linear.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii]].angular = solver_vel2.angular.extract(ii);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -682,9 +674,9 @@ impl JointOneBodyConstraint<Real, 1> {
|
||||
}
|
||||
|
||||
pub fn solve(&mut self, solver_vels: &mut [SolverVel<Real>]) {
|
||||
let mut solver_vel2 = solver_vels[self.solver_vel2[0] as usize];
|
||||
let mut solver_vel2 = solver_vels[self.solver_vel2[0]];
|
||||
self.solve_generic(&mut solver_vel2);
|
||||
solver_vels[self.solver_vel2[0] as usize] = solver_vel2;
|
||||
solver_vels[self.solver_vel2[0]] = solver_vel2;
|
||||
}
|
||||
|
||||
pub fn writeback_impulses(&self, joints_all: &mut [JointGraphEdge]) {
|
||||
@@ -751,19 +743,15 @@ impl JointOneBodyConstraint<SimdReal, SIMD_WIDTH> {
|
||||
|
||||
pub fn solve(&mut self, solver_vels: &mut [SolverVel<Real>]) {
|
||||
let mut solver_vel2 = SolverVel {
|
||||
linear: Vector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel2[ii] as usize].linear
|
||||
]),
|
||||
angular: AngVector::from(gather![
|
||||
|ii| solver_vels[self.solver_vel2[ii] as usize].angular
|
||||
]),
|
||||
linear: Vector::from(gather![|ii| solver_vels[self.solver_vel2[ii]].linear]),
|
||||
angular: AngVector::from(gather![|ii| solver_vels[self.solver_vel2[ii]].angular]),
|
||||
};
|
||||
|
||||
self.solve_generic(&mut solver_vel2);
|
||||
|
||||
for ii in 0..SIMD_WIDTH {
|
||||
solver_vels[self.solver_vel2[ii] as usize].linear = solver_vel2.linear.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii] as usize].angular = solver_vel2.angular.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii]].linear = solver_vel2.linear.extract(ii);
|
||||
solver_vels[self.solver_vel2[ii]].angular = solver_vel2.angular.extract(ii);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -7,17 +7,17 @@ pub(crate) use self::island_solver::IslandSolver;
|
||||
// #[cfg(feature = "parallel")]
|
||||
// pub(self) use self::parallel_velocity_solver::ParallelVelocitySolver;
|
||||
// #[cfg(not(feature = "parallel"))]
|
||||
pub(self) use self::solver_constraints_set::SolverConstraintsSet;
|
||||
use self::solver_constraints_set::SolverConstraintsSet;
|
||||
// #[cfg(not(feature = "parallel"))]
|
||||
pub(self) use self::velocity_solver::VelocitySolver;
|
||||
use self::velocity_solver::VelocitySolver;
|
||||
|
||||
pub(self) use contact_constraint::*;
|
||||
pub(self) use interaction_groups::*;
|
||||
use contact_constraint::*;
|
||||
use interaction_groups::*;
|
||||
pub(crate) use joint_constraint::MotorParameters;
|
||||
pub use joint_constraint::*;
|
||||
pub(self) use solver_body::SolverBody;
|
||||
pub(self) use solver_constraints_set::{AnyConstraintMut, ConstraintTypes};
|
||||
pub(self) use solver_vel::SolverVel;
|
||||
use solver_body::SolverBody;
|
||||
use solver_constraints_set::{AnyConstraintMut, ConstraintTypes};
|
||||
use solver_vel::SolverVel;
|
||||
|
||||
mod categorization;
|
||||
mod contact_constraint;
|
||||
|
||||
@@ -175,8 +175,8 @@ impl VelocitySolver {
|
||||
/*
|
||||
* Update & solve constraints.
|
||||
*/
|
||||
joint_constraints.update(¶ms, multibodies, &self.solver_bodies);
|
||||
contact_constraints.update(¶ms, substep_id, multibodies, &self.solver_bodies);
|
||||
joint_constraints.update(params, multibodies, &self.solver_bodies);
|
||||
contact_constraints.update(params, substep_id, multibodies, &self.solver_bodies);
|
||||
|
||||
for _ in 0..params.num_internal_pgs_iterations {
|
||||
joint_constraints.solve(&mut self.solver_vels, &mut self.generic_solver_vels);
|
||||
@@ -196,7 +196,7 @@ impl VelocitySolver {
|
||||
/*
|
||||
* Integrate positions.
|
||||
*/
|
||||
self.integrate_positions(¶ms, is_last_substep, bodies, multibodies);
|
||||
self.integrate_positions(params, is_last_substep, bodies, multibodies);
|
||||
|
||||
/*
|
||||
* Resolution without bias.
|
||||
|
||||
@@ -445,9 +445,8 @@ impl BroadPhase {
|
||||
);
|
||||
}
|
||||
|
||||
let need_region_propagation = !layer.created_regions.is_empty();
|
||||
|
||||
need_region_propagation
|
||||
// Returns true if propagation is needed.
|
||||
!layer.created_regions.is_empty()
|
||||
}
|
||||
|
||||
/// Updates the broad-phase, taking into account the new collider positions.
|
||||
|
||||
@@ -2,12 +2,12 @@ pub use self::broad_phase::BroadPhase;
|
||||
pub use self::broad_phase_pair_event::{BroadPhasePairEvent, ColliderPair};
|
||||
pub use self::sap_proxy::SAPProxyIndex;
|
||||
|
||||
pub(self) use self::sap_axis::*;
|
||||
pub(self) use self::sap_endpoint::*;
|
||||
pub(self) use self::sap_layer::*;
|
||||
pub(self) use self::sap_proxy::*;
|
||||
pub(self) use self::sap_region::*;
|
||||
pub(self) use self::sap_utils::*;
|
||||
use self::sap_axis::*;
|
||||
use self::sap_endpoint::*;
|
||||
use self::sap_layer::*;
|
||||
use self::sap_proxy::*;
|
||||
use self::sap_region::*;
|
||||
use self::sap_utils::*;
|
||||
|
||||
mod broad_phase;
|
||||
mod broad_phase_pair_event;
|
||||
|
||||
@@ -65,9 +65,8 @@ impl SAPAxis {
|
||||
proxy.aabb,
|
||||
self.min_bound
|
||||
);
|
||||
let start_endpoint =
|
||||
SAPEndpoint::start_endpoint(proxy.aabb.mins[dim], *proxy_id as u32);
|
||||
let end_endpoint = SAPEndpoint::end_endpoint(proxy.aabb.maxs[dim], *proxy_id as u32);
|
||||
let start_endpoint = SAPEndpoint::start_endpoint(proxy.aabb.mins[dim], *proxy_id);
|
||||
let end_endpoint = SAPEndpoint::end_endpoint(proxy.aabb.maxs[dim], *proxy_id);
|
||||
|
||||
self.new_endpoints.push((start_endpoint, 0));
|
||||
self.new_endpoints.push((end_endpoint, 0));
|
||||
|
||||
@@ -15,10 +15,7 @@ pub enum SAPProxyData {
|
||||
|
||||
impl SAPProxyData {
|
||||
pub fn is_region(&self) -> bool {
|
||||
match self {
|
||||
SAPProxyData::Region(_) => true,
|
||||
_ => false,
|
||||
}
|
||||
matches!(self, SAPProxyData::Region(_))
|
||||
}
|
||||
|
||||
pub fn as_region(&self) -> &SAPRegion {
|
||||
@@ -102,7 +99,7 @@ impl SAPProxies {
|
||||
}
|
||||
|
||||
pub fn insert(&mut self, proxy: SAPProxy) -> SAPProxyIndex {
|
||||
let result = if self.first_free != NEXT_FREE_SENTINEL {
|
||||
if self.first_free != NEXT_FREE_SENTINEL {
|
||||
let proxy_id = self.first_free;
|
||||
self.first_free = self.elements[proxy_id as usize].next_free;
|
||||
self.elements[proxy_id as usize] = proxy;
|
||||
@@ -110,15 +107,13 @@ impl SAPProxies {
|
||||
} else {
|
||||
self.elements.push(proxy);
|
||||
self.elements.len() as u32 - 1
|
||||
};
|
||||
|
||||
result
|
||||
}
|
||||
}
|
||||
|
||||
pub fn remove(&mut self, proxy_id: SAPProxyIndex) {
|
||||
let proxy = &mut self.elements[proxy_id as usize];
|
||||
proxy.next_free = self.first_free;
|
||||
self.first_free = proxy_id as u32;
|
||||
self.first_free = proxy_id;
|
||||
}
|
||||
|
||||
// NOTE: this must not take holes into account.
|
||||
|
||||
@@ -73,6 +73,7 @@ impl SAPRegion {
|
||||
old
|
||||
}
|
||||
|
||||
#[allow(clippy::vec_box)] // PERF: see if Box actually makes it faster (due to less copying).
|
||||
pub fn recycle_or_new(bounds: Aabb, pool: &mut Vec<Box<Self>>) -> Box<Self> {
|
||||
if let Some(old) = pool.pop() {
|
||||
Self::recycle(bounds, old)
|
||||
|
||||
@@ -157,10 +157,7 @@ impl Collider {
|
||||
|
||||
/// Is this collider enabled?
|
||||
pub fn is_enabled(&self) -> bool {
|
||||
match self.flags.enabled {
|
||||
ColliderEnabled::Enabled => true,
|
||||
_ => false,
|
||||
}
|
||||
matches!(self.flags.enabled, ColliderEnabled::Enabled)
|
||||
}
|
||||
|
||||
/// Sets whether or not this collider is enabled.
|
||||
@@ -916,8 +913,8 @@ impl ColliderBuilder {
|
||||
}
|
||||
}
|
||||
|
||||
impl Into<Collider> for ColliderBuilder {
|
||||
fn into(self) -> Collider {
|
||||
self.build()
|
||||
impl From<ColliderBuilder> for Collider {
|
||||
fn from(val: ColliderBuilder) -> Collider {
|
||||
val.build()
|
||||
}
|
||||
}
|
||||
|
||||
@@ -24,11 +24,11 @@ impl ColliderSet {
|
||||
}
|
||||
|
||||
pub(crate) fn take_modified(&mut self) -> Vec<ColliderHandle> {
|
||||
std::mem::replace(&mut self.modified_colliders, vec![])
|
||||
std::mem::take(&mut self.modified_colliders)
|
||||
}
|
||||
|
||||
pub(crate) fn take_removed(&mut self) -> Vec<ColliderHandle> {
|
||||
std::mem::replace(&mut self.removed_colliders, vec![])
|
||||
std::mem::take(&mut self.removed_colliders)
|
||||
}
|
||||
|
||||
/// An always-invalid collider handle.
|
||||
|
||||
@@ -1,3 +1,5 @@
|
||||
#![allow(clippy::bad_bit_mask)] // Clippy will complain about the bitmasks due to Group::NONE being 0.
|
||||
|
||||
/// Pairwise filtering using bit masks.
|
||||
///
|
||||
/// This filtering method is based on two 32-bit values:
|
||||
|
||||
@@ -126,7 +126,7 @@ impl NarrowPhase {
|
||||
/// The returned contact pairs identify pairs of colliders with intersecting bounding-volumes.
|
||||
/// To check if any geometric contact happened between the collider shapes, check
|
||||
/// [`ContactPair::has_any_active_contact`].
|
||||
pub fn contact_pairs_with<'a>(
|
||||
pub fn contact_pairs_with(
|
||||
&self,
|
||||
collider: ColliderHandle,
|
||||
) -> impl Iterator<Item = &ContactPair> {
|
||||
@@ -324,7 +324,7 @@ impl NarrowPhase {
|
||||
&mut self,
|
||||
intersection_graph_id: ColliderGraphIndex,
|
||||
contact_graph_id: ColliderGraphIndex,
|
||||
mut islands: Option<&mut IslandManager>,
|
||||
islands: Option<&mut IslandManager>,
|
||||
colliders: &mut ColliderSet,
|
||||
bodies: &mut RigidBodySet,
|
||||
prox_id_remap: &mut HashMap<ColliderHandle, ColliderGraphIndex>,
|
||||
@@ -332,7 +332,7 @@ impl NarrowPhase {
|
||||
events: &dyn EventHandler,
|
||||
) {
|
||||
// Wake up every body in contact with the deleted collider and generate Stopped collision events.
|
||||
if let Some(islands) = islands.as_deref_mut() {
|
||||
if let Some(islands) = islands {
|
||||
for (a, b, pair) in self.contact_graph.interactions_with(contact_graph_id) {
|
||||
if let Some(parent) = colliders.get(a).and_then(|c| c.parent.as_ref()) {
|
||||
islands.wake_up(bodies, parent.handle, true)
|
||||
@@ -539,18 +539,17 @@ impl NarrowPhase {
|
||||
|
||||
// Emit an intersection lost event if we had an intersection before removing the edge.
|
||||
if let Some(mut intersection) = intersection {
|
||||
if intersection.intersecting {
|
||||
if (co1.flags.active_events | co2.flags.active_events)
|
||||
if intersection.intersecting
|
||||
&& (co1.flags.active_events | co2.flags.active_events)
|
||||
.contains(ActiveEvents::COLLISION_EVENTS)
|
||||
{
|
||||
intersection.emit_stop_event(
|
||||
bodies,
|
||||
colliders,
|
||||
pair.collider1,
|
||||
pair.collider2,
|
||||
events,
|
||||
)
|
||||
}
|
||||
{
|
||||
intersection.emit_stop_event(
|
||||
bodies,
|
||||
colliders,
|
||||
pair.collider1,
|
||||
pair.collider2,
|
||||
events,
|
||||
)
|
||||
}
|
||||
}
|
||||
} else {
|
||||
@@ -588,15 +587,14 @@ impl NarrowPhase {
|
||||
if let (Some(co1), Some(co2)) =
|
||||
(colliders.get(pair.collider1), colliders.get(pair.collider2))
|
||||
{
|
||||
if co1.parent.map(|p| p.handle) == co2.parent.map(|p| p.handle) {
|
||||
if co1.parent.is_some() {
|
||||
// Same parents. Ignore collisions.
|
||||
return;
|
||||
}
|
||||
|
||||
// These colliders have no parents - continue.
|
||||
if co1.parent.map(|p| p.handle) == co2.parent.map(|p| p.handle) && co1.parent.is_some()
|
||||
{
|
||||
// Same parents. Ignore collisions.
|
||||
return;
|
||||
}
|
||||
|
||||
// These colliders have no parents - continue.
|
||||
|
||||
let (gid1, gid2) = self.graph_indices.ensure_pair_exists(
|
||||
pair.collider1.0,
|
||||
pair.collider2.0,
|
||||
@@ -712,7 +710,7 @@ impl NarrowPhase {
|
||||
let co2 = &colliders[handle2];
|
||||
|
||||
// TODO: remove the `loop` once labels on blocks is stabilized.
|
||||
'emit_events: loop {
|
||||
'emit_events: {
|
||||
if !co1.changes.needs_narrow_phase_update()
|
||||
&& !co2.changes.needs_narrow_phase_update()
|
||||
{
|
||||
@@ -813,7 +811,7 @@ impl NarrowPhase {
|
||||
let co2 = &colliders[pair.collider2];
|
||||
|
||||
// TODO: remove the `loop` once labels on blocks are supported.
|
||||
'emit_events: loop {
|
||||
'emit_events: {
|
||||
if !co1.changes.needs_narrow_phase_update()
|
||||
&& !co2.changes.needs_narrow_phase_update()
|
||||
{
|
||||
@@ -979,7 +977,7 @@ impl NarrowPhase {
|
||||
// Apply the user-defined contact modification.
|
||||
if active_hooks.contains(ActiveHooks::MODIFY_SOLVER_CONTACTS) {
|
||||
let mut modifiable_solver_contacts =
|
||||
std::mem::replace(&mut manifold.data.solver_contacts, Vec::new());
|
||||
std::mem::take(&mut manifold.data.solver_contacts);
|
||||
let mut modifiable_user_data = manifold.data.user_data;
|
||||
let mut modifiable_normal = manifold.data.normal;
|
||||
|
||||
@@ -1009,13 +1007,13 @@ impl NarrowPhase {
|
||||
|
||||
let active_events = co1.flags.active_events | co2.flags.active_events;
|
||||
|
||||
if pair.has_any_active_contact != had_any_active_contact {
|
||||
if active_events.contains(ActiveEvents::COLLISION_EVENTS) {
|
||||
if pair.has_any_active_contact {
|
||||
pair.emit_start_event(bodies, colliders, events);
|
||||
} else {
|
||||
pair.emit_stop_event(bodies, colliders, events);
|
||||
}
|
||||
if pair.has_any_active_contact != had_any_active_contact
|
||||
&& active_events.contains(ActiveEvents::COLLISION_EVENTS)
|
||||
{
|
||||
if pair.has_any_active_contact {
|
||||
pair.emit_start_event(bodies, colliders, events);
|
||||
} else {
|
||||
pair.emit_stop_event(bodies, colliders, events);
|
||||
}
|
||||
}
|
||||
});
|
||||
@@ -1029,7 +1027,7 @@ impl NarrowPhase {
|
||||
bodies: &RigidBodySet,
|
||||
out_contact_pairs: &mut Vec<TemporaryInteractionIndex>,
|
||||
out_manifolds: &mut Vec<&'a mut ContactManifold>,
|
||||
out: &mut Vec<Vec<ContactManifoldIndex>>,
|
||||
out: &mut [Vec<ContactManifoldIndex>],
|
||||
) {
|
||||
for out_island in &mut out[..islands.num_islands()] {
|
||||
out_island.clear();
|
||||
|
||||
@@ -12,6 +12,9 @@
|
||||
|
||||
#![deny(bare_trait_objects)]
|
||||
#![warn(missing_docs)] // FIXME: deny that
|
||||
#![allow(clippy::too_many_arguments)]
|
||||
#![allow(clippy::needless_range_loop)] // TODO: remove this? I find that in the math code using indices adds clarity.
|
||||
#![allow(clippy::module_inception)]
|
||||
|
||||
#[cfg(all(feature = "dim2", feature = "f32"))]
|
||||
pub extern crate parry2d as parry;
|
||||
|
||||
@@ -149,7 +149,7 @@ impl CollisionPipeline {
|
||||
bodies,
|
||||
colliders,
|
||||
&modified_colliders[..],
|
||||
&mut removed_colliders,
|
||||
&removed_colliders,
|
||||
hooks,
|
||||
events,
|
||||
true,
|
||||
|
||||
@@ -79,12 +79,10 @@ pub trait DebugRenderBackend {
|
||||
self.draw_line(object, a, b, color);
|
||||
}
|
||||
|
||||
if closed {
|
||||
if vertices.len() > 2 {
|
||||
let a = transform * (Scale::from(*scale) * vertices[0]);
|
||||
let b = transform * (Scale::from(*scale) * vertices.last().unwrap());
|
||||
self.draw_line(object, a, b, color);
|
||||
}
|
||||
if closed && vertices.len() > 2 {
|
||||
let a = transform * (Scale::from(*scale) * vertices[0]);
|
||||
let b = transform * (Scale::from(*scale) * vertices.last().unwrap());
|
||||
self.draw_line(object, a, b, color);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -41,12 +41,17 @@ impl Default for DebugRenderMode {
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "dim2")]
|
||||
type InstancesMap = HashMap<TypeId, Vec<Point<Real>>>;
|
||||
#[cfg(feature = "dim3")]
|
||||
type InstancesMap = HashMap<TypeId, (Vec<Point<Real>>, Vec<[u32; 2]>)>;
|
||||
|
||||
/// Pipeline responsible for rendering the state of the physics engine for debugging purpose.
|
||||
pub struct DebugRenderPipeline {
|
||||
#[cfg(feature = "dim2")]
|
||||
instances: HashMap<TypeId, Vec<Point<Real>>>,
|
||||
instances: InstancesMap,
|
||||
#[cfg(feature = "dim3")]
|
||||
instances: HashMap<TypeId, (Vec<Point<Real>>, Vec<[u32; 2]>)>,
|
||||
instances: InstancesMap,
|
||||
/// The style used to compute the line colors for each element
|
||||
/// to render.
|
||||
pub style: DebugRenderStyle,
|
||||
|
||||
@@ -5,4 +5,4 @@ pub use self::debug_render_style::{DebugColor, DebugRenderStyle};
|
||||
mod debug_render_backend;
|
||||
mod debug_render_pipeline;
|
||||
mod debug_render_style;
|
||||
pub(self) mod outlines;
|
||||
mod outlines;
|
||||
|
||||
@@ -17,6 +17,7 @@ pub fn instances(nsubdivs: u32) -> HashMap<TypeId, Vec<Point<Real>>> {
|
||||
}
|
||||
|
||||
#[cfg(feature = "dim3")]
|
||||
#[allow(clippy::type_complexity)]
|
||||
pub fn instances(nsubdivs: u32) -> HashMap<TypeId, (Vec<Point<Real>>, Vec<[u32; 2]>)> {
|
||||
let mut result = HashMap::new();
|
||||
result.insert(
|
||||
|
||||
@@ -69,7 +69,7 @@ impl<'a> ContactModificationContext<'a> {
|
||||
|
||||
// Test the allowed normal with the local-space contact normal that
|
||||
// points towards the exterior of context.collider1.
|
||||
let contact_is_ok = self.manifold.local_n1.dot(&allowed_local_n1) >= cang;
|
||||
let contact_is_ok = self.manifold.local_n1.dot(allowed_local_n1) >= cang;
|
||||
|
||||
match *self.user_data {
|
||||
CONTACT_CONFIGURATION_UNKNOWN => {
|
||||
|
||||
@@ -212,7 +212,7 @@ impl PhysicsPipeline {
|
||||
rb.mprops.update_world_mass_properties(&rb.pos.position);
|
||||
let effective_mass = rb.mprops.effective_mass();
|
||||
rb.forces
|
||||
.compute_effective_force_and_torque(&gravity, &effective_mass);
|
||||
.compute_effective_force_and_torque(gravity, &effective_mass);
|
||||
}
|
||||
self.counters.stages.update_time.pause();
|
||||
|
||||
@@ -270,14 +270,13 @@ impl PhysicsPipeline {
|
||||
.enumerate()
|
||||
.for_each(|(island_id, solver)| {
|
||||
let bodies: &mut RigidBodySet =
|
||||
unsafe { std::mem::transmute(bodies.load(Ordering::Relaxed)) };
|
||||
unsafe { &mut *bodies.load(Ordering::Relaxed) };
|
||||
let manifolds: &mut Vec<&mut ContactManifold> =
|
||||
unsafe { std::mem::transmute(manifolds.load(Ordering::Relaxed)) };
|
||||
unsafe { &mut *manifolds.load(Ordering::Relaxed) };
|
||||
let impulse_joints: &mut Vec<JointGraphEdge> =
|
||||
unsafe { std::mem::transmute(impulse_joints.load(Ordering::Relaxed)) };
|
||||
let multibody_joints: &mut MultibodyJointSet = unsafe {
|
||||
std::mem::transmute(multibody_joints.load(Ordering::Relaxed))
|
||||
};
|
||||
unsafe { &mut *impulse_joints.load(Ordering::Relaxed) };
|
||||
let multibody_joints: &mut MultibodyJointSet =
|
||||
unsafe { &mut *multibody_joints.load(Ordering::Relaxed) };
|
||||
|
||||
let mut counters = Counters::new(false);
|
||||
solver.init_and_solve(
|
||||
|
||||
@@ -114,6 +114,7 @@ pub struct QueryFilter<'a> {
|
||||
/// If set, any collider attached to this rigid-body will be excluded from the scene query.
|
||||
pub exclude_rigid_body: Option<RigidBodyHandle>,
|
||||
/// If set, any collider for which this closure returns false will be excluded from the scene query.
|
||||
#[allow(clippy::type_complexity)] // Type doesn’t look really complex?
|
||||
pub predicate: Option<&'a dyn Fn(ColliderHandle, &Collider) -> bool>,
|
||||
}
|
||||
|
||||
@@ -668,10 +669,10 @@ impl QueryPipeline {
|
||||
/// the shape is penetrating another shape at its starting point **and** its trajectory is such
|
||||
/// that it’s on a path to exist that penetration state.
|
||||
/// * `filter`: set of rules used to determine which collider is taken into account by this scene query.
|
||||
pub fn cast_shape<'a>(
|
||||
pub fn cast_shape(
|
||||
&self,
|
||||
bodies: &RigidBodySet,
|
||||
colliders: &'a ColliderSet,
|
||||
colliders: &ColliderSet,
|
||||
shape_pos: &Isometry<Real>,
|
||||
shape_vel: &Vector<Real>,
|
||||
shape: &dyn Shape,
|
||||
@@ -746,10 +747,10 @@ impl QueryPipeline {
|
||||
/// * `shape` - The shape to test.
|
||||
/// * `filter`: set of rules used to determine which collider is taken into account by this scene query.
|
||||
/// * `callback` - A function called with the handles of each collider intersecting the `shape`.
|
||||
pub fn intersections_with_shape<'a>(
|
||||
pub fn intersections_with_shape(
|
||||
&self,
|
||||
bodies: &RigidBodySet,
|
||||
colliders: &'a ColliderSet,
|
||||
colliders: &ColliderSet,
|
||||
shape_pos: &Isometry<Real>,
|
||||
shape: &dyn Shape,
|
||||
filter: QueryFilter,
|
||||
|
||||
@@ -111,15 +111,13 @@ pub(crate) fn handle_user_changes_to_rigid_bodies(
|
||||
}
|
||||
|
||||
// Update the active kinematic set.
|
||||
if changes.contains(RigidBodyChanges::POSITION)
|
||||
|| changes.contains(RigidBodyChanges::COLLIDERS)
|
||||
if (changes.contains(RigidBodyChanges::POSITION)
|
||||
|| changes.contains(RigidBodyChanges::COLLIDERS))
|
||||
&& rb.is_kinematic()
|
||||
&& islands.active_kinematic_set.get(ids.active_set_id) != Some(handle)
|
||||
{
|
||||
if rb.is_kinematic()
|
||||
&& islands.active_kinematic_set.get(ids.active_set_id) != Some(handle)
|
||||
{
|
||||
ids.active_set_id = islands.active_kinematic_set.len();
|
||||
islands.active_kinematic_set.push(*handle);
|
||||
}
|
||||
ids.active_set_id = islands.active_kinematic_set.len();
|
||||
islands.active_kinematic_set.push(*handle);
|
||||
}
|
||||
|
||||
// Push the body to the active set if it is not
|
||||
|
||||
@@ -25,7 +25,7 @@ impl SimdRealCopy for SimdReal {}
|
||||
const INV_EPSILON: Real = 1.0e-20;
|
||||
|
||||
pub(crate) fn inv(val: Real) -> Real {
|
||||
if val >= -INV_EPSILON && val <= INV_EPSILON {
|
||||
if (-INV_EPSILON..=INV_EPSILON).contains(&val) {
|
||||
0.0
|
||||
} else {
|
||||
1.0 / val
|
||||
|
||||
Reference in New Issue
Block a user