aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorCrozet Sébastien <developer@crozet.re>2021-05-25 11:00:13 +0200
committerCrozet Sébastien <developer@crozet.re>2021-05-25 11:00:13 +0200
commit1bef66fea941307a7305ddaebdb0abe3d0cb281f (patch)
tree450bc3cd2fd611f91cb7d7809edcc4260f043b0b
parent47139323e01f978a94ed7aa2c33bbf63b00f4c30 (diff)
downloadrapier-1bef66fea941307a7305ddaebdb0abe3d0cb281f.tar.gz
rapier-1bef66fea941307a7305ddaebdb0abe3d0cb281f.tar.bz2
rapier-1bef66fea941307a7305ddaebdb0abe3d0cb281f.zip
Add prelude + use vectors for setting linvel/translation in builders
-rw-r--r--CHANGELOG.md23
-rw-r--r--benchmarks2d/balls2.rs14
-rw-r--r--benchmarks2d/boxes2.rs22
-rw-r--r--benchmarks2d/capsules2.rs22
-rw-r--r--benchmarks2d/convex_polygons2.rs24
-rw-r--r--benchmarks2d/heightfield2.rs19
-rw-r--r--benchmarks2d/joint_ball2.rs14
-rw-r--r--benchmarks2d/joint_fixed2.rs18
-rw-r--r--benchmarks2d/joint_prismatic2.rs24
-rw-r--r--benchmarks2d/pyramid2.rs14
-rw-r--r--benchmarks3d/balls3.rs12
-rw-r--r--benchmarks3d/boxes3.rs16
-rw-r--r--benchmarks3d/capsules3.rs16
-rw-r--r--benchmarks3d/ccd3.rs16
-rw-r--r--benchmarks3d/compound3.rs24
-rw-r--r--benchmarks3d/convex_polyhedron3.rs18
-rw-r--r--benchmarks3d/heightfield3.rs19
-rw-r--r--benchmarks3d/joint_ball3.rs17
-rw-r--r--benchmarks3d/joint_fixed3.rs21
-rw-r--r--benchmarks3d/joint_prismatic3.rs31
-rw-r--r--benchmarks3d/joint_revolute3.rs37
-rw-r--r--benchmarks3d/keva3.rs38
-rw-r--r--benchmarks3d/pyramid3.rs24
-rw-r--r--benchmarks3d/stacks3.rs60
-rw-r--r--benchmarks3d/trimesh3.rs19
-rw-r--r--examples2d/add_remove2.rs10
-rw-r--r--examples2d/ccd2.rs52
-rw-r--r--examples2d/collision_groups2.rs33
-rw-r--r--examples2d/convex_polygons2.rs24
-rw-r--r--examples2d/damping2.rs14
-rw-r--r--examples2d/debug_box_ball2.rs14
-rw-r--r--examples2d/heightfield2.rs19
-rw-r--r--examples2d/joints2.rs16
-rw-r--r--examples2d/locked_rotations2.rs18
-rw-r--r--examples2d/one_way_platforms2.rs39
-rw-r--r--examples2d/platform2.rs20
-rw-r--r--examples2d/polyline2.rs23
-rw-r--r--examples2d/pyramid2.rs14
-rw-r--r--examples2d/restitution2.rs14
-rw-r--r--examples2d/sensor2.rs40
-rw-r--r--examples2d/trimesh2.rs22
-rw-r--r--examples3d/ccd3.rs70
-rw-r--r--examples3d/collision_groups3.rs33
-rw-r--r--examples3d/compound3.rs32
-rw-r--r--examples3d/convex_decomposition3.rs18
-rw-r--r--examples3d/convex_polyhedron3.rs18
-rw-r--r--examples3d/damping3.rs16
-rw-r--r--examples3d/debug_add_remove_collider3.rs22
-rw-r--r--examples3d/debug_big_colliders3.rs14
-rw-r--r--examples3d/debug_boxes3.rs16
-rw-r--r--examples3d/debug_cylinder3.rs16
-rw-r--r--examples3d/debug_dynamic_collider_add3.rs28
-rw-r--r--examples3d/debug_friction3.rs16
-rw-r--r--examples3d/debug_infinite_fall3.rs18
-rw-r--r--examples3d/debug_prismatic3.rs50
-rw-r--r--examples3d/debug_rollback3.rs22
-rw-r--r--examples3d/debug_shape_modification3.rs28
-rw-r--r--examples3d/debug_triangle3.rs20
-rw-r--r--examples3d/debug_trimesh3.rs32
-rw-r--r--examples3d/domino3.rs20
-rw-r--r--examples3d/fountain3.rs14
-rw-r--r--examples3d/harness_capsules3.rs15
-rw-r--r--examples3d/heightfield3.rs23
-rw-r--r--examples3d/joints3.rs143
-rw-r--r--examples3d/keva3.rs38
-rw-r--r--examples3d/locked_rotations3.rs22
-rw-r--r--examples3d/one_way_platforms3.rs39
-rw-r--r--examples3d/platform3.rs20
-rw-r--r--examples3d/primitives3.rs16
-rw-r--r--examples3d/restitution3.rs14
-rw-r--r--examples3d/sensor3.rs39
-rw-r--r--examples3d/trimesh3.rs23
-rw-r--r--src/data/coarena.rs8
-rw-r--r--src/dynamics/integration_parameters.rs13
-rw-r--r--src/dynamics/joint/fixed_joint.rs10
-rw-r--r--src/dynamics/rigid_body.rs174
-rw-r--r--src/dynamics/solver/joint_constraint/fixed_position_constraint.rs34
-rw-r--r--src/dynamics/solver/joint_constraint/fixed_velocity_constraint.rs12
-rw-r--r--src/dynamics/solver/joint_constraint/fixed_velocity_constraint_wide.rs24
-rw-r--r--src/geometry/collider.rs179
-rw-r--r--src/geometry/collider_components.rs10
-rw-r--r--src/geometry/collider_set.rs44
-rw-r--r--src/geometry/contact_pair.rs16
-rw-r--r--src/geometry/interaction_groups.rs54
-rw-r--r--src/geometry/narrow_phase.rs108
-rw-r--r--src/lib.rs9
-rw-r--r--src/pipeline/physics_hooks.rs47
-rw-r--r--src_testbed/box2d_backend.rs25
-rw-r--r--src_testbed/graphics.rs65
-rw-r--r--src_testbed/nphysics_backend.rs36
-rw-r--r--src_testbed/objects/node.rs14
-rw-r--r--src_testbed/physx_backend.rs45
-rw-r--r--src_testbed/testbed.rs25
93 files changed, 1525 insertions, 1256 deletions
diff --git a/CHANGELOG.md b/CHANGELOG.md
index 2d3dcf9..f7c1d3d 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -1,8 +1,31 @@
## v0.9.0
+The user-guide has been fully rewritten and is now exhaustive! Check it out on [rapier.rs](https://rapier.rs/)
+
+### Added
+- A prelude has been added in order to simplify the most common imports. For example: `use rapier3d::prelude::*`
### Modified
- Renamed `BodyStatus` to `RigidBodyType`.
+FIXME:
+- `RigidBodyBuilder::translation` now takes a vector instead of individual components.
+- `RigidBodyBuilder::linvel` now takes a vector instead of individual components.
+- `Colliderbuilder::translation` now takes a vector instead of individual components.
+- The way `PhysicsHooks` are enabled changed. Now, a physics hooks is executed if any of the two
+ colliders involved in the contact/intersection pair contains the related `PhysicsHooksFlag`.
+ These flags are configured on each collider with `ColliderBuilder::active_hooks`. As a result,
+ there is no `PhysicsHooks::active_hooks` method any more.
+- Before, sensor colliders had a default density set to 0.0 whereas non-sensor colliders had a
+ default density of 1.0. This has been unified by setting the default density to 1.0 for both
+ sensor and non-sensor colliders.
+- Colliders are no longer required to be attached to a rigid-body. Therefore, `ColliderSet::insert`
+ only takes the collider as argument now. In order to attach the collider to a rigid-body,
+ (i.e., the old behavior of `ColliderSet::insert`), use `ColliderSet::insert_with_parent`.
+- The field `ContactPair::pair` (which contained two collider handles) has been replaced by two
+ fields: `ContactPair::collider1` and `ContactPair::collider2`.
+- The fields `FixedJoint::local_anchor1` and `FixedJoint::local_anchor2` have been renamed to
+ `FixedJoint::local_frame1` and `FixedJoint::local_frame2`.
+
## v0.8.0
### Modified
- Switch to nalgebra 0.26.
diff --git a/benchmarks2d/balls2.rs b/benchmarks2d/balls2.rs
index 8fa9775..ec55f24 100644
--- a/benchmarks2d/balls2.rs
+++ b/benchmarks2d/balls2.rs
@@ -1,6 +1,4 @@
-use na::Point2;
-use rapier2d::dynamics::{JointSet, RigidBodyBuilder, RigidBodySet, RigidBodyType};
-use rapier2d::geometry::{ColliderBuilder, ColliderSet};
+use rapier2d::prelude::*;
use rapier_testbed2d::Testbed;
pub fn init_world(testbed: &mut Testbed) {
@@ -22,7 +20,7 @@ pub fn init_world(testbed: &mut Testbed) {
let co = ColliderDesc::new(ground_shape)
.translation(-Vector2::y())
.build(BodyPartHandle(ground_handle, 0));
- colliders.insert(co);
+ colliders.insert_with_parent(co);
*/
/*
@@ -48,10 +46,12 @@ pub fn init_world(testbed: &mut Testbed) {
};
// Build the rigid body.
- let rigid_body = RigidBodyBuilder::new(status).translation(x, y).build();
+ let rigid_body = RigidBodyBuilder::new(status)
+ .translation(vector![x, y])
+ .build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::ball(rad).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
}
}
@@ -59,5 +59,5 @@ pub fn init_world(testbed: &mut Testbed) {
* Set up the testbed.
*/
testbed.set_world(bodies, colliders, joints);
- testbed.look_at(Point2::new(0.0, 2.5), 5.0);
+ testbed.look_at(point![0.0, 2.5], 5.0);
}
diff --git a/benchmarks2d/boxes2.rs b/benchmarks2d/boxes2.rs
index e524386..2e4c5e4 100644
--- a/benchmarks2d/boxes2.rs
+++ b/benchmarks2d/boxes2.rs
@@ -1,6 +1,4 @@
-use na::Point2;
-use rapier2d::dynamics::{JointSet, RigidBodyBuilder, RigidBodySet};
-use rapier2d::geometry::{ColliderBuilder, ColliderSet};
+use rapier2d::prelude::*;
use rapier_testbed2d::Testbed;
pub fn init_world(testbed: &mut Testbed) {
@@ -19,23 +17,23 @@ pub fn init_world(testbed: &mut Testbed) {
let rigid_body = RigidBodyBuilder::new_static().build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
let rigid_body = RigidBodyBuilder::new_static()
.rotation(std::f32::consts::FRAC_PI_2)
- .translation(ground_size, ground_size * 2.0)
+ .translation(vector![ground_size, ground_size * 2.0])
.build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size * 2.0, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
let rigid_body = RigidBodyBuilder::new_static()
.rotation(std::f32::consts::FRAC_PI_2)
- .translation(-ground_size, ground_size * 2.0)
+ .translation(vector![-ground_size, ground_size * 2.0])
.build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size * 2.0, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
/*
* Create the cubes
@@ -53,10 +51,12 @@ pub fn init_world(testbed: &mut Testbed) {
let y = j as f32 * shift + centery + 2.0;
// Build the rigid body.
- let rigid_body = RigidBodyBuilder::new_dynamic().translation(x, y).build();
+ let rigid_body = RigidBodyBuilder::new_dynamic()
+ .translation(vector![x, y])
+ .build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(rad, rad).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
}
}
@@ -64,5 +64,5 @@ pub fn init_world(testbed: &mut Testbed) {
* Set up the testbed.
*/
testbed.set_world(bodies, colliders, joints);
- testbed.look_at(Point2::new(0.0, 50.0), 10.0);
+ testbed.look_at(point![0.0, 50.0], 10.0);
}
diff --git a/benchmarks2d/capsules2.rs b/benchmarks2d/capsules2.rs
index 89ddfde..e75afe4 100644
--- a/benchmarks2d/capsules2.rs
+++ b/benchmarks2d/capsules2.rs
@@ -1,6 +1,4 @@
-use na::Point2;
-use rapier2d::dynamics::{JointSet, RigidBodyBuilder, RigidBodySet};
-use rapier2d::geometry::{ColliderBuilder, ColliderSet};
+use rapier2d::prelude::*;
use rapier_testbed2d::Testbed;
pub fn init_world(testbed: &mut Testbed) {
@@ -19,23 +17,23 @@ pub fn init_world(testbed: &mut Testbed) {
let rigid_body = RigidBodyBuilder::new_static().build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
let rigid_body = RigidBodyBuilder::new_static()
.rotation(std::f32::consts::FRAC_PI_2)
- .translation(ground_size, ground_size * 4.0)
+ .translation(vector![ground_size, ground_size * 4.0])
.build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size * 4.0, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
let rigid_body = RigidBodyBuilder::new_static()
.rotation(std::f32::consts::FRAC_PI_2)
- .translation(-ground_size, ground_size * 4.0)
+ .translation(vector![-ground_size, ground_size * 4.0])
.build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size * 4.0, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
/*
* Create the cubes
@@ -55,10 +53,12 @@ pub fn init_world(testbed: &mut Testbed) {
let y = j as f32 * shifty + centery + 3.0;
// Build the rigid body.
- let rigid_body = RigidBodyBuilder::new_dynamic().translation(x, y).build();
+ let rigid_body = RigidBodyBuilder::new_dynamic()
+ .translation(vector![x, y])
+ .build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::capsule_y(rad * 1.5, rad).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
}
}
@@ -66,5 +66,5 @@ pub fn init_world(testbed: &mut Testbed) {
* Set up the testbed.
*/
testbed.set_world(bodies, colliders, joints);
- testbed.look_at(Point2::new(0.0, 50.0), 10.0);
+ testbed.look_at(point![0.0, 50.0], 10.0);
}
diff --git a/benchmarks2d/convex_polygons2.rs b/benchmarks2d/convex_polygons2.rs
index 99f5a14..6c9792e 100644
--- a/benchmarks2d/convex_polygons2.rs
+++ b/benchmarks2d/convex_polygons2.rs
@@ -1,8 +1,6 @@
-use na::Point2;
use rand::distributions::{Distribution, Standard};
use rand::{rngs::StdRng, SeedableRng};
-use rapier2d::dynamics::{JointSet, RigidBodyBuilder, RigidBodySet};
-use rapier2d::geometry::{ColliderBuilder, ColliderSet};
+use rapier2d::prelude::*;
use rapier_testbed2d::Testbed;
pub fn init_world(testbed: &mut Testbed) {
@@ -21,23 +19,23 @@ pub fn init_world(testbed: &mut Testbed) {
let rigid_body = RigidBodyBuilder::new_static().build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
let rigid_body = RigidBodyBuilder::new_static()
.rotation(std::f32::consts::FRAC_PI_2)
- .translation(ground_size, ground_size * 2.0)
+ .translation(vector![ground_size, ground_size * 2.0])
.build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size * 2.0, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
let rigid_body = RigidBodyBuilder::new_static()
.rotation(std::f32::consts::FRAC_PI_2)
- .translation(-ground_size, ground_size * 2.0)
+ .translation(vector![-ground_size, ground_size * 2.0])
.build();
let handle = bodies.insert(rigid_body);
let collider = ColliderBuilder::cuboid(ground_size * 2.0, 1.2).build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
/*
* Create the convex polygons
@@ -58,18 +56,20 @@ pub fn init_world(testbed: &mut Testbed) {
let x = i as f32 * shift - centerx;
let y = j as f32 * shift * 2.0 + centery + 2.0;
- let rigid_body = RigidBodyBuilder::new_dynamic().translation(x, y).build();
+ let rigid_body = RigidBodyBuilder::new_dynamic()
+ .translation(vector![x, y])
+ .build();
let handle = bodies.insert(rigid_body);
let mut points = Vec::new();
for _ in 0..10 {
- let pt: Point2<f32> = distribution.sample(&mut rng);
+ let pt: Point<f32> = distribution.sample(&mut rng);
points.push(pt * scale);
}
let collider = ColliderBuilder::convex_hull(&points).unwrap().build();
- colliders.insert(collider, handle, &mut bodies);
+ colliders.insert_with_parent(collider, handle, &mut bodies);
}
}
@@ -77,5 +77,5 @@ pub fn init_world(testbed: &mut Testbed) {
* Set up the testbed.
*/
testbed.set_world(bodies, colliders, joints);
- testbed.look_at(Point2::new(0.0, 50.0), 10.0);
+ testbed.look_at(point![0.0, 50.0], 10.0);
}
diff --git a/benchmarks2d/heightfield2.rs b/benchmarks2d/heightfield2.rs
index 1a30849..a07eb6e 100644
--- a/