rapier2d/geometry/collider.rs
1use crate::dynamics::{CoefficientCombineRule, MassProperties, RigidBodyHandle, RigidBodySet};
2#[cfg(feature = "dim3")]
3use crate::geometry::HeightFieldFlags;
4use crate::geometry::{
5 ActiveCollisionTypes, ColliderChanges, ColliderFlags, ColliderMassProps, ColliderMaterial,
6 ColliderParent, ColliderPosition, ColliderShape, ColliderType, InteractionGroups,
7 MeshConverter, MeshConverterError, SharedShape,
8};
9use crate::math::{AngVector, DIM, Isometry, Point, Real, Rotation, Vector};
10use crate::parry::transformation::vhacd::VHACDParameters;
11use crate::pipeline::{ActiveEvents, ActiveHooks};
12use crate::prelude::{ColliderEnabled, IntegrationParameters};
13use na::Unit;
14use parry::bounding_volume::{Aabb, BoundingVolume};
15use parry::shape::{Shape, TriMeshBuilderError, TriMeshFlags};
16use parry::transformation::voxelization::FillMode;
17
18#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
19#[derive(Clone, Debug)]
20/// The collision shape attached to a rigid body that defines what it can collide with.
21///
22/// Think of a collider as the "hitbox" or "collision shape" for your physics object. While a
23/// [`RigidBody`](crate::dynamics::RigidBody) handles the physics (mass, velocity, forces),
24/// the collider defines what shape the object has for collision detection.
25///
26/// ## Key concepts
27///
28/// - **Shape**: The geometric form (box, sphere, capsule, mesh, etc.)
29/// - **Material**: Physical properties like friction (slipperiness) and restitution (bounciness)
30/// - **Sensor vs. Solid**: Sensors detect overlaps but don't create physical collisions
31/// - **Mass properties**: Automatically computed from the shape's volume and density
32///
33/// ## Creating colliders
34///
35/// Always use [`ColliderBuilder`] to create colliders:
36///
37/// ```ignore
38/// let collider = ColliderBuilder::cuboid(1.0, 0.5, 1.0) // 2x1x2 box
39/// .friction(0.7)
40/// .restitution(0.3);
41/// colliders.insert_with_parent(collider, body_handle, &mut bodies);
42/// ```
43///
44/// ## Attaching to bodies
45///
46/// Colliders are usually attached to rigid bodies. One body can have multiple colliders
47/// to create compound shapes (like a character with separate colliders for head, torso, limbs).
48pub struct Collider {
49 pub(crate) coll_type: ColliderType,
50 pub(crate) shape: ColliderShape,
51 pub(crate) mprops: ColliderMassProps,
52 pub(crate) changes: ColliderChanges,
53 pub(crate) parent: Option<ColliderParent>,
54 pub(crate) pos: ColliderPosition,
55 pub(crate) material: ColliderMaterial,
56 pub(crate) flags: ColliderFlags,
57 contact_skin: Real,
58 contact_force_event_threshold: Real,
59 /// User-defined data associated to this collider.
60 pub user_data: u128,
61}
62
63impl Collider {
64 pub(crate) fn reset_internal_references(&mut self) {
65 self.changes = ColliderChanges::all();
66 }
67
68 pub(crate) fn effective_contact_force_event_threshold(&self) -> Real {
69 if self
70 .flags
71 .active_events
72 .contains(ActiveEvents::CONTACT_FORCE_EVENTS)
73 {
74 self.contact_force_event_threshold
75 } else {
76 Real::MAX
77 }
78 }
79
80 /// The rigid body this collider is attached to, if any.
81 ///
82 /// Returns `None` for standalone colliders (not attached to any body).
83 pub fn parent(&self) -> Option<RigidBodyHandle> {
84 self.parent.map(|parent| parent.handle)
85 }
86
87 /// Checks if this collider is a sensor (detects overlaps without physical collision).
88 ///
89 /// Sensors are like "trigger zones" - they detect when other colliders enter/exit them
90 /// but don't create physical contact forces. Use for:
91 /// - Trigger zones (checkpoint areas, damage regions)
92 /// - Proximity detection
93 /// - Collectible items
94 /// - Area-of-effect detection
95 pub fn is_sensor(&self) -> bool {
96 self.coll_type.is_sensor()
97 }
98
99 /// Copy all the characteristics from `other` to `self`.
100 ///
101 /// If you have a mutable reference to a collider `collider: &mut Collider`, attempting to
102 /// assign it a whole new collider instance, e.g., `*collider = ColliderBuilder::ball(0.5).build()`,
103 /// will crash due to some internal indices being overwritten. Instead, use
104 /// `collider.copy_from(&ColliderBuilder::ball(0.5).build())`.
105 ///
106 /// This method will allow you to set most characteristics of this collider from another
107 /// collider instance without causing any breakage.
108 ///
109 /// This method **cannot** be used for reparenting a collider. Therefore, the parent of the
110 /// `other` (if any), as well as its relative position to that parent will not be copied into
111 /// `self`.
112 ///
113 /// The pose of `other` will only copied into `self` if `self` doesn’t have a parent (if it has
114 /// a parent, its position is directly controlled by the parent rigid-body).
115 pub fn copy_from(&mut self, other: &Collider) {
116 // NOTE: we deconstruct the collider struct to be sure we don’t forget to
117 // add some copies here if we add more field to Collider in the future.
118 let Collider {
119 coll_type,
120 shape,
121 mprops,
122 changes: _changes, // Will be set to ALL.
123 parent: _parent, // This function cannot be used to reparent the collider.
124 pos,
125 material,
126 flags,
127 contact_force_event_threshold,
128 user_data,
129 contact_skin,
130 } = other;
131
132 if self.parent.is_none() {
133 self.pos = *pos;
134 }
135
136 self.coll_type = *coll_type;
137 self.shape = shape.clone();
138 self.mprops = mprops.clone();
139 self.material = *material;
140 self.contact_force_event_threshold = *contact_force_event_threshold;
141 self.user_data = *user_data;
142 self.flags = *flags;
143 self.changes = ColliderChanges::all();
144 self.contact_skin = *contact_skin;
145 }
146
147 /// Which physics hooks are enabled for this collider.
148 ///
149 /// Hooks allow custom filtering and modification of collisions. See [`PhysicsHooks`](crate::pipeline::PhysicsHooks).
150 pub fn active_hooks(&self) -> ActiveHooks {
151 self.flags.active_hooks
152 }
153
154 /// Enables/disables physics hooks for this collider.
155 ///
156 /// Use to opt colliders into custom collision filtering logic.
157 pub fn set_active_hooks(&mut self, active_hooks: ActiveHooks) {
158 self.flags.active_hooks = active_hooks;
159 }
160
161 /// Which events are enabled for this collider.
162 ///
163 /// Controls whether you receive collision/contact force events. See [`ActiveEvents`](crate::pipeline::ActiveEvents).
164 pub fn active_events(&self) -> ActiveEvents {
165 self.flags.active_events
166 }
167
168 /// Enables/disables event generation for this collider.
169 ///
170 /// Set to `ActiveEvents::COLLISION_EVENTS` to receive started/stopped collision notifications.
171 /// Set to `ActiveEvents::CONTACT_FORCE_EVENTS` to receive force threshold events.
172 pub fn set_active_events(&mut self, active_events: ActiveEvents) {
173 self.flags.active_events = active_events;
174 }
175
176 /// The collision types enabled for this collider.
177 pub fn active_collision_types(&self) -> ActiveCollisionTypes {
178 self.flags.active_collision_types
179 }
180
181 /// Sets the collision types enabled for this collider.
182 pub fn set_active_collision_types(&mut self, active_collision_types: ActiveCollisionTypes) {
183 self.flags.active_collision_types = active_collision_types;
184 }
185
186 /// The contact skin of this collider.
187 ///
188 /// See the documentation of [`ColliderBuilder::contact_skin`] for details.
189 pub fn contact_skin(&self) -> Real {
190 self.contact_skin
191 }
192
193 /// Sets the contact skin of this collider.
194 ///
195 /// See the documentation of [`ColliderBuilder::contact_skin`] for details.
196 pub fn set_contact_skin(&mut self, skin_thickness: Real) {
197 self.contact_skin = skin_thickness;
198 }
199
200 /// The friction coefficient of this collider (how "slippery" it is).
201 ///
202 /// - `0.0` = perfectly slippery (ice)
203 /// - `1.0` = high friction (rubber on concrete)
204 /// - Typical values: 0.3-0.8
205 pub fn friction(&self) -> Real {
206 self.material.friction
207 }
208
209 /// Sets the friction coefficient (slipperiness).
210 ///
211 /// Controls how much this surface resists sliding. Higher values = more grip.
212 /// Works with other collider's friction via the combine rule.
213 pub fn set_friction(&mut self, coefficient: Real) {
214 self.material.friction = coefficient
215 }
216
217 /// The combine rule used by this collider to combine its friction
218 /// coefficient with the friction coefficient of the other collider it
219 /// is in contact with.
220 pub fn friction_combine_rule(&self) -> CoefficientCombineRule {
221 self.material.friction_combine_rule
222 }
223
224 /// Sets the combine rule used by this collider to combine its friction
225 /// coefficient with the friction coefficient of the other collider it
226 /// is in contact with.
227 pub fn set_friction_combine_rule(&mut self, rule: CoefficientCombineRule) {
228 self.material.friction_combine_rule = rule;
229 }
230
231 /// The restitution coefficient of this collider (how "bouncy" it is).
232 ///
233 /// - `0.0` = no bounce (clay, soft material)
234 /// - `1.0` = perfect bounce (ideal elastic collision)
235 /// - `>1.0` = super bouncy (gains energy, unrealistic but fun!)
236 /// - Typical values: 0.0-0.8
237 pub fn restitution(&self) -> Real {
238 self.material.restitution
239 }
240
241 /// Sets the restitution coefficient (bounciness).
242 ///
243 /// Controls how much velocity is preserved after impact. Higher values = more bounce.
244 /// Works with other collider's restitution via the combine rule.
245 pub fn set_restitution(&mut self, coefficient: Real) {
246 self.material.restitution = coefficient
247 }
248
249 /// The combine rule used by this collider to combine its restitution
250 /// coefficient with the restitution coefficient of the other collider it
251 /// is in contact with.
252 pub fn restitution_combine_rule(&self) -> CoefficientCombineRule {
253 self.material.restitution_combine_rule
254 }
255
256 /// Sets the combine rule used by this collider to combine its restitution
257 /// coefficient with the restitution coefficient of the other collider it
258 /// is in contact with.
259 pub fn set_restitution_combine_rule(&mut self, rule: CoefficientCombineRule) {
260 self.material.restitution_combine_rule = rule;
261 }
262
263 /// Sets the total force magnitude beyond which a contact force event can be emitted.
264 pub fn set_contact_force_event_threshold(&mut self, threshold: Real) {
265 self.contact_force_event_threshold = threshold;
266 }
267
268 /// Converts this collider to/from a sensor.
269 ///
270 /// Sensors detect overlaps but don't create physical contact forces.
271 /// Use `true` for trigger zones, `false` for solid collision shapes.
272 pub fn set_sensor(&mut self, is_sensor: bool) {
273 if is_sensor != self.is_sensor() {
274 self.changes.insert(ColliderChanges::TYPE);
275 self.coll_type = if is_sensor {
276 ColliderType::Sensor
277 } else {
278 ColliderType::Solid
279 };
280 }
281 }
282
283 /// Returns `true` if this collider is active in the simulation.
284 ///
285 /// Disabled colliders are excluded from collision detection and physics.
286 pub fn is_enabled(&self) -> bool {
287 matches!(self.flags.enabled, ColliderEnabled::Enabled)
288 }
289
290 /// Enables or disables this collider.
291 ///
292 /// When disabled, the collider is excluded from all collision detection and physics.
293 /// Useful for temporarily "turning off" colliders without removing them.
294 pub fn set_enabled(&mut self, enabled: bool) {
295 match self.flags.enabled {
296 ColliderEnabled::Enabled | ColliderEnabled::DisabledByParent => {
297 if !enabled {
298 self.changes.insert(ColliderChanges::ENABLED_OR_DISABLED);
299 self.flags.enabled = ColliderEnabled::Disabled;
300 }
301 }
302 ColliderEnabled::Disabled => {
303 if enabled {
304 self.changes.insert(ColliderChanges::ENABLED_OR_DISABLED);
305 self.flags.enabled = ColliderEnabled::Enabled;
306 }
307 }
308 }
309 }
310
311 /// Sets the collider's position (for standalone colliders).
312 ///
313 /// For attached colliders, modify the parent body's position instead.
314 /// This directly sets world-space position.
315 pub fn set_translation(&mut self, translation: Vector<Real>) {
316 self.changes.insert(ColliderChanges::POSITION);
317 self.pos.0.translation.vector = translation;
318 }
319
320 /// Sets the collider's rotation (for standalone colliders).
321 ///
322 /// For attached colliders, modify the parent body's rotation instead.
323 pub fn set_rotation(&mut self, rotation: Rotation<Real>) {
324 self.changes.insert(ColliderChanges::POSITION);
325 self.pos.0.rotation = rotation;
326 }
327
328 /// Sets the collider's full pose (for standalone colliders).
329 ///
330 /// For attached colliders, modify the parent body instead.
331 pub fn set_position(&mut self, position: Isometry<Real>) {
332 self.changes.insert(ColliderChanges::POSITION);
333 self.pos.0 = position;
334 }
335
336 /// The current world-space position of this collider.
337 ///
338 /// For attached colliders, this is automatically updated when the parent body moves.
339 /// For standalone colliders, this is the position you set directly.
340 pub fn position(&self) -> &Isometry<Real> {
341 &self.pos
342 }
343
344 /// The current position vector of this collider (world coordinates).
345 pub fn translation(&self) -> &Vector<Real> {
346 &self.pos.0.translation.vector
347 }
348
349 /// The current rotation/orientation of this collider.
350 pub fn rotation(&self) -> &Rotation<Real> {
351 &self.pos.0.rotation
352 }
353
354 /// The collider's position relative to its parent body (local coordinates).
355 ///
356 /// Returns `None` for standalone colliders. This is the offset from the parent body's origin.
357 pub fn position_wrt_parent(&self) -> Option<&Isometry<Real>> {
358 self.parent.as_ref().map(|p| &p.pos_wrt_parent)
359 }
360
361 /// Changes this collider's position offset from its parent body.
362 ///
363 /// Useful for adjusting where a collider sits on a body without moving the whole body.
364 /// Does nothing if the collider has no parent.
365 pub fn set_translation_wrt_parent(&mut self, translation: Vector<Real>) {
366 if let Some(parent) = self.parent.as_mut() {
367 self.changes.insert(ColliderChanges::PARENT);
368 parent.pos_wrt_parent.translation.vector = translation;
369 }
370 }
371
372 /// Changes this collider's rotation offset from its parent body.
373 ///
374 /// Rotates the collider relative to its parent. Does nothing if no parent.
375 pub fn set_rotation_wrt_parent(&mut self, rotation: AngVector<Real>) {
376 if let Some(parent) = self.parent.as_mut() {
377 self.changes.insert(ColliderChanges::PARENT);
378 parent.pos_wrt_parent.rotation = Rotation::new(rotation);
379 }
380 }
381
382 /// Changes this collider's full pose (position + rotation) relative to its parent.
383 ///
384 /// Does nothing if the collider is not attached to a rigid-body.
385 pub fn set_position_wrt_parent(&mut self, pos_wrt_parent: Isometry<Real>) {
386 if let Some(parent) = self.parent.as_mut() {
387 self.changes.insert(ColliderChanges::PARENT);
388 parent.pos_wrt_parent = pos_wrt_parent;
389 }
390 }
391
392 /// The collision groups controlling what this collider can interact with.
393 ///
394 /// See [`InteractionGroups`] for details on collision filtering.
395 pub fn collision_groups(&self) -> InteractionGroups {
396 self.flags.collision_groups
397 }
398
399 /// Changes which collision groups this collider belongs to and can interact with.
400 ///
401 /// Use to control collision filtering (like changing layers).
402 pub fn set_collision_groups(&mut self, groups: InteractionGroups) {
403 if self.flags.collision_groups != groups {
404 self.changes.insert(ColliderChanges::GROUPS);
405 self.flags.collision_groups = groups;
406 }
407 }
408
409 /// The solver groups for this collider (advanced collision filtering).
410 ///
411 /// Most users should use `collision_groups()` instead.
412 pub fn solver_groups(&self) -> InteractionGroups {
413 self.flags.solver_groups
414 }
415
416 /// Changes the solver groups (advanced contact resolution filtering).
417 pub fn set_solver_groups(&mut self, groups: InteractionGroups) {
418 if self.flags.solver_groups != groups {
419 self.changes.insert(ColliderChanges::GROUPS);
420 self.flags.solver_groups = groups;
421 }
422 }
423
424 /// Returns the material properties (friction and restitution) of this collider.
425 pub fn material(&self) -> &ColliderMaterial {
426 &self.material
427 }
428
429 /// Returns the volume (3D) or area (2D) of this collider's shape.
430 ///
431 /// Used internally for mass calculations when density is set.
432 pub fn volume(&self) -> Real {
433 self.shape.mass_properties(1.0).mass()
434 }
435
436 /// The density of this collider (mass per unit volume).
437 ///
438 /// Used to automatically compute mass from the collider's volume.
439 /// Returns an approximate density if mass was set directly instead.
440 pub fn density(&self) -> Real {
441 match &self.mprops {
442 ColliderMassProps::Density(density) => *density,
443 ColliderMassProps::Mass(mass) => {
444 let inv_volume = self.shape.mass_properties(1.0).inv_mass;
445 mass * inv_volume
446 }
447 ColliderMassProps::MassProperties(mprops) => {
448 let inv_volume = self.shape.mass_properties(1.0).inv_mass;
449 mprops.mass() * inv_volume
450 }
451 }
452 }
453
454 /// The mass contributed by this collider to its parent body.
455 ///
456 /// Either set directly or computed from density × volume.
457 pub fn mass(&self) -> Real {
458 match &self.mprops {
459 ColliderMassProps::Density(density) => self.shape.mass_properties(*density).mass(),
460 ColliderMassProps::Mass(mass) => *mass,
461 ColliderMassProps::MassProperties(mprops) => mprops.mass(),
462 }
463 }
464
465 /// Sets the uniform density of this collider.
466 ///
467 /// This will override any previous mass-properties set by [`Self::set_density`],
468 /// [`Self::set_mass`], [`Self::set_mass_properties`], [`ColliderBuilder::density`],
469 /// [`ColliderBuilder::mass`], or [`ColliderBuilder::mass_properties`]
470 /// for this collider.
471 ///
472 /// The mass and angular inertia of this collider will be computed automatically based on its
473 /// shape.
474 pub fn set_density(&mut self, density: Real) {
475 self.do_set_mass_properties(ColliderMassProps::Density(density));
476 }
477
478 /// Sets the mass of this collider.
479 ///
480 /// This will override any previous mass-properties set by [`Self::set_density`],
481 /// [`Self::set_mass`], [`Self::set_mass_properties`], [`ColliderBuilder::density`],
482 /// [`ColliderBuilder::mass`], or [`ColliderBuilder::mass_properties`]
483 /// for this collider.
484 ///
485 /// The angular inertia of this collider will be computed automatically based on its shape
486 /// and this mass value.
487 pub fn set_mass(&mut self, mass: Real) {
488 self.do_set_mass_properties(ColliderMassProps::Mass(mass));
489 }
490
491 /// Sets the mass properties of this collider.
492 ///
493 /// This will override any previous mass-properties set by [`Self::set_density`],
494 /// [`Self::set_mass`], [`Self::set_mass_properties`], [`ColliderBuilder::density`],
495 /// [`ColliderBuilder::mass`], or [`ColliderBuilder::mass_properties`]
496 /// for this collider.
497 pub fn set_mass_properties(&mut self, mass_properties: MassProperties) {
498 self.do_set_mass_properties(ColliderMassProps::MassProperties(Box::new(mass_properties)))
499 }
500
501 fn do_set_mass_properties(&mut self, mprops: ColliderMassProps) {
502 if mprops != self.mprops {
503 self.changes |= ColliderChanges::LOCAL_MASS_PROPERTIES;
504 self.mprops = mprops;
505 }
506 }
507
508 /// The geometric shape of this collider (ball, cuboid, mesh, etc.).
509 ///
510 /// Returns a reference to the underlying shape object for reading properties
511 /// or performing geometric queries.
512 pub fn shape(&self) -> &dyn Shape {
513 self.shape.as_ref()
514 }
515
516 /// A mutable reference to the geometric shape of this collider.
517 ///
518 /// If that shape is shared by multiple colliders, it will be
519 /// cloned first so that `self` contains a unique copy of that
520 /// shape that you can modify.
521 pub fn shape_mut(&mut self) -> &mut dyn Shape {
522 self.changes.insert(ColliderChanges::SHAPE);
523 self.shape.make_mut()
524 }
525
526 /// Sets the shape of this collider.
527 pub fn set_shape(&mut self, shape: SharedShape) {
528 self.changes.insert(ColliderChanges::SHAPE);
529 self.shape = shape;
530 }
531
532 /// Returns the shape as a `SharedShape` (reference-counted shape).
533 ///
534 /// Use `shape()` for the trait object, this for the concrete type.
535 pub fn shared_shape(&self) -> &SharedShape {
536 &self.shape
537 }
538
539 /// Computes the axis-aligned bounding box (AABB) of this collider.
540 ///
541 /// The AABB is the smallest box (aligned with world axes) that contains the shape.
542 /// Doesn't include contact skin.
543 pub fn compute_aabb(&self) -> Aabb {
544 self.shape.compute_aabb(&self.pos)
545 }
546
547 /// Computes the AABB including contact skin and prediction distance.
548 ///
549 /// This is the AABB used for collision detection (slightly larger than the visual shape).
550 pub fn compute_collision_aabb(&self, prediction: Real) -> Aabb {
551 self.shape
552 .compute_aabb(&self.pos)
553 .loosened(self.contact_skin + prediction)
554 }
555
556 /// Computes the AABB swept from current position to `next_position`.
557 ///
558 /// Returns a box that contains the shape at both positions plus everything in between.
559 /// Used for continuous collision detection.
560 pub fn compute_swept_aabb(&self, next_position: &Isometry<Real>) -> Aabb {
561 self.shape.compute_swept_aabb(&self.pos, next_position)
562 }
563
564 // TODO: we have a lot of different AABB computation functions
565 // We should group them somehow.
566 /// Computes the collider’s AABB for usage in a broad-phase.
567 ///
568 /// It takes into account soft-ccd, the contact skin, and the contact prediction.
569 pub fn compute_broad_phase_aabb(
570 &self,
571 params: &IntegrationParameters,
572 bodies: &RigidBodySet,
573 ) -> Aabb {
574 // Take soft-ccd into account by growing the aabb.
575 let next_pose = self.parent.and_then(|p| {
576 let parent = bodies.get(p.handle)?;
577 (parent.soft_ccd_prediction() > 0.0).then(|| {
578 parent.predict_position_using_velocity_and_forces_with_max_dist(
579 params.dt,
580 parent.soft_ccd_prediction(),
581 ) * p.pos_wrt_parent
582 })
583 });
584
585 let prediction_distance = params.prediction_distance();
586 let mut aabb = self.compute_collision_aabb(prediction_distance / 2.0);
587 if let Some(next_pose) = next_pose {
588 let next_aabb = self
589 .shape
590 .compute_aabb(&next_pose)
591 .loosened(self.contact_skin() + prediction_distance / 2.0);
592 aabb.merge(&next_aabb);
593 }
594
595 aabb
596 }
597
598 /// Computes the full mass properties (mass, center of mass, angular inertia).
599 ///
600 /// Returns properties in the collider's local coordinate system.
601 pub fn mass_properties(&self) -> MassProperties {
602 self.mprops.mass_properties(&*self.shape)
603 }
604
605 /// Returns the force threshold for contact force events.
606 ///
607 /// When contact forces exceed this value, a `ContactForceEvent` is generated.
608 /// See `set_contact_force_event_threshold()` for details.
609 pub fn contact_force_event_threshold(&self) -> Real {
610 self.contact_force_event_threshold
611 }
612}
613
614/// A builder for creating colliders with custom shapes and properties.
615///
616/// This builder lets you create collision shapes and configure their physical properties
617/// (friction, bounciness, density, etc.) before adding them to your world.
618///
619/// # Common shapes
620///
621/// - [`ball(radius)`](Self::ball) - Sphere (3D) or circle (2D)
622/// - [`cuboid(hx, hy, hz)`](Self::cuboid) - Box with half-extents
623/// - [`capsule_y(half_height, radius)`](Self::capsule_y) - Pill shape (great for characters)
624/// - [`trimesh(vertices, indices)`](Self::trimesh) - Triangle mesh for complex geometry
625/// - [`heightfield(...)`](Self::heightfield) - Terrain from height data
626///
627/// # Example
628///
629/// ```ignore
630/// // Create a bouncy ball
631/// let collider = ColliderBuilder::ball(0.5)
632/// .restitution(0.9) // Very bouncy
633/// .friction(0.1) // Low friction (slippery)
634/// .density(2.0); // Heavy material
635/// colliders.insert_with_parent(collider, body_handle, &mut bodies);
636/// ```
637#[derive(Clone, Debug)]
638#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
639#[must_use = "Builder functions return the updated builder"]
640pub struct ColliderBuilder {
641 /// The shape of the collider to be built.
642 pub shape: SharedShape,
643 /// Controls the way the collider’s mass-properties are computed.
644 pub mass_properties: ColliderMassProps,
645 /// The friction coefficient of the collider to be built.
646 pub friction: Real,
647 /// The rule used to combine two friction coefficients.
648 pub friction_combine_rule: CoefficientCombineRule,
649 /// The restitution coefficient of the collider to be built.
650 pub restitution: Real,
651 /// The rule used to combine two restitution coefficients.
652 pub restitution_combine_rule: CoefficientCombineRule,
653 /// The position of this collider.
654 pub position: Isometry<Real>,
655 /// Is this collider a sensor?
656 pub is_sensor: bool,
657 /// Contact pairs enabled for this collider.
658 pub active_collision_types: ActiveCollisionTypes,
659 /// Physics hooks enabled for this collider.
660 pub active_hooks: ActiveHooks,
661 /// Events enabled for this collider.
662 pub active_events: ActiveEvents,
663 /// The user-data of the collider being built.
664 pub user_data: u128,
665 /// The collision groups for the collider being built.
666 pub collision_groups: InteractionGroups,
667 /// The solver groups for the collider being built.
668 pub solver_groups: InteractionGroups,
669 /// Will the collider being built be enabled?
670 pub enabled: bool,
671 /// The total force magnitude beyond which a contact force event can be emitted.
672 pub contact_force_event_threshold: Real,
673 /// An extra thickness around the collider shape to keep them further apart when colliding.
674 pub contact_skin: Real,
675}
676
677impl Default for ColliderBuilder {
678 fn default() -> Self {
679 Self::ball(0.5)
680 }
681}
682
683impl ColliderBuilder {
684 /// Initialize a new collider builder with the given shape.
685 pub fn new(shape: SharedShape) -> Self {
686 Self {
687 shape,
688 mass_properties: ColliderMassProps::default(),
689 friction: Self::default_friction(),
690 restitution: 0.0,
691 position: Isometry::identity(),
692 is_sensor: false,
693 user_data: 0,
694 collision_groups: InteractionGroups::all(),
695 solver_groups: InteractionGroups::all(),
696 friction_combine_rule: CoefficientCombineRule::Average,
697 restitution_combine_rule: CoefficientCombineRule::Average,
698 active_collision_types: ActiveCollisionTypes::default(),
699 active_hooks: ActiveHooks::empty(),
700 active_events: ActiveEvents::empty(),
701 enabled: true,
702 contact_force_event_threshold: 0.0,
703 contact_skin: 0.0,
704 }
705 }
706
707 /// Initialize a new collider builder with a compound shape.
708 pub fn compound(shapes: Vec<(Isometry<Real>, SharedShape)>) -> Self {
709 Self::new(SharedShape::compound(shapes))
710 }
711
712 /// Creates a sphere (3D) or circle (2D) collider.
713 ///
714 /// The simplest and fastest collision shape. Use for:
715 /// - Balls and spheres
716 /// - Approximate round objects
717 /// - Projectiles
718 /// - Particles
719 ///
720 /// # Parameters
721 /// * `radius` - The sphere's radius
722 pub fn ball(radius: Real) -> Self {
723 Self::new(SharedShape::ball(radius))
724 }
725
726 /// Initialize a new collider build with a half-space shape defined by the outward normal
727 /// of its planar boundary.
728 pub fn halfspace(outward_normal: Unit<Vector<Real>>) -> Self {
729 Self::new(SharedShape::halfspace(outward_normal))
730 }
731
732 /// Initializes a shape made of voxels.
733 ///
734 /// Each voxel has the size `voxel_size` and grid coordinate given by `voxels`.
735 /// The `primitive_geometry` controls the behavior of collision detection at voxels boundaries.
736 ///
737 /// For initializing a voxels shape from points in space, see [`Self::voxels_from_points`].
738 /// For initializing a voxels shape from a mesh to voxelize, see [`Self::voxelized_mesh`].
739 pub fn voxels(voxel_size: Vector<Real>, voxels: &[Point<i32>]) -> Self {
740 Self::new(SharedShape::voxels(voxel_size, voxels))
741 }
742
743 /// Initializes a collider made of voxels.
744 ///
745 /// Each voxel has the size `voxel_size` and contains at least one point from `centers`.
746 /// The `primitive_geometry` controls the behavior of collision detection at voxels boundaries.
747 pub fn voxels_from_points(voxel_size: Vector<Real>, points: &[Point<Real>]) -> Self {
748 Self::new(SharedShape::voxels_from_points(voxel_size, points))
749 }
750
751 /// Initializes a voxels obtained from the decomposition of the given trimesh (in 3D)
752 /// or polyline (in 2D) into voxelized convex parts.
753 pub fn voxelized_mesh(
754 vertices: &[Point<Real>],
755 indices: &[[u32; DIM]],
756 voxel_size: Real,
757 fill_mode: FillMode,
758 ) -> Self {
759 Self::new(SharedShape::voxelized_mesh(
760 vertices, indices, voxel_size, fill_mode,
761 ))
762 }
763
764 /// Initialize a new collider builder with a cylindrical shape defined by its half-height
765 /// (along the Y axis) and its radius.
766 #[cfg(feature = "dim3")]
767 pub fn cylinder(half_height: Real, radius: Real) -> Self {
768 Self::new(SharedShape::cylinder(half_height, radius))
769 }
770
771 /// Initialize a new collider builder with a rounded cylindrical shape defined by its half-height
772 /// (along the Y axis), its radius, and its roundedness (the radius of the sphere used for
773 /// dilating the cylinder).
774 #[cfg(feature = "dim3")]
775 pub fn round_cylinder(half_height: Real, radius: Real, border_radius: Real) -> Self {
776 Self::new(SharedShape::round_cylinder(
777 half_height,
778 radius,
779 border_radius,
780 ))
781 }
782
783 /// Initialize a new collider builder with a cone shape defined by its half-height
784 /// (along the Y axis) and its basis radius.
785 #[cfg(feature = "dim3")]
786 pub fn cone(half_height: Real, radius: Real) -> Self {
787 Self::new(SharedShape::cone(half_height, radius))
788 }
789
790 /// Initialize a new collider builder with a rounded cone shape defined by its half-height
791 /// (along the Y axis), its radius, and its roundedness (the radius of the sphere used for
792 /// dilating the cylinder).
793 #[cfg(feature = "dim3")]
794 pub fn round_cone(half_height: Real, radius: Real, border_radius: Real) -> Self {
795 Self::new(SharedShape::round_cone(half_height, radius, border_radius))
796 }
797
798 /// Initialize a new collider builder with a cuboid shape defined by its half-extents.
799 #[cfg(feature = "dim2")]
800 pub fn cuboid(hx: Real, hy: Real) -> Self {
801 Self::new(SharedShape::cuboid(hx, hy))
802 }
803
804 /// Initialize a new collider builder with a round cuboid shape defined by its half-extents
805 /// and border radius.
806 #[cfg(feature = "dim2")]
807 pub fn round_cuboid(hx: Real, hy: Real, border_radius: Real) -> Self {
808 Self::new(SharedShape::round_cuboid(hx, hy, border_radius))
809 }
810
811 /// Initialize a new collider builder with a capsule defined from its endpoints.
812 ///
813 /// See also [`ColliderBuilder::capsule_x`], [`ColliderBuilder::capsule_y`],
814 /// (and `ColliderBuilder::capsule_z` in 3D only)
815 /// for a simpler way to build capsules with common
816 /// orientations.
817 pub fn capsule_from_endpoints(a: Point<Real>, b: Point<Real>, radius: Real) -> Self {
818 Self::new(SharedShape::capsule(a, b, radius))
819 }
820
821 /// Initialize a new collider builder with a capsule shape aligned with the `x` axis.
822 pub fn capsule_x(half_height: Real, radius: Real) -> Self {
823 Self::new(SharedShape::capsule_x(half_height, radius))
824 }
825
826 /// Creates a capsule (pill-shaped) collider aligned with the Y axis.
827 ///
828 /// Capsules are cylinders with hemispherical caps. Excellent for characters because:
829 /// - Smooth collision (no getting stuck on edges)
830 /// - Good for upright objects (characters, trees)
831 /// - Fast collision detection
832 ///
833 /// # Parameters
834 /// * `half_height` - Half the height of the cylindrical part (not including caps)
835 /// * `radius` - Radius of the cylinder and caps
836 ///
837 /// **Example**: `capsule_y(1.0, 0.5)` creates a 3.0 tall capsule (1.0×2 cylinder + 0.5×2 caps)
838 pub fn capsule_y(half_height: Real, radius: Real) -> Self {
839 Self::new(SharedShape::capsule_y(half_height, radius))
840 }
841
842 /// Initialize a new collider builder with a capsule shape aligned with the `z` axis.
843 #[cfg(feature = "dim3")]
844 pub fn capsule_z(half_height: Real, radius: Real) -> Self {
845 Self::new(SharedShape::capsule_z(half_height, radius))
846 }
847
848 /// Creates a box collider defined by its half-extents (half-widths).
849 ///
850 /// Very fast collision detection. Use for:
851 /// - Boxes and crates
852 /// - Buildings and rooms
853 /// - Most rectangular objects
854 ///
855 /// # Parameters (3D)
856 /// * `hx`, `hy`, `hz` - Half-extents (half the width) along each axis
857 ///
858 /// **Example**: `cuboid(1.0, 0.5, 2.0)` creates a box with full size 2×1×4
859 #[cfg(feature = "dim3")]
860 pub fn cuboid(hx: Real, hy: Real, hz: Real) -> Self {
861 Self::new(SharedShape::cuboid(hx, hy, hz))
862 }
863
864 /// Initialize a new collider builder with a round cuboid shape defined by its half-extents
865 /// and border radius.
866 #[cfg(feature = "dim3")]
867 pub fn round_cuboid(hx: Real, hy: Real, hz: Real, border_radius: Real) -> Self {
868 Self::new(SharedShape::round_cuboid(hx, hy, hz, border_radius))
869 }
870
871 /// Creates a line segment collider between two points.
872 ///
873 /// Useful for thin barriers, edges, or 2D line-based collision.
874 /// Has no thickness - purely a mathematical line.
875 pub fn segment(a: Point<Real>, b: Point<Real>) -> Self {
876 Self::new(SharedShape::segment(a, b))
877 }
878
879 /// Creates a single triangle collider.
880 ///
881 /// Use for simple 3-sided shapes or as building blocks for more complex geometry.
882 pub fn triangle(a: Point<Real>, b: Point<Real>, c: Point<Real>) -> Self {
883 Self::new(SharedShape::triangle(a, b, c))
884 }
885
886 /// Initializes a collider builder with a triangle shape with round corners.
887 pub fn round_triangle(
888 a: Point<Real>,
889 b: Point<Real>,
890 c: Point<Real>,
891 border_radius: Real,
892 ) -> Self {
893 Self::new(SharedShape::round_triangle(a, b, c, border_radius))
894 }
895
896 /// Initializes a collider builder with a polyline shape defined by its vertex and index buffers.
897 pub fn polyline(vertices: Vec<Point<Real>>, indices: Option<Vec<[u32; 2]>>) -> Self {
898 Self::new(SharedShape::polyline(vertices, indices))
899 }
900
901 /// Creates a triangle mesh collider from vertices and triangle indices.
902 ///
903 /// Use for complex, arbitrary shapes like:
904 /// - Level geometry and terrain
905 /// - Imported 3D models
906 /// - Custom irregular shapes
907 ///
908 /// **Performance note**: Triangle meshes are slower than primitive shapes (balls, boxes, capsules).
909 /// Consider using compound shapes or simpler approximations when possible.
910 ///
911 /// # Parameters
912 /// * `vertices` - Array of 3D points
913 /// * `indices` - Array of triangles, each is 3 indices into the vertex array
914 ///
915 /// # Example
916 /// ```ignore
917 /// use rapier3d::prelude::*;
918 /// use nalgebra::Point3;
919 ///
920 /// let vertices = vec![
921 /// Point3::new(0.0, 0.0, 0.0),
922 /// Point3::new(1.0, 0.0, 0.0),
923 /// Point3::new(0.0, 1.0, 0.0),
924 /// ];
925 /// let triangle: [u32; 3] = [0, 1, 2];
926 /// let indices = vec![triangle]; // One triangle
927 /// let collider = ColliderBuilder::trimesh(vertices, indices)?;
928 /// ```
929 pub fn trimesh(
930 vertices: Vec<Point<Real>>,
931 indices: Vec<[u32; 3]>,
932 ) -> Result<Self, TriMeshBuilderError> {
933 Ok(Self::new(SharedShape::trimesh(vertices, indices)?))
934 }
935
936 /// Initializes a collider builder with a triangle mesh shape defined by its vertex and index buffers and
937 /// flags controlling its pre-processing.
938 pub fn trimesh_with_flags(
939 vertices: Vec<Point<Real>>,
940 indices: Vec<[u32; 3]>,
941 flags: TriMeshFlags,
942 ) -> Result<Self, TriMeshBuilderError> {
943 Ok(Self::new(SharedShape::trimesh_with_flags(
944 vertices, indices, flags,
945 )?))
946 }
947
948 /// Initializes a collider builder with a shape converted from the given triangle mesh index
949 /// and vertex buffer.
950 ///
951 /// All the conversion variants could be achieved with other constructors of [`ColliderBuilder`]
952 /// but having this specified by an enum can occasionally be easier or more flexible (determined
953 /// at runtime).
954 pub fn converted_trimesh(
955 vertices: Vec<Point<Real>>,
956 indices: Vec<[u32; 3]>,
957 converter: MeshConverter,
958 ) -> Result<Self, MeshConverterError> {
959 let (shape, pose) = converter.convert(vertices, indices)?;
960 Ok(Self::new(shape).position(pose))
961 }
962
963 /// Creates a compound collider by decomposing a mesh/polyline into convex pieces.
964 ///
965 /// Concave shapes (like an 'L' or 'C') are automatically broken into multiple convex
966 /// parts for efficient collision detection. This is often faster than using a trimesh.
967 ///
968 /// Uses the V-HACD algorithm. Good for imported models that aren't already convex.
969 pub fn convex_decomposition(vertices: &[Point<Real>], indices: &[[u32; DIM]]) -> Self {
970 Self::new(SharedShape::convex_decomposition(vertices, indices))
971 }
972
973 /// Initializes a collider builder with a compound shape obtained from the decomposition of
974 /// the given trimesh (in 3D) or polyline (in 2D) into convex parts dilated with round corners.
975 pub fn round_convex_decomposition(
976 vertices: &[Point<Real>],
977 indices: &[[u32; DIM]],
978 border_radius: Real,
979 ) -> Self {
980 Self::new(SharedShape::round_convex_decomposition(
981 vertices,
982 indices,
983 border_radius,
984 ))
985 }
986
987 /// Initializes a collider builder with a compound shape obtained from the decomposition of
988 /// the given trimesh (in 3D) or polyline (in 2D) into convex parts.
989 pub fn convex_decomposition_with_params(
990 vertices: &[Point<Real>],
991 indices: &[[u32; DIM]],
992 params: &VHACDParameters,
993 ) -> Self {
994 Self::new(SharedShape::convex_decomposition_with_params(
995 vertices, indices, params,
996 ))
997 }
998
999 /// Initializes a collider builder with a compound shape obtained from the decomposition of
1000 /// the given trimesh (in 3D) or polyline (in 2D) into convex parts dilated with round corners.
1001 pub fn round_convex_decomposition_with_params(
1002 vertices: &[Point<Real>],
1003 indices: &[[u32; DIM]],
1004 params: &VHACDParameters,
1005 border_radius: Real,
1006 ) -> Self {
1007 Self::new(SharedShape::round_convex_decomposition_with_params(
1008 vertices,
1009 indices,
1010 params,
1011 border_radius,
1012 ))
1013 }
1014
1015 /// Creates the smallest convex shape that contains all the given points.
1016 ///
1017 /// Computes the "shrink-wrap" around a point cloud. Useful for:
1018 /// - Creating collision shapes from vertex data
1019 /// - Approximating complex shapes with a simpler convex one
1020 ///
1021 /// Returns `None` if the points don't form a valid convex shape.
1022 ///
1023 /// **Performance**: Convex shapes are much faster than triangle meshes!
1024 pub fn convex_hull(points: &[Point<Real>]) -> Option<Self> {
1025 SharedShape::convex_hull(points).map(Self::new)
1026 }
1027
1028 /// Initializes a new collider builder with a round 2D convex polygon or 3D convex polyhedron
1029 /// obtained after computing the convex-hull of the given points. The shape is dilated
1030 /// by a sphere of radius `border_radius`.
1031 pub fn round_convex_hull(points: &[Point<Real>], border_radius: Real) -> Option<Self> {
1032 SharedShape::round_convex_hull(points, border_radius).map(Self::new)
1033 }
1034
1035 /// Creates a new collider builder that is a convex polygon formed by the
1036 /// given polyline assumed to be convex (no convex-hull will be automatically
1037 /// computed).
1038 #[cfg(feature = "dim2")]
1039 pub fn convex_polyline(points: Vec<Point<Real>>) -> Option<Self> {
1040 SharedShape::convex_polyline(points).map(Self::new)
1041 }
1042
1043 /// Creates a new collider builder that is a round convex polygon formed by the
1044 /// given polyline assumed to be convex (no convex-hull will be automatically
1045 /// computed). The polygon shape is dilated by a sphere of radius `border_radius`.
1046 #[cfg(feature = "dim2")]
1047 pub fn round_convex_polyline(points: Vec<Point<Real>>, border_radius: Real) -> Option<Self> {
1048 SharedShape::round_convex_polyline(points, border_radius).map(Self::new)
1049 }
1050
1051 /// Creates a new collider builder that is a convex polyhedron formed by the
1052 /// given triangle-mesh assumed to be convex (no convex-hull will be automatically
1053 /// computed).
1054 #[cfg(feature = "dim3")]
1055 pub fn convex_mesh(points: Vec<Point<Real>>, indices: &[[u32; 3]]) -> Option<Self> {
1056 SharedShape::convex_mesh(points, indices).map(Self::new)
1057 }
1058
1059 /// Creates a new collider builder that is a round convex polyhedron formed by the
1060 /// given triangle-mesh assumed to be convex (no convex-hull will be automatically
1061 /// computed). The triangle mesh shape is dilated by a sphere of radius `border_radius`.
1062 #[cfg(feature = "dim3")]
1063 pub fn round_convex_mesh(
1064 points: Vec<Point<Real>>,
1065 indices: &[[u32; 3]],
1066 border_radius: Real,
1067 ) -> Option<Self> {
1068 SharedShape::round_convex_mesh(points, indices, border_radius).map(Self::new)
1069 }
1070
1071 /// Initializes a collider builder with a heightfield shape defined by its set of height and a scale
1072 /// factor along each coordinate axis.
1073 #[cfg(feature = "dim2")]
1074 pub fn heightfield(heights: na::DVector<Real>, scale: Vector<Real>) -> Self {
1075 Self::new(SharedShape::heightfield(heights, scale))
1076 }
1077
1078 /// Creates a terrain/landscape collider from a 2D grid of height values.
1079 ///
1080 /// Perfect for outdoor terrain in 3D games. The heightfield is a grid where each cell
1081 /// stores a height value, creating a landscape surface.
1082 ///
1083 /// Use for:
1084 /// - Terrain and landscapes
1085 /// - Hills and valleys
1086 /// - Ground surfaces in open worlds
1087 ///
1088 /// # Parameters
1089 /// * `heights` - 2D matrix of height values (Y coordinates)
1090 /// * `scale` - Size of each grid cell in X and Z directions
1091 ///
1092 /// **Performance**: Much faster than triangle meshes for terrain!
1093 #[cfg(feature = "dim3")]
1094 pub fn heightfield(heights: na::DMatrix<Real>, scale: Vector<Real>) -> Self {
1095 Self::new(SharedShape::heightfield(heights, scale))
1096 }
1097
1098 /// Initializes a collider builder with a heightfield shape defined by its set of height and a scale
1099 /// factor along each coordinate axis.
1100 #[cfg(feature = "dim3")]
1101 pub fn heightfield_with_flags(
1102 heights: na::DMatrix<Real>,
1103 scale: Vector<Real>,
1104 flags: HeightFieldFlags,
1105 ) -> Self {
1106 Self::new(SharedShape::heightfield_with_flags(heights, scale, flags))
1107 }
1108
1109 /// Returns the default friction value used when not specified (0.5).
1110 pub fn default_friction() -> Real {
1111 0.5
1112 }
1113
1114 /// Returns the default density value used when not specified (1.0).
1115 pub fn default_density() -> Real {
1116 1.0
1117 }
1118
1119 /// Stores custom user data with this collider (128-bit integer).
1120 ///
1121 /// Use to associate game data (entity ID, type, etc.) with physics objects.
1122 ///
1123 /// # Example
1124 /// ```ignore
1125 /// let collider = ColliderBuilder::ball(0.5)
1126 /// .user_data(entity_id as u128)
1127 /// .build();
1128 /// ```
1129 pub fn user_data(mut self, data: u128) -> Self {
1130 self.user_data = data;
1131 self
1132 }
1133
1134 /// Sets which collision groups this collider belongs to and can interact with.
1135 ///
1136 /// Use this to control what can collide with what (like collision layers).
1137 /// See [`InteractionGroups`] for examples.
1138 ///
1139 /// # Example
1140 /// ```ignore
1141 /// // Player bullet: in group 1, only hits group 2 (enemies)
1142 /// let groups = InteractionGroups::new(Group::GROUP_1, Group::GROUP_2);
1143 /// let bullet = ColliderBuilder::ball(0.1)
1144 /// .collision_groups(groups)
1145 /// .build();
1146 /// ```
1147 pub fn collision_groups(mut self, groups: InteractionGroups) -> Self {
1148 self.collision_groups = groups;
1149 self
1150 }
1151
1152 /// Sets solver groups (advanced collision filtering for contact resolution).
1153 ///
1154 /// Similar to collision_groups but specifically for the contact solver.
1155 /// Most users should use `collision_groups()` instead - this is for advanced scenarios
1156 /// where you want collisions detected but not resolved (e.g., one-way platforms).
1157 pub fn solver_groups(mut self, groups: InteractionGroups) -> Self {
1158 self.solver_groups = groups;
1159 self
1160 }
1161
1162 /// Makes this collider a sensor (trigger zone) instead of a solid collision shape.
1163 ///
1164 /// Sensors detect overlaps but don't create physical collisions. Use for:
1165 /// - Trigger zones (checkpoints, danger areas)
1166 /// - Collectible item detection
1167 /// - Proximity sensors
1168 /// - Win/lose conditions
1169 ///
1170 /// You'll receive collision events when objects enter/exit the sensor.
1171 ///
1172 /// # Example
1173 /// ```ignore
1174 /// let trigger = ColliderBuilder::cuboid(5.0, 5.0, 5.0)
1175 /// .sensor(true)
1176 /// .build();
1177 /// ```
1178 pub fn sensor(mut self, is_sensor: bool) -> Self {
1179 self.is_sensor = is_sensor;
1180 self
1181 }
1182
1183 /// Enables custom physics hooks for this collider (advanced).
1184 ///
1185 /// See [`ActiveHooks`](crate::pipeline::ActiveHooks) for details on custom collision filtering.
1186 pub fn active_hooks(mut self, active_hooks: ActiveHooks) -> Self {
1187 self.active_hooks = active_hooks;
1188 self
1189 }
1190
1191 /// Enables event generation for this collider.
1192 ///
1193 /// Set to `ActiveEvents::COLLISION_EVENTS` for start/stop notifications.
1194 /// Set to `ActiveEvents::CONTACT_FORCE_EVENTS` for force threshold events.
1195 ///
1196 /// # Example
1197 /// ```ignore
1198 /// let sensor = ColliderBuilder::ball(1.0)
1199 /// .sensor(true)
1200 /// .active_events(ActiveEvents::COLLISION_EVENTS)
1201 /// .build();
1202 /// ```
1203 pub fn active_events(mut self, active_events: ActiveEvents) -> Self {
1204 self.active_events = active_events;
1205 self
1206 }
1207
1208 /// Sets which body type combinations can collide with this collider.
1209 ///
1210 /// See [`ActiveCollisionTypes`] for details. Most users don't need to change this.
1211 pub fn active_collision_types(mut self, active_collision_types: ActiveCollisionTypes) -> Self {
1212 self.active_collision_types = active_collision_types;
1213 self
1214 }
1215
1216 /// Sets the friction coefficient (slipperiness) for this collider.
1217 ///
1218 /// - `0.0` = ice (very slippery)
1219 /// - `0.5` = wood on wood
1220 /// - `1.0` = rubber (high grip)
1221 ///
1222 /// Default is `0.5`.
1223 pub fn friction(mut self, friction: Real) -> Self {
1224 self.friction = friction;
1225 self
1226 }
1227
1228 /// Sets how friction coefficients are combined when two colliders touch.
1229 ///
1230 /// Options: Average, Min, Max, Multiply. Default is Average.
1231 /// Most games can ignore this and use the default.
1232 pub fn friction_combine_rule(mut self, rule: CoefficientCombineRule) -> Self {
1233 self.friction_combine_rule = rule;
1234 self
1235 }
1236
1237 /// Sets the restitution coefficient (bounciness) for this collider.
1238 ///
1239 /// - `0.0` = no bounce (clay, soft)
1240 /// - `0.5` = moderate bounce
1241 /// - `1.0` = perfect elastic bounce
1242 /// - `>1.0` = super bouncy (gains energy!)
1243 ///
1244 /// Default is `0.0`.
1245 pub fn restitution(mut self, restitution: Real) -> Self {
1246 self.restitution = restitution;
1247 self
1248 }
1249
1250 /// Sets the rule to be used to combine two restitution coefficients in a contact.
1251 pub fn restitution_combine_rule(mut self, rule: CoefficientCombineRule) -> Self {
1252 self.restitution_combine_rule = rule;
1253 self
1254 }
1255
1256 /// Sets the density (mass per unit volume) of this collider.
1257 ///
1258 /// Mass will be computed as: `density × volume`. Common densities:
1259 /// - `1000.0` = water
1260 /// - `2700.0` = aluminum
1261 /// - `7850.0` = steel
1262 ///
1263 /// ⚠️ Use either `density()` OR `mass()`, not both (last call wins).
1264 ///
1265 /// # Example
1266 /// ```ignore
1267 /// let steel_ball = ColliderBuilder::ball(0.5).density(7850.0).build();
1268 /// ```
1269 pub fn density(mut self, density: Real) -> Self {
1270 self.mass_properties = ColliderMassProps::Density(density);
1271 self
1272 }
1273
1274 /// Sets the total mass of this collider directly.
1275 ///
1276 /// Angular inertia is computed automatically from the shape and mass.
1277 ///
1278 /// ⚠️ Use either `mass()` OR `density()`, not both (last call wins).
1279 ///
1280 /// # Example
1281 /// ```ignore
1282 /// // 10kg ball regardless of its radius
1283 /// let collider = ColliderBuilder::ball(0.5).mass(10.0).build();
1284 /// ```
1285 pub fn mass(mut self, mass: Real) -> Self {
1286 self.mass_properties = ColliderMassProps::Mass(mass);
1287 self
1288 }
1289
1290 /// Sets the mass properties of the collider this builder will build.
1291 ///
1292 /// This will be overridden by a call to [`Self::density`] or [`Self::mass`] so it only
1293 /// makes sense to call either [`Self::density`] or [`Self::mass`] or [`Self::mass_properties`].
1294 pub fn mass_properties(mut self, mass_properties: MassProperties) -> Self {
1295 self.mass_properties = ColliderMassProps::MassProperties(Box::new(mass_properties));
1296 self
1297 }
1298
1299 /// Sets the force threshold for triggering contact force events.
1300 ///
1301 /// When total contact force exceeds this value, a `ContactForceEvent` is generated
1302 /// (if `ActiveEvents::CONTACT_FORCE_EVENTS` is enabled).
1303 ///
1304 /// Use for detecting hard impacts, breaking objects, or damage systems.
1305 ///
1306 /// # Example
1307 /// ```ignore
1308 /// let glass = ColliderBuilder::cuboid(1.0, 1.0, 0.1)
1309 /// .active_events(ActiveEvents::CONTACT_FORCE_EVENTS)
1310 /// .contact_force_event_threshold(1000.0) // Break at 1000N
1311 /// .build();
1312 /// ```
1313 pub fn contact_force_event_threshold(mut self, threshold: Real) -> Self {
1314 self.contact_force_event_threshold = threshold;
1315 self
1316 }
1317
1318 /// Sets where the collider sits relative to its parent body.
1319 ///
1320 /// For attached colliders, this is the offset from the body's origin.
1321 /// For standalone colliders, this is the world position.
1322 ///
1323 /// # Example
1324 /// ```ignore
1325 /// // Collider offset 2 units to the right of the body
1326 /// let collider = ColliderBuilder::ball(0.5)
1327 /// .translation(vector![2.0, 0.0, 0.0])
1328 /// .build();
1329 /// ```
1330 pub fn translation(mut self, translation: Vector<Real>) -> Self {
1331 self.position.translation.vector = translation;
1332 self
1333 }
1334
1335 /// Sets the collider's rotation relative to its parent body.
1336 ///
1337 /// For attached colliders, this rotates the collider relative to the body.
1338 /// For standalone colliders, this is the world rotation.
1339 pub fn rotation(mut self, angle: AngVector<Real>) -> Self {
1340 self.position.rotation = Rotation::new(angle);
1341 self
1342 }
1343
1344 /// Sets the collider's full pose (position + rotation) relative to its parent.
1345 ///
1346 /// For attached colliders, this is relative to the parent body.
1347 /// For standalone colliders, this is the world pose.
1348 pub fn position(mut self, pos: Isometry<Real>) -> Self {
1349 self.position = pos;
1350 self
1351 }
1352
1353 /// Sets the initial position (translation and orientation) of the collider to be created,
1354 /// relative to the rigid-body it is attached to.
1355 #[deprecated(note = "Use `.position` instead.")]
1356 pub fn position_wrt_parent(mut self, pos: Isometry<Real>) -> Self {
1357 self.position = pos;
1358 self
1359 }
1360
1361 /// Set the position of this collider in the local-space of the rigid-body it is attached to.
1362 #[deprecated(note = "Use `.position` instead.")]
1363 pub fn delta(mut self, delta: Isometry<Real>) -> Self {
1364 self.position = delta;
1365 self
1366 }
1367
1368 /// Sets the contact skin of the collider.
1369 ///
1370 /// The contact skin acts as if the collider was enlarged with a skin of width `skin_thickness`
1371 /// around it, keeping objects further apart when colliding.
1372 ///
1373 /// A non-zero contact skin can increase performance, and in some cases, stability. However
1374 /// it creates a small gap between colliding object (equal to the sum of their skin). If the
1375 /// skin is sufficiently small, this might not be visually significant or can be hidden by the
1376 /// rendering assets.
1377 pub fn contact_skin(mut self, skin_thickness: Real) -> Self {
1378 self.contact_skin = skin_thickness;
1379 self
1380 }
1381
1382 /// Sets whether this collider starts enabled or disabled.
1383 ///
1384 /// Default is `true` (enabled). Set to `false` to create a disabled collider.
1385 pub fn enabled(mut self, enabled: bool) -> Self {
1386 self.enabled = enabled;
1387 self
1388 }
1389
1390 /// Finalizes the collider and returns it, ready to be added to the world.
1391 ///
1392 /// # Example
1393 /// ```ignore
1394 /// let collider = ColliderBuilder::ball(0.5)
1395 /// .friction(0.7)
1396 /// .build();
1397 /// colliders.insert_with_parent(collider, body_handle, &mut bodies);
1398 /// ```
1399 pub fn build(&self) -> Collider {
1400 let shape = self.shape.clone();
1401 let material = ColliderMaterial {
1402 friction: self.friction,
1403 restitution: self.restitution,
1404 friction_combine_rule: self.friction_combine_rule,
1405 restitution_combine_rule: self.restitution_combine_rule,
1406 };
1407 let flags = ColliderFlags {
1408 collision_groups: self.collision_groups,
1409 solver_groups: self.solver_groups,
1410 active_collision_types: self.active_collision_types,
1411 active_hooks: self.active_hooks,
1412 active_events: self.active_events,
1413 enabled: if self.enabled {
1414 ColliderEnabled::Enabled
1415 } else {
1416 ColliderEnabled::Disabled
1417 },
1418 };
1419 let changes = ColliderChanges::all();
1420 let pos = ColliderPosition(self.position);
1421 let coll_type = if self.is_sensor {
1422 ColliderType::Sensor
1423 } else {
1424 ColliderType::Solid
1425 };
1426
1427 Collider {
1428 shape,
1429 mprops: self.mass_properties.clone(),
1430 material,
1431 parent: None,
1432 changes,
1433 pos,
1434 flags,
1435 coll_type,
1436 contact_force_event_threshold: self.contact_force_event_threshold,
1437 contact_skin: self.contact_skin,
1438 user_data: self.user_data,
1439 }
1440 }
1441}
1442
1443impl From<ColliderBuilder> for Collider {
1444 fn from(val: ColliderBuilder) -> Collider {
1445 val.build()
1446 }
1447}