aboutsummaryrefslogtreecommitdiff
path: root/src/pipeline
diff options
context:
space:
mode:
Diffstat (limited to 'src/pipeline')
-rw-r--r--src/pipeline/debug_render_pipeline/debug_render_backend.rs44
-rw-r--r--src/pipeline/debug_render_pipeline/debug_render_pipeline.rs29
-rw-r--r--src/pipeline/debug_render_pipeline/outlines.rs6
-rw-r--r--src/pipeline/event_handler.rs8
-rw-r--r--src/pipeline/physics_hooks.rs20
-rw-r--r--src/pipeline/physics_pipeline.rs7
-rw-r--r--src/pipeline/query_pipeline.rs26
7 files changed, 78 insertions, 62 deletions
diff --git a/src/pipeline/debug_render_pipeline/debug_render_backend.rs b/src/pipeline/debug_render_pipeline/debug_render_backend.rs
index 664bf46..84aa2cc 100644
--- a/src/pipeline/debug_render_pipeline/debug_render_backend.rs
+++ b/src/pipeline/debug_render_pipeline/debug_render_backend.rs
@@ -2,9 +2,8 @@ use crate::dynamics::{
ImpulseJoint, ImpulseJointHandle, Multibody, MultibodyLink, RigidBody, RigidBodyHandle,
};
use crate::geometry::{Aabb, Collider, ContactPair};
-use crate::math::{Isometry, Point, Real, Vector};
+use crate::math::*;
use crate::prelude::{ColliderHandle, MultibodyJointHandle};
-use na::Scale;
/// The object currently being rendered by the debug-renderer.
#[derive(Copy, Clone)]
@@ -38,27 +37,25 @@ pub trait DebugRenderBackend {
/// Draws a colored line.
///
/// Note that this method can be called multiple time for the same `object`.
- fn draw_line(
- &mut self,
- object: DebugRenderObject,
- a: Point<Real>,
- b: Point<Real>,
- color: [f32; 4],
- );
+ fn draw_line(&mut self, object: DebugRenderObject, a: Point, b: Point, color: [f32; 4]);
/// Draws a set of line.
fn draw_polyline(
&mut self,
object: DebugRenderObject,
- vertices: &[Point<Real>],
+ vertices: &[Point],
indices: &[[u32; 2]],
- transform: &Isometry<Real>,
- scale: &Vector<Real>,
+ transform: &Isometry,
+ scale: &Vector,
color: [f32; 4],
) {
for idx in indices {
- let a = transform * (Scale::from(*scale) * vertices[idx[0] as usize]);
- let b = transform * (Scale::from(*scale) * vertices[idx[1] as usize]);
+ let a = transform.transform_point(&Point::from(
+ vertices[idx[0] as usize].as_vector().component_mul(scale),
+ ));
+ let b = transform.transform_point(&Point::from(
+ vertices[idx[1] as usize].as_vector().component_mul(scale),
+ ));
self.draw_line(object, a, b, color);
}
}
@@ -67,21 +64,26 @@ pub trait DebugRenderBackend {
fn draw_line_strip(
&mut self,
object: DebugRenderObject,
- vertices: &[Point<Real>],
- transform: &Isometry<Real>,
- scale: &Vector<Real>,
+ vertices: &[Point],
+ transform: &Isometry,
+ scale: &Vector,
color: [f32; 4],
closed: bool,
) {
for vtx in vertices.windows(2) {
- let a = transform * (Scale::from(*scale) * vtx[0]);
- let b = transform * (Scale::from(*scale) * vtx[1]);
+ let a =
+ transform.transform_point(&Point::from(vtx[0].as_vector().component_mul(scale)));
+ let b =
+ transform.transform_point(&Point::from(vtx[1].as_vector().component_mul(scale)));
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());
+ let a = transform
+ .transform_point(&Point::from(vertices[0].as_vector().component_mul(scale)));
+ let b = transform.transform_point(&Point::from(
+ vertices.last().unwrap().as_vector().component_mul(scale),
+ ));
self.draw_line(object, a, b, color);
}
}
diff --git a/src/pipeline/debug_render_pipeline/debug_render_pipeline.rs b/src/pipeline/debug_render_pipeline/debug_render_pipeline.rs
index b429c90..779e220 100644
--- a/src/pipeline/debug_render_pipeline/debug_render_pipeline.rs
+++ b/src/pipeline/debug_render_pipeline/debug_render_pipeline.rs
@@ -5,7 +5,7 @@ use crate::dynamics::{
use crate::geometry::{Ball, ColliderSet, Cuboid, NarrowPhase, Shape, TypedShape};
#[cfg(feature = "dim3")]
use crate::geometry::{Cone, Cylinder};
-use crate::math::{Isometry, Point, Real, Vector, DIM};
+use crate::math::*;
use crate::pipeline::debug_render_pipeline::debug_render_backend::DebugRenderObject;
use crate::pipeline::debug_render_pipeline::DebugRenderStyle;
use crate::utils::SimdBasis;
@@ -42,9 +42,9 @@ impl Default for DebugRenderMode {
}
#[cfg(feature = "dim2")]
-type InstancesMap = HashMap<TypeId, Vec<Point<Real>>>;
+type InstancesMap = HashMap<TypeId, Vec<Point>>;
#[cfg(feature = "dim3")]
-type InstancesMap = HashMap<TypeId, (Vec<Point<Real>>, Vec<[u32; 2]>)>;
+type InstancesMap = HashMap<TypeId, (Vec<Point>, Vec<[u32; 2]>)>;
/// Pipeline responsible for rendering the state of the physics engine for debugging purpose.
pub struct DebugRenderPipeline {
@@ -117,16 +117,17 @@ impl DebugRenderPipeline {
for contact in manifold.contacts() {
backend.draw_line(
object,
- co1.position() * contact.local_p1,
- co2.position() * contact.local_p2,
+ co1.position().transform_point(&contact.local_p1),
+ co2.position().transform_point(&contact.local_p2),
self.style.contact_depth_color,
);
backend.draw_line(
object,
- co1.position() * contact.local_p1,
- co1.position()
- * (contact.local_p1
+ co1.position().transform_point(&contact.local_p1),
+ co1.position().transform_point(
+ &(contact.local_p1
+ manifold.local_n1 * self.style.contact_normal_length),
+ ),
self.style.contact_normal_color,
);
}
@@ -193,10 +194,10 @@ impl DebugRenderPipeline {
let frame1 = rb1.position() * data.local_frame1;
let frame2 = rb2.position() * data.local_frame2;
- let a = *rb1.translation();
- let b = frame1.translation.vector;
- let c = frame2.translation.vector;
- let d = *rb2.translation();
+ let a = rb1.translation();
+ let b = frame1.translation.into_vector();
+ let c = frame2.translation.into_vector();
+ let d = rb2.translation();
for k in 0..4 {
anchor_color[k] *= coeff[k];
@@ -351,7 +352,7 @@ impl DebugRenderPipeline {
object: DebugRenderObject,
backend: &mut impl DebugRenderBackend,
shape: &dyn Shape,
- pos: &Isometry<Real>,
+ pos: &Isometry,
color: [f32; 4],
) {
match shape.as_typed_shape() {
@@ -451,7 +452,7 @@ impl DebugRenderPipeline {
object: DebugRenderObject,
backend: &mut impl DebugRenderBackend,
shape: &dyn Shape,
- pos: &Isometry<Real>,
+ pos: &Isometry,
color: [f32; 4],
) {
match shape.as_typed_shape() {
diff --git a/src/pipeline/debug_render_pipeline/outlines.rs b/src/pipeline/debug_render_pipeline/outlines.rs
index cd0b6ed..56e26ec 100644
--- a/src/pipeline/debug_render_pipeline/outlines.rs
+++ b/src/pipeline/debug_render_pipeline/outlines.rs
@@ -1,12 +1,12 @@
use crate::geometry::{Ball, Cuboid};
#[cfg(feature = "dim3")]
use crate::geometry::{Cone, Cylinder};
-use crate::math::{Point, Real, Vector};
+use crate::math::*;
use std::any::TypeId;
use std::collections::HashMap;
#[cfg(feature = "dim2")]
-pub fn instances(nsubdivs: u32) -> HashMap<TypeId, Vec<Point<Real>>> {
+pub fn instances(nsubdivs: u32) -> HashMap<TypeId, Vec<Point>> {
let mut result = HashMap::new();
result.insert(
TypeId::of::<Cuboid>(),
@@ -18,7 +18,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]>)> {
+pub fn instances(nsubdivs: u32) -> HashMap<TypeId, (Vec<Point>, Vec<[u32; 2]>)> {
let mut result = HashMap::new();
result.insert(
TypeId::of::<Cuboid>(),
diff --git a/src/pipeline/event_handler.rs b/src/pipeline/event_handler.rs
index 7957ccf..ba11b03 100644
--- a/src/pipeline/event_handler.rs
+++ b/src/pipeline/event_handler.rs
@@ -3,8 +3,16 @@ use crate::geometry::{ColliderSet, CollisionEvent, ContactForceEvent, ContactPai
use crate::math::Real;
use crossbeam::channel::Sender;
+#[cfg(feature = "bevy")]
+use bevy::prelude::{Component, Reflect, ReflectComponent};
+
bitflags::bitflags! {
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
+ #[cfg_attr(
+ feature = "bevy",
+ derive(Component, Reflect),
+ reflect(Component, PartialEq)
+ )]
/// Flags affecting the events generated for this collider.
pub struct ActiveEvents: u32 {
/// If set, Rapier will call `EventHandler::handle_collision_event`
diff --git a/src/pipeline/physics_hooks.rs b/src/pipeline/physics_hooks.rs
index 11166b5..ed130c7 100644
--- a/src/pipeline/physics_hooks.rs
+++ b/src/pipeline/physics_hooks.rs
@@ -1,8 +1,11 @@
use crate::dynamics::{RigidBodyHandle, RigidBodySet};
use crate::geometry::{ColliderHandle, ColliderSet, ContactManifold, SolverContact, SolverFlags};
-use crate::math::{Real, Vector};
+use crate::math::*;
use na::ComplexField;
+#[cfg(feature = "bevy")]
+use bevy::prelude::{Component, Reflect, ReflectComponent};
+
/// Context given to custom collision filters to filter-out collisions.
pub struct PairFilterContext<'a> {
/// The set of rigid-bodies.
@@ -38,7 +41,7 @@ pub struct ContactModificationContext<'a> {
/// The solver contacts that can be modified.
pub solver_contacts: &'a mut Vec<SolverContact>,
/// The contact normal that can be modified.
- pub normal: &'a mut Vector<Real>,
+ pub normal: &'a mut Vector,
/// User-defined data attached to the manifold.
// NOTE: we keep this a &'a mut u32 to emphasize the
// fact that this can be modified.
@@ -56,11 +59,7 @@ impl<'a> ContactModificationContext<'a> {
/// `PhysicsHooks::modify_solver_contacts` method at each timestep, for each
/// contact manifold involving a one-way platform. The `self.user_data` field
/// must not be modified from the outside of this method.
- pub fn update_as_oneway_platform(
- &mut self,
- allowed_local_n1: &Vector<Real>,
- allowed_angle: Real,
- ) {
+ pub fn update_as_oneway_platform(&mut self, allowed_local_n1: &Vector, allowed_angle: Real) {
const CONTACT_CONFIGURATION_UNKNOWN: u32 = 0;
const CONTACT_CURRENTLY_ALLOWED: u32 = 1;
const CONTACT_CURRENTLY_FORBIDDEN: u32 = 2;
@@ -69,7 +68,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 => {
@@ -118,6 +117,11 @@ impl<'a> ContactModificationContext<'a> {
bitflags::bitflags! {
#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
+ #[cfg_attr(
+ feature = "bevy",
+ derive(Component, Reflect),
+ reflect(Component, Hash, PartialEq)
+ )]
/// Flags affecting the behavior of the constraints solver for a given contact manifold.
pub struct ActiveHooks: u32 {
/// If set, Rapier will call `PhysicsHooks::filter_contact_pair` whenever relevant.
diff --git a/src/pipeline/physics_pipeline.rs b/src/pipeline/physics_pipeline.rs
index 6dbc4e5..82c9e9d 100644
--- a/src/pipeline/physics_pipeline.rs
+++ b/src/pipeline/physics_pipeline.rs
@@ -13,7 +13,7 @@ use crate::geometry::{
BroadPhase, BroadPhasePairEvent, ColliderChanges, ColliderHandle, ColliderPair,
ContactManifoldIndex, NarrowPhase, TemporaryInteractionIndex,
};
-use crate::math::{Real, Vector};
+use crate::math::*;
use crate::pipeline::{EventHandler, PhysicsHooks, QueryPipeline};
use {crate::dynamics::RigidBodySet, crate::geometry::ColliderSet};
@@ -158,7 +158,7 @@ impl PhysicsPipeline {
fn build_islands_and_solve_velocity_constraints(
&mut self,
- gravity: &Vector<Real>,
+ gravity: &Vector,
integration_parameters: &IntegrationParameters,
islands: &mut IslandManager,
narrow_phase: &mut NarrowPhase,
@@ -403,7 +403,7 @@ impl PhysicsPipeline {
/// Executes one timestep of the physics simulation.
pub fn step(
&mut self,
- gravity: &Vector<Real>,
+ gravity: &Vector,
integration_parameters: &IntegrationParameters,
islands: &mut IslandManager,
broad_phase: &mut BroadPhase,
@@ -564,6 +564,7 @@ impl PhysicsPipeline {
self.counters.ccd.num_substeps += 1;
self.interpolate_kinematic_velocities(&integration_parameters, islands, bodies);
+
self.build_islands_and_solve_velocity_constraints(
gravity,
&integration_parameters,
diff --git a/src/pipeline/query_pipeline.rs b/src/pipeline/query_pipeline.rs
index 4dc5652..7b6f9b9 100644
--- a/src/pipeline/query_pipeline.rs
+++ b/src/pipeline/query_pipeline.rs
@@ -2,7 +2,7 @@ use crate::dynamics::RigidBodyHandle;
use crate::geometry::{
Aabb, Collider, ColliderHandle, InteractionGroups, PointProjection, Qbvh, Ray, RayIntersection,
};
-use crate::math::{Isometry, Point, Real, Vector};
+use crate::math::*;
use crate::{dynamics::RigidBodySet, geometry::ColliderSet};
use parry::partitioning::{QbvhDataGenerator, QbvhUpdateWorkspace};
use parry::query::details::{
@@ -252,7 +252,7 @@ impl<'a> TypedSimdCompositeShape for QueryPipelineAsCompositeShape<'a> {
fn map_typed_part_at(
&self,
shape_id: Self::PartId,
- mut f: impl FnMut(Option<&Isometry<Real>>, &Self::PartShape),
+ mut f: impl FnMut(Option<&Isometry>, &Self::PartShape),
) {
if let Some(co) = self.colliders.get(shape_id) {
if self.filter.test(self.bodies, shape_id, co) {
@@ -264,7 +264,7 @@ impl<'a> TypedSimdCompositeShape for QueryPipelineAsCompositeShape<'a> {
fn map_untyped_part_at(
&self,
shape_id: Self::PartId,
- f: impl FnMut(Option<&Isometry<Real>>, &Self::PartShape),
+ f: impl FnMut(Option<&Isometry>, &Self::PartShape),
) {
self.map_typed_part_at(shape_id, f);
}
@@ -380,12 +380,12 @@ impl QueryPipeline {
fn for_each(&mut self, mut f: impl FnMut(ColliderHandle, Aabb)) {
match self.mode {
QueryPipelineMode::CurrentPosition => {
- for (h, co) in self.colliders.iter_enabled() {
+ for (h, co) in self.colliders.iter_enabled_internal() {
f(h, co.shape.compute_aabb(&co.pos))
}
}
QueryPipelineMode::SweepTestWithNextPosition => {
- for (h, co) in self.colliders.iter_enabled() {
+ for (h, co) in self.colliders.iter_enabled_internal() {
if let Some(co_parent) = co.parent {
let rb_next_pos = &self.bodies[co_parent.handle].pos.next_position;
let next_position = rb_next_pos * co_parent.pos_wrt_parent;
@@ -396,7 +396,7 @@ impl QueryPipeline {
}
}
QueryPipelineMode::SweepTestWithPredictedPosition { dt } => {
- for (h, co) in self.colliders.iter_enabled() {
+ for (h, co) in self.colliders.iter_enabled_internal() {
if let Some(co_parent) = co.parent {
let rb = &self.bodies[co_parent.handle];
let predicted_pos = rb.pos.integrate_forces_and_velocities(
@@ -534,7 +534,7 @@ impl QueryPipeline {
&self,
bodies: &RigidBodySet,
colliders: &ColliderSet,
- shape_pos: &Isometry<Real>,
+ shape_pos: &Isometry,
shape: &dyn Shape,
filter: QueryFilter,
) -> Option<ColliderHandle> {
@@ -570,7 +570,7 @@ impl QueryPipeline {
&self,
bodies: &RigidBodySet,
colliders: &ColliderSet,
- point: &Point<Real>,
+ point: &Point,
solid: bool,
filter: QueryFilter,
) -> Option<(ColliderHandle, PointProjection)> {
@@ -595,7 +595,7 @@ impl QueryPipeline {
&self,
bodies: &RigidBodySet,
colliders: &ColliderSet,
- point: &Point<Real>,
+ point: &Point,
filter: QueryFilter,
mut callback: impl FnMut(ColliderHandle) -> bool,
) {
@@ -631,7 +631,7 @@ impl QueryPipeline {
&self,
bodies: &RigidBodySet,
colliders: &ColliderSet,
- point: &Point<Real>,
+ point: &Point,
filter: QueryFilter,
) -> Option<(ColliderHandle, PointProjection, FeatureId)> {
let pipeline_shape = self.as_composite_shape(bodies, colliders, filter);
@@ -673,8 +673,8 @@ impl QueryPipeline {
&self,
bodies: &RigidBodySet,
colliders: &ColliderSet,
- shape_pos: &Isometry<Real>,
- shape_vel: &Vector<Real>,
+ shape_pos: &Isometry,
+ shape_vel: &Vector,
shape: &dyn Shape,
max_toi: Real,
stop_at_penetration: bool,
@@ -751,7 +751,7 @@ impl QueryPipeline {
&self,
bodies: &RigidBodySet,
colliders: &ColliderSet,
- shape_pos: &Isometry<Real>,
+ shape_pos: &Isometry,
shape: &dyn Shape,
filter: QueryFilter,
mut callback: impl FnMut(ColliderHandle) -> bool,