parry2d/shape/voxels/voxels.rs
1use super::{
2 VoxelIndex, EMPTY_FACE_MASK, FACES_TO_FEATURE_MASKS, FACES_TO_OCTANT_MASKS,
3 FACES_TO_VOXEL_TYPES, INTERIOR_FACE_MASK,
4};
5use crate::bounding_volume::{Aabb, BoundingVolume};
6use crate::math::{Point, Real, Vector};
7use crate::partitioning::{Bvh, BvhBuildStrategy, BvhNode};
8use crate::shape::voxels::voxels_chunk::{VoxelsChunk, VoxelsChunkHeader};
9use crate::shape::VoxelsChunkRef;
10use crate::utils::hashmap::HashMap;
11use alloc::{vec, vec::Vec};
12#[cfg(not(feature = "std"))]
13use na::ComplexField;
14
15/// Categorization of a voxel based on its neighbors.
16///
17/// This enum describes the local topology of a filled voxel by examining which of its
18/// immediate neighbors (along coordinate axes) are also filled. This information is crucial
19/// for collision detection to avoid the "internal edges problem" where objects can get
20/// caught on edges between adjacent voxels.
21///
22/// # Type Classification
23///
24/// - **Empty**: The voxel is not filled.
25/// - **Interior**: All axis-aligned neighbors are filled (safest for collision).
26/// - **Face**: Missing neighbors in one coordinate direction (e.g., top face exposed).
27/// - **Edge** (3D only): Missing neighbors in two coordinate directions (e.g., corner edge exposed).
28/// - **Vertex**: Missing neighbors in all coordinate directions (isolated corner).
29///
30/// # Examples
31///
32/// ```
33/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
34/// use parry3d::shape::{Voxels, VoxelType};
35/// use nalgebra::{Point3, Vector3};
36///
37/// // Create a small 2x2x2 cube of voxels
38/// let voxels = Voxels::new(
39/// Vector3::new(1.0, 1.0, 1.0),
40/// &[
41/// Point3::new(0, 0, 0),
42/// Point3::new(1, 0, 0),
43/// Point3::new(0, 1, 0),
44/// Point3::new(1, 1, 0),
45/// Point3::new(0, 0, 1),
46/// Point3::new(1, 0, 1),
47/// Point3::new(0, 1, 1),
48/// Point3::new(1, 1, 1),
49/// ],
50/// );
51///
52/// // Check voxel type - interior voxels are fully surrounded
53/// let state = voxels.voxel_state(Point3::new(0, 0, 0)).unwrap();
54/// let voxel_type = state.voxel_type();
55/// println!("Voxel type: {:?}", voxel_type);
56/// # }
57/// ```
58#[derive(Copy, Clone, Debug, PartialEq, Eq)]
59pub enum VoxelType {
60 /// The voxel is empty.
61 Empty,
62 /// The voxel is a vertex if all three coordinate axis directions have at
63 /// least one empty neighbor.
64 Vertex,
65 /// The voxel is on an edge if it has non-empty neighbors in both directions of
66 /// a single coordinate axis.
67 #[cfg(feature = "dim3")]
68 Edge,
69 /// The voxel is on an edge if it has non-empty neighbors in both directions of
70 /// two coordinate axes.
71 Face,
72 /// The voxel is on an edge if it has non-empty neighbors in both directions of
73 /// all coordinate axes.
74 Interior,
75}
76
77#[derive(Clone, Copy, Debug, Default, Eq, Hash, Ord, PartialEq, PartialOrd)]
78/// The status of the cell of an heightfield.
79pub struct AxisMask(u8);
80
81bitflags::bitflags! {
82 /// Flags for identifying signed directions along coordinate axes, or faces of a voxel.
83 impl AxisMask: u8 {
84 /// The direction or face along the `+x` coordinate axis.
85 const X_POS = 1 << 0;
86 /// The direction or face along the `-x` coordinate axis.
87 const X_NEG = 1 << 1;
88 /// The direction or face along the `+y` coordinate axis.
89 const Y_POS = 1 << 2;
90 /// The direction or face along the `-y` coordinate axis.
91 const Y_NEG = 1 << 3;
92 /// The direction or face along the `+z` coordinate axis.
93 #[cfg(feature= "dim3")]
94 const Z_POS = 1 << 4;
95 /// The direction or face along the `-z` coordinate axis.
96 #[cfg(feature= "dim3")]
97 const Z_NEG = 1 << 5;
98 }
99}
100
101/// Indicates the local shape of a voxel on each octant.
102///
103/// This provides geometric information of the shape’s exposed features on each octant.
104// This is an alternative to `FACES_TO_FEATURE_MASKS` that can be more convenient for some
105// collision-detection algorithms.
106#[derive(Copy, Clone, Debug, PartialEq, Eq)]
107pub struct OctantPattern;
108
109// NOTE: it is important that the max value of any OctantPattern variant
110// is 7 because we don’t allocate more than 3 bits to store it in
111// `FACES_TO_OCTANT_MASKS`.
112/// Indicates the local shape of a voxel on each octant.
113///
114/// This provides geometric information of the shape’s exposed features on each octant.
115// This is an alternative to `FACES_TO_FEATURE_MASKS` that can be more convenient for some
116// collision-detection algorithms.
117#[cfg(feature = "dim3")]
118impl OctantPattern {
119 /// The voxel doesn't have any exposed feature on the octant with this mask.
120 pub const INTERIOR: u32 = 0;
121 /// The voxel has an exposed vertex on the octant with this mask.
122 pub const VERTEX: u32 = 1;
123 /// The voxel has an exposed edges with direction X on the octant with this mask.
124 pub const EDGE_X: u32 = 2;
125 /// The voxel has an exposed edges with direction Y on the octant with this mask.
126 pub const EDGE_Y: u32 = 3;
127 /// The voxel has an exposed edges with direction Z on the octant with this mask.
128 pub const EDGE_Z: u32 = 4;
129 /// The voxel has an exposed face with normal X on the octant with this mask.
130 pub const FACE_X: u32 = 5;
131 /// The voxel has an exposed face with normal Y on the octant with this mask.
132 pub const FACE_Y: u32 = 6;
133 /// The voxel has an exposed face with normal Z on the octant with this mask.
134 pub const FACE_Z: u32 = 7;
135}
136
137// NOTE: it is important that the max value of any OctantPattern variant
138// is 7 because we don’t allocate more than 3 bits to store it in
139// `FACES_TO_OCTANT_MASKS`.
140/// Indicates the local shape of a voxel on each octant.
141///
142/// This provides geometric information of the shape’s exposed features on each octant.
143/// This is an alternative to `FACES_TO_FEATURE_MASKS` that can be more convenient for some
144/// collision-detection algorithms.
145#[cfg(feature = "dim2")]
146impl OctantPattern {
147 /// The voxel doesn't have any exposed feature on the octant with this mask.
148 pub const INTERIOR: u32 = 0;
149 /// The voxel has an exposed vertex on the octant with this mask.
150 pub const VERTEX: u32 = 1;
151 /// The voxel has an exposed face with normal X on the octant with this mask.
152 pub const FACE_X: u32 = 2;
153 /// The voxel has an exposed face with normal Y on the octant with this mask.
154 pub const FACE_Y: u32 = 3;
155}
156
157// The local neighborhood information is encoded in a 8-bits number in groups of two bits
158// per coordinate axis: `0bwwzzyyxx`. In each group of two bits, e.g. `xx`, the rightmost (resp.
159// leftmost) bit set to 1 means that the neighbor voxel with coordinate `+1` (resp `-1`) relative
160// to the current voxel along the `x` axis is filled. If the bit is 0, then the corresponding
161// neighbor is empty. See the `AxisMask` bitflags.
162// For example, in 2D, the mask `0b00_00_10_01` matches the following configuration (assuming +y goes
163// up, and +x goes right):
164//
165// ```txt
166// 0 0 0
167// 0 x 1
168// 0 1 0
169// ```
170//
171// The special value `0b01000000` indicates that the voxel is empty.
172// And the value `0b00111111` (`0b00001111` in 2D) indicates that the voxel is an interior voxel (its whole neighborhood
173// is filled).
174/// A description of the local neighborhood of a voxel.
175///
176/// This compact representation stores which immediate neighbors (along coordinate axes) of a
177/// voxel are filled. This information is essential for proper collision detection between voxels
178/// and other shapes, as it helps avoid the "internal edges problem."
179///
180/// The state is encoded as a single byte where each pair of bits represents one coordinate axis,
181/// indicating whether neighbors in the positive and negative directions are filled.
182///
183/// # Special States
184///
185/// - [`VoxelState::EMPTY`]: The voxel itself is empty (not part of the shape).
186/// - [`VoxelState::INTERIOR`]: All neighbors are filled (completely surrounded voxel).
187///
188/// # Examples
189///
190/// ```
191/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
192/// use parry3d::shape::{Voxels, VoxelState, AxisMask};
193/// use nalgebra::{Point3, Vector3};
194///
195/// // Create a simple voxel shape
196/// let voxels = Voxels::new(
197/// Vector3::new(1.0, 1.0, 1.0),
198/// &[Point3::new(0, 0, 0), Point3::new(1, 0, 0)],
199/// );
200///
201/// // Query the state of a voxel
202/// let state = voxels.voxel_state(Point3::new(0, 0, 0)).unwrap();
203///
204/// // Check if empty
205/// assert!(!state.is_empty());
206///
207/// // Get which faces are exposed (not adjacent to other voxels)
208/// let free_faces = state.free_faces();
209/// if free_faces.contains(AxisMask::X_NEG) {
210/// println!("The -X face is exposed");
211/// }
212///
213/// // Get the voxel type based on neighborhood
214/// println!("Voxel type: {:?}", state.voxel_type());
215/// # }
216/// ```
217#[derive(Copy, Clone, Debug, PartialEq, Eq)]
218#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
219pub struct VoxelState(pub(super) u8);
220
221impl VoxelState {
222 /// The value of empty voxels.
223 pub const EMPTY: VoxelState = VoxelState(EMPTY_FACE_MASK);
224 /// The value of a voxel with non-empty neighbors in all directions.
225 pub const INTERIOR: VoxelState = VoxelState(INTERIOR_FACE_MASK);
226
227 pub(crate) const fn new(state: u8) -> Self {
228 Self(state)
229 }
230
231 /// Is this voxel empty?
232 pub const fn is_empty(self) -> bool {
233 self.0 == EMPTY_FACE_MASK
234 }
235
236 /// A bit mask indicating which faces of the voxel don’t have any
237 /// adjacent non-empty voxel.
238 pub const fn free_faces(self) -> AxisMask {
239 if self.0 == INTERIOR_FACE_MASK || self.0 == EMPTY_FACE_MASK {
240 AxisMask::empty()
241 } else {
242 AxisMask::from_bits_truncate((!self.0) & INTERIOR_FACE_MASK)
243 }
244 }
245
246 /// The [`VoxelType`] of this voxel.
247 pub const fn voxel_type(self) -> VoxelType {
248 FACES_TO_VOXEL_TYPES[self.0 as usize]
249 }
250
251 // Bitmask indicating what vertices, edges, or faces of the voxel are "free".
252 pub(crate) const fn feature_mask(self) -> u16 {
253 FACES_TO_FEATURE_MASKS[self.0 as usize]
254 }
255
256 pub(crate) const fn octant_mask(self) -> u32 {
257 FACES_TO_OCTANT_MASKS[self.0 as usize]
258 }
259}
260
261/// Information associated to a voxel.
262///
263/// This structure provides complete information about a single voxel including its position
264/// in both grid coordinates and world space, as well as its state (empty/filled and neighborhood).
265///
266/// # Note
267///
268/// The `linear_id` field is an internal implementation detail that can become invalidated when
269/// the voxel structure is modified (e.g., via [`Voxels::set_voxel`] or [`Voxels::crop`]).
270/// For stable references to voxels, always use `grid_coords`.
271///
272/// # Examples
273///
274/// ```
275/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
276/// use parry3d::shape::Voxels;
277/// use nalgebra::{Point3, Vector3};
278///
279/// let voxels = Voxels::new(
280/// Vector3::new(0.5, 0.5, 0.5),
281/// &[Point3::new(0, 0, 0), Point3::new(1, 0, 0)],
282/// );
283///
284/// // Iterate through all voxels
285/// for voxel in voxels.voxels() {
286/// if !voxel.state.is_empty() {
287/// println!("Voxel at grid position {:?}", voxel.grid_coords);
288/// println!(" World center: {:?}", voxel.center);
289/// println!(" Type: {:?}", voxel.state.voxel_type());
290/// }
291/// }
292/// # }
293/// ```
294#[derive(Copy, Clone, Debug, PartialEq)]
295pub struct VoxelData {
296 /// The temporary index in the internal voxels' storage.
297 ///
298 /// This index can be invalidated after a call to [`Voxels::set_voxel`], or
299 /// [`Voxels::crop`].
300 pub linear_id: VoxelIndex,
301 /// The voxel's integer grid coordinates.
302 pub grid_coords: Point<i32>,
303 /// The voxel's center position in the local-space of the [`Voxels`] shape it is part of.
304 pub center: Point<Real>,
305 /// The voxel's state, indicating if it's empty or full.
306 pub state: VoxelState,
307}
308
309/// A shape made of axis-aligned, uniformly sized cubes (aka. voxels).
310///
311/// # What are Voxels?
312///
313/// Voxels (volumetric pixels) are 3D cubes (or 2D squares) arranged on a regular grid. Think of
314/// them as 3D building blocks, like LEGO bricks or Minecraft blocks. Each voxel has:
315/// - A position on an integer grid (e.g., `(0, 0, 0)`, `(1, 2, 3)`)
316/// - A uniform size (e.g., 1.0 × 1.0 × 1.0 meters)
317/// - A state: filled (solid) or empty (air)
318///
319/// # When to Use Voxels?
320///
321/// Voxels are ideal for:
322/// - **Minecraft-style worlds**: Block-based terrain and structures
323/// - **Destructible environments**: Easy to add/remove individual blocks
324/// - **Procedural generation**: Grid-based algorithms for caves, terrain, dungeons
325/// - **Volumetric data**: Medical imaging, scientific simulations
326/// - **Retro aesthetics**: Pixel art style in 3D
327///
328/// Voxels may NOT be ideal for:
329/// - Smooth organic shapes (use meshes instead)
330/// - Very large sparse worlds (consider octrees or chunk-based systems)
331/// - Scenes requiring fine geometric detail at all scales
332///
333/// # The Internal Edges Problem
334///
335/// When an object slides across a flat surface made of voxels, it can snag on the edges between
336/// adjacent voxels, causing jerky motion. Parry's `Voxels` shape solves this by tracking neighbor
337/// relationships: it knows which voxel faces are internal (adjacent to another voxel) vs external
338/// (exposed to air), allowing smooth collision response.
339///
340/// # Memory Efficiency
341///
342/// The internal storage uses sparse chunks, storing only one byte per voxel for neighborhood
343/// information. Empty regions consume minimal memory. This is much more efficient than storing
344/// a triangle mesh representation of all voxel surfaces.
345///
346/// # Examples
347///
348/// ## Basic Usage: Creating a Voxel Shape
349///
350/// ```
351/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
352/// use parry3d::shape::Voxels;
353/// use nalgebra::{Point3, Vector3};
354///
355/// // Create a simple 3×3×3 cube of voxels
356/// let voxel_size = Vector3::new(1.0, 1.0, 1.0);
357/// let mut coords = Vec::new();
358/// for x in 0..3 {
359/// for y in 0..3 {
360/// for z in 0..3 {
361/// coords.push(Point3::new(x, y, z));
362/// }
363/// }
364/// }
365///
366/// let voxels = Voxels::new(voxel_size, &coords);
367/// println!("Created voxel shape with {} voxels", coords.len());
368/// # }
369/// ```
370///
371/// ## Creating Voxels from World-Space Points
372///
373/// ```
374/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
375/// use parry3d::shape::Voxels;
376/// use nalgebra::{Point3, Vector3};
377///
378/// // Sample points in world space (e.g., from a point cloud)
379/// let points = vec![
380/// Point3::new(0.1, 0.2, 0.3),
381/// Point3::new(1.5, 2.1, 3.7),
382/// Point3::new(0.8, 0.9, 1.2),
383/// ];
384///
385/// // Create voxels with 0.5 unit size - nearby points merge into same voxel
386/// let voxels = Voxels::from_points(Vector3::new(0.5, 0.5, 0.5), &points);
387/// println!("Created voxel shape from {} points", points.len());
388/// # }
389/// ```
390///
391/// ## Querying Voxel State
392///
393/// ```
394/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
395/// use parry3d::shape::Voxels;
396/// use nalgebra::{Point3, Vector3};
397///
398/// let voxels = Voxels::new(
399/// Vector3::new(1.0, 1.0, 1.0),
400/// &[Point3::new(0, 0, 0), Point3::new(1, 0, 0)],
401/// );
402///
403/// // Check if a specific grid position is filled
404/// if let Some(state) = voxels.voxel_state(Point3::new(0, 0, 0)) {
405/// println!("Voxel is filled!");
406/// println!("Type: {:?}", state.voxel_type());
407/// println!("Free faces: {:?}", state.free_faces());
408/// } else {
409/// println!("Voxel is empty or outside the domain");
410/// }
411///
412/// // Convert world-space point to grid coordinates
413/// let world_point = Point3::new(1.3, 0.7, 0.2);
414/// let grid_coord = voxels.voxel_at_point(world_point);
415/// println!("Point at {:?} is in voxel {:?}", world_point, grid_coord);
416/// # }
417/// ```
418///
419/// ## Iterating Through Voxels
420///
421/// ```
422/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
423/// use parry3d::shape::Voxels;
424/// use nalgebra::{Point3, Vector3};
425///
426/// let voxels = Voxels::new(
427/// Vector3::new(0.5, 0.5, 0.5),
428/// &[Point3::new(0, 0, 0), Point3::new(1, 0, 0), Point3::new(0, 1, 0)],
429/// );
430///
431/// // Iterate through all non-empty voxels
432/// for voxel in voxels.voxels() {
433/// if !voxel.state.is_empty() {
434/// println!("Voxel at grid {:?}, world center {:?}",
435/// voxel.grid_coords, voxel.center);
436/// }
437/// }
438/// # }
439/// ```
440///
441/// ## Modifying Voxels Dynamically
442///
443/// ```
444/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
445/// use parry3d::shape::Voxels;
446/// use nalgebra::{Point3, Vector3};
447///
448/// let mut voxels = Voxels::new(
449/// Vector3::new(1.0, 1.0, 1.0),
450/// &[Point3::new(0, 0, 0)],
451/// );
452///
453/// // Add a new voxel
454/// voxels.set_voxel(Point3::new(1, 0, 0), true);
455///
456/// // Remove a voxel
457/// voxels.set_voxel(Point3::new(0, 0, 0), false);
458///
459/// // Check the result
460/// assert!(voxels.voxel_state(Point3::new(0, 0, 0)).unwrap().is_empty());
461/// assert!(!voxels.voxel_state(Point3::new(1, 0, 0)).unwrap().is_empty());
462/// # }
463/// ```
464///
465/// ## Spatial Queries
466///
467/// ```
468/// # #[cfg(all(feature = "dim3", feature = "f32"))] {
469/// use parry3d::shape::Voxels;
470/// use parry3d::bounding_volume::Aabb;
471/// use nalgebra::{Point3, Vector3};
472///
473/// let voxels = Voxels::new(
474/// Vector3::new(1.0, 1.0, 1.0),
475/// &[Point3::new(0, 0, 0), Point3::new(1, 0, 0), Point3::new(2, 0, 0)],
476/// );
477///
478/// // Find voxels intersecting an AABB
479/// let query_aabb = Aabb::new(Point3::new(-0.5, -0.5, -0.5), Point3::new(1.5, 1.5, 1.5));
480/// let count = voxels.voxels_intersecting_local_aabb(&query_aabb)
481/// .filter(|v| !v.state.is_empty())
482/// .count();
483/// println!("Found {} voxels in AABB", count);
484///
485/// // Get the overall domain bounds
486/// let [mins, maxs] = voxels.domain();
487/// println!("Voxel grid spans from {:?} to {:?}", mins, maxs);
488/// # }
489/// ```
490///
491/// # See Also
492///
493/// - [`VoxelState`]: Information about a voxel's neighbors
494/// - [`VoxelType`]: Classification of voxels by their topology
495/// - [`VoxelData`]: Complete information about a single voxel
496/// - [`crate::transformation::voxelization`]: Convert meshes to voxels
497#[derive(Clone, Debug)]
498#[cfg_attr(feature = "serde-serialize", derive(Serialize, Deserialize))]
499pub struct Voxels {
500 /// A BVH of chunk keys.
501 ///
502 /// The bounding boxes are the ones of the chunk’s voxels **keys**. This is equivalent to a bvh
503 /// of the chunks with a uniform voxel size of 1.
504 pub(super) chunk_bvh: Bvh,
505 pub(super) chunk_headers: HashMap<Point<i32>, VoxelsChunkHeader>,
506 pub(super) chunk_keys: Vec<Point<i32>>,
507 pub(super) chunks: Vec<VoxelsChunk>,
508 pub(super) free_chunks: Vec<usize>,
509 pub(super) voxel_size: Vector<Real>,
510}
511
512impl Voxels {
513 /// Initializes a voxel shape from grid coordinates.
514 ///
515 /// This is the primary constructor for creating a `Voxels` shape. You provide:
516 /// - `voxel_size`: The physical dimensions of each voxel (e.g., `1.0 × 1.0 × 1.0` meters)
517 /// - `grid_coordinates`: Integer grid positions for each filled voxel
518 ///
519 /// # Coordinate System
520 ///
521 /// Each voxel with grid coordinates `(x, y, z)` will be positioned such that:
522 /// - Its minimum corner (bottom-left-back) is at `(x, y, z) * voxel_size`
523 /// - Its center is at `((x, y, z) + 0.5) * voxel_size`
524 /// - Its maximum corner is at `((x, y, z) + 1) * voxel_size`
525 ///
526 /// For example, with `voxel_size = 2.0` and grid coord `(1, 0, 0)`:
527 /// - Minimum corner: `(2.0, 0.0, 0.0)`
528 /// - Center: `(3.0, 1.0, 1.0)`
529 /// - Maximum corner: `(4.0, 2.0, 2.0)`
530 ///
531 /// # Examples
532 ///
533 /// ```
534 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
535 /// use parry3d::shape::Voxels;
536 /// use nalgebra::{Point3, Vector3};
537 ///
538 /// // Create a 2×2×2 cube of voxels with 1.0 unit size
539 /// let voxels = Voxels::new(
540 /// Vector3::new(1.0, 1.0, 1.0),
541 /// &[
542 /// Point3::new(0, 0, 0), Point3::new(1, 0, 0),
543 /// Point3::new(0, 1, 0), Point3::new(1, 1, 0),
544 /// Point3::new(0, 0, 1), Point3::new(1, 0, 1),
545 /// Point3::new(0, 1, 1), Point3::new(1, 1, 1),
546 /// ],
547 /// );
548 ///
549 /// // Verify the first voxel's center position
550 /// let center = voxels.voxel_center(Point3::new(0, 0, 0));
551 /// assert_eq!(center, Point3::new(0.5, 0.5, 0.5));
552 /// # }
553 /// ```
554 ///
555 /// ```
556 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
557 /// use parry3d::shape::Voxels;
558 /// use nalgebra::{Point3, Vector3};
559 ///
560 /// // Create a line of voxels along the X axis
561 /// let voxels = Voxels::new(
562 /// Vector3::new(0.5, 0.5, 0.5),
563 /// &[Point3::new(0, 0, 0), Point3::new(1, 0, 0), Point3::new(2, 0, 0)],
564 /// );
565 ///
566 /// // Query the domain (bounding grid coordinates)
567 /// // Note: domain is aligned to internal chunk boundaries for efficiency
568 /// let [mins, maxs] = voxels.domain();
569 /// assert_eq!(mins, Point3::new(0, 0, 0));
570 /// // maxs will be chunk-aligned (chunks are 8x8x8), so it includes more space
571 /// assert!(maxs.x >= 3 && maxs.y >= 1 && maxs.z >= 1);
572 /// # }
573 /// ```
574 pub fn new(voxel_size: Vector<Real>, grid_coordinates: &[Point<i32>]) -> Self {
575 let mut result = Self {
576 chunk_bvh: Bvh::new(),
577 chunk_headers: HashMap::default(),
578 chunk_keys: vec![],
579 chunks: vec![],
580 free_chunks: vec![],
581 voxel_size,
582 };
583
584 for vox in grid_coordinates {
585 let (chunk_key, id_in_chunk) = Self::chunk_key_and_id_in_chunk(*vox);
586 let chunk_header = result.chunk_headers.entry(chunk_key).or_insert_with(|| {
587 let id = result.chunks.len();
588 result.chunks.push(VoxelsChunk::default());
589 result.chunk_keys.push(chunk_key);
590 VoxelsChunkHeader { id, len: 0 }
591 });
592 chunk_header.len += 1;
593 result.chunks[chunk_header.id].states[id_in_chunk] = VoxelState::INTERIOR;
594 }
595
596 result.chunk_bvh = Bvh::from_iter(
597 BvhBuildStrategy::Ploc,
598 result.chunk_headers.iter().map(|(chunk_key, chunk_id)| {
599 (
600 chunk_id.id,
601 VoxelsChunk::aabb(chunk_key, &result.voxel_size),
602 )
603 }),
604 );
605
606 result.recompute_all_voxels_states();
607 result
608 }
609
610 /// Computes a voxel shape from a set of world-space points.
611 ///
612 /// This constructor converts continuous world-space coordinates into discrete grid coordinates
613 /// by snapping each point to the voxel grid. Multiple points can map to the same voxel.
614 ///
615 /// # How it Works
616 ///
617 /// Each point is converted to grid coordinates by:
618 /// 1. Dividing the point's coordinates by `voxel_size`
619 /// 2. Taking the floor to get integer grid coordinates
620 /// 3. Removing duplicates (multiple points in the same voxel become one voxel)
621 ///
622 /// For example, with `voxel_size = 1.0`:
623 /// - Point `(0.3, 0.7, 0.9)` → Grid `(0, 0, 0)`
624 /// - Point `(1.1, 0.2, 0.5)` → Grid `(1, 0, 0)`
625 /// - Point `(0.9, 0.1, 0.8)` → Grid `(0, 0, 0)` (merges with first)
626 ///
627 /// # Use Cases
628 ///
629 /// - Converting point clouds into voxel representations
630 /// - Creating voxel shapes from scattered data
631 /// - Simplifying complex point sets into uniform grids
632 ///
633 /// # Examples
634 ///
635 /// ```
636 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
637 /// use parry3d::shape::Voxels;
638 /// use nalgebra::{Point3, Vector3};
639 ///
640 /// // Sample points in world space
641 /// let points = vec![
642 /// Point3::new(0.1, 0.2, 0.3), // → Grid (0, 0, 0)
643 /// Point3::new(0.7, 0.8, 0.9), // → Grid (0, 0, 0) - same voxel!
644 /// Point3::new(1.2, 0.3, 0.1), // → Grid (1, 0, 0)
645 /// Point3::new(0.5, 1.5, 0.2), // → Grid (0, 1, 0)
646 /// ];
647 ///
648 /// // Create voxels with 1.0 unit size
649 /// let voxels = Voxels::from_points(Vector3::new(1.0, 1.0, 1.0), &points);
650 ///
651 /// // Only 3 unique voxels created (first two points merged)
652 /// let filled_count = voxels.voxels()
653 /// .filter(|v| !v.state.is_empty())
654 /// .count();
655 /// assert_eq!(filled_count, 3);
656 /// # }
657 /// ```
658 ///
659 /// ```
660 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
661 /// use parry3d::shape::Voxels;
662 /// use nalgebra::{Point3, Vector3};
663 ///
664 /// // Higher resolution voxelization
665 /// let points = vec![
666 /// Point3::origin(),
667 /// Point3::new(1.0, 1.0, 1.0),
668 /// ];
669 ///
670 /// // Smaller voxels = finer detail
671 /// let voxels = Voxels::from_points(Vector3::new(0.5, 0.5, 0.5), &points);
672 ///
673 /// // First point at grid (0,0,0), second at grid (2,2,2) due to smaller voxel size
674 /// assert!(voxels.voxel_state(Point3::new(0, 0, 0)).is_some());
675 /// assert!(voxels.voxel_state(Point3::new(2, 2, 2)).is_some());
676 /// # }
677 /// ```
678 pub fn from_points(voxel_size: Vector<Real>, points: &[Point<Real>]) -> Self {
679 let voxels: Vec<_> = points
680 .iter()
681 .map(|pt| {
682 Point::from(
683 pt.coords
684 .component_div(&voxel_size)
685 .map(|x| x.floor() as i32),
686 )
687 })
688 .collect();
689 Self::new(voxel_size, &voxels)
690 }
691
692 pub(crate) fn chunk_bvh(&self) -> &Bvh {
693 &self.chunk_bvh
694 }
695
696 /// The semi-open range of grid coordinates covered by this voxel shape.
697 ///
698 /// Returns `[mins, maxs]` where the domain is the semi-open interval `[mins, maxs)`,
699 /// meaning `mins` is included but `maxs` is excluded. This provides conservative bounds
700 /// on the range of voxel grid coordinates that might be filled.
701 ///
702 /// This is useful for:
703 /// - Determining the spatial extent of the voxel shape
704 /// - Pre-allocating storage for processing voxels
705 /// - Clipping operations to valid regions
706 ///
707 /// # Examples
708 ///
709 /// ```
710 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
711 /// use parry3d::shape::Voxels;
712 /// use nalgebra::{Point3, Vector3};
713 ///
714 /// let voxels = Voxels::new(
715 /// Vector3::new(1.0, 1.0, 1.0),
716 /// &[Point3::new(0, 0, 0), Point3::new(2, 3, 1)],
717 /// );
718 ///
719 /// let [mins, maxs] = voxels.domain();
720 /// assert_eq!(mins, Point3::new(0, 0, 0));
721 /// // Domain is conservative and chunk-aligned
722 /// assert!(maxs.x > 2 && maxs.y > 3 && maxs.z > 1);
723 ///
724 /// // Iterate through filled voxels (more efficient than iterating domain)
725 /// for voxel in voxels.voxels() {
726 /// if !voxel.state.is_empty() {
727 /// println!("Filled voxel at {:?}", voxel.grid_coords);
728 /// }
729 /// }
730 /// # }
731 /// ```
732 pub fn domain(&self) -> [Point<i32>; 2] {
733 let aabb = self.chunk_bvh.root_aabb();
734
735 // NOTE that we shift the AABB’s bounds so the endpoint matches a voxel center
736 // to avoid rounding errors.
737 let half_sz = self.voxel_size() / 2.0;
738 let mins = self.voxel_at_point(aabb.mins + half_sz);
739 // + 1 because the range is semi-open.
740 let maxs = self.voxel_at_point(aabb.maxs - half_sz) + Vector::repeat(1);
741 [mins, maxs]
742 }
743
744 // /// The number of voxels along each coordinate axis.
745 // pub fn dimensions(&self) -> Vector<u32> {
746 // (self.domain_maxs - self.domain_mins).map(|e| e as u32)
747 // }
748
749 /// The size of each voxel part this [`Voxels`] shape.
750 pub fn voxel_size(&self) -> Vector<Real> {
751 self.voxel_size
752 }
753
754 /// Scale this shape.
755 pub fn scaled(mut self, scale: &Vector<Real>) -> Self {
756 self.voxel_size.component_mul_assign(scale);
757 self
758 }
759
760 /// A reference to the chunk with id `chunk_id`.
761 ///
762 /// Panics if the chunk doesn’t exist.
763 pub fn chunk_ref(&self, chunk_id: u32) -> VoxelsChunkRef<'_> {
764 VoxelsChunkRef {
765 my_id: chunk_id as usize,
766 parent: self,
767 states: &self.chunks[chunk_id as usize].states,
768 key: &self.chunk_keys[chunk_id as usize],
769 }
770 }
771
772 /// The AABB of the voxel with the given quantized `key`.
773 pub fn voxel_aabb(&self, key: Point<i32>) -> Aabb {
774 let center = self.voxel_center(key);
775 let hext = self.voxel_size / 2.0;
776 Aabb::from_half_extents(center, hext)
777 }
778
779 /// Returns the state of the voxel at the given grid coordinates.
780 ///
781 /// Returns `None` if the voxel doesn't exist in this shape's internal storage,
782 /// or `Some(VoxelState)` containing information about whether the voxel is filled
783 /// and which of its neighbors are also filled.
784 ///
785 /// # Examples
786 ///
787 /// ```
788 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
789 /// use parry3d::shape::Voxels;
790 /// use nalgebra::{Point3, Vector3};
791 ///
792 /// let voxels = Voxels::new(
793 /// Vector3::new(1.0, 1.0, 1.0),
794 /// &[Point3::new(0, 0, 0), Point3::new(1, 0, 0)],
795 /// );
796 ///
797 /// // Query an existing voxel
798 /// if let Some(state) = voxels.voxel_state(Point3::new(0, 0, 0)) {
799 /// assert!(!state.is_empty());
800 /// println!("Voxel type: {:?}", state.voxel_type());
801 /// }
802 ///
803 /// // Query a non-existent voxel
804 /// assert!(voxels.voxel_state(Point3::new(10, 10, 10)).is_none());
805 /// # }
806 /// ```
807 pub fn voxel_state(&self, key: Point<i32>) -> Option<VoxelState> {
808 let vid = self.linear_index(key)?;
809 Some(self.chunks[vid.chunk_id].states[vid.id_in_chunk])
810 }
811
812 /// Calculates the grid coordinates of the voxel containing the given world-space point.
813 ///
814 /// This conversion is independent of whether the voxel is actually filled or empty - it
815 /// simply determines which grid cell the point falls into based on the voxel size.
816 ///
817 /// # Examples
818 ///
819 /// ```
820 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
821 /// use parry3d::shape::Voxels;
822 /// use nalgebra::{Point3, Vector3};
823 ///
824 /// let voxels = Voxels::new(
825 /// Vector3::new(1.0, 1.0, 1.0),
826 /// &[Point3::new(0, 0, 0)],
827 /// );
828 ///
829 /// // Point in first voxel (center at 0.5, 0.5, 0.5)
830 /// assert_eq!(voxels.voxel_at_point(Point3::new(0.3, 0.7, 0.2)), Point3::new(0, 0, 0));
831 ///
832 /// // Point just inside second voxel boundary
833 /// assert_eq!(voxels.voxel_at_point(Point3::new(1.0, 0.0, 0.0)), Point3::new(1, 0, 0));
834 ///
835 /// // Negative coordinates work too
836 /// assert_eq!(voxels.voxel_at_point(Point3::new(-0.5, -0.5, -0.5)), Point3::new(-1, -1, -1));
837 /// # }
838 /// ```
839 ///
840 /// ```
841 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
842 /// use parry3d::shape::Voxels;
843 /// use nalgebra::{Point3, Vector3};
844 ///
845 /// // With non-uniform voxel size
846 /// let voxels = Voxels::new(
847 /// Vector3::new(2.0, 0.5, 1.0),
848 /// &[],
849 /// );
850 ///
851 /// // X coordinate divided by 2.0, Y by 0.5, Z by 1.0
852 /// assert_eq!(voxels.voxel_at_point(Point3::new(3.0, 1.2, 0.8)), Point3::new(1, 2, 0));
853 /// # }
854 /// ```
855 pub fn voxel_at_point(&self, point: Point<Real>) -> Point<i32> {
856 point
857 .coords
858 .component_div(&self.voxel_size)
859 .map(|x| x.floor() as i32)
860 .into()
861 }
862
863 /// Gets the voxel at the given flat voxel index.
864 pub fn voxel_at_flat_id(&self, id: u32) -> Option<Point<i32>> {
865 let vid = VoxelIndex::from_flat_id(id as usize);
866 let chunk_key = self.chunk_keys.get(vid.chunk_id)?;
867 if *chunk_key == VoxelsChunk::INVALID_CHUNK_KEY {
868 return None;
869 }
870
871 Some(VoxelsChunk::voxel_key_at_id(
872 *chunk_key,
873 vid.id_in_chunk as u32,
874 ))
875 }
876
877 /// The range of grid coordinates of voxels intersecting the given AABB.
878 ///
879 /// The returned range covers both empty and non-empty voxels, and is not limited to the
880 /// bounds defined by [`Self::domain`].
881 /// The range is semi, open, i.e., the range along each dimension `i` is understood as
882 /// the semi-open interval: `range[0][i]..range[1][i]`.
883 pub fn voxel_range_intersecting_local_aabb(&self, aabb: &Aabb) -> [Point<i32>; 2] {
884 let mins = aabb
885 .mins
886 .coords
887 .component_div(&self.voxel_size)
888 .map(|x| x.floor() as i32);
889 let maxs = aabb
890 .maxs
891 .coords
892 .component_div(&self.voxel_size)
893 .map(|x| x.ceil() as i32);
894 [mins.into(), maxs.into()]
895 }
896
897 /// The AABB of a given range of voxels.
898 ///
899 /// The AABB is computed independently of [`Self::domain`] and independently of whether
900 /// the voxels contained within are empty or not.
901 pub fn voxel_range_aabb(&self, mins: Point<i32>, maxs: Point<i32>) -> Aabb {
902 Aabb {
903 mins: mins
904 .cast::<Real>()
905 .coords
906 .component_mul(&self.voxel_size)
907 .into(),
908 maxs: maxs
909 .cast::<Real>()
910 .coords
911 .component_mul(&self.voxel_size)
912 .into(),
913 }
914 }
915
916 /// Aligns the given AABB with the voxelized grid.
917 ///
918 /// The aligned is calculated such that the returned AABB has corners lying at the grid
919 /// intersections (i.e. matches voxel corners) and fully contains the input `aabb`.
920 pub fn align_aabb_to_grid(&self, aabb: &Aabb) -> Aabb {
921 let mins = aabb
922 .mins
923 .coords
924 .zip_map(&self.voxel_size, |m, sz| (m / sz).floor() * m)
925 .into();
926 let maxs = aabb
927 .maxs
928 .coords
929 .zip_map(&self.voxel_size, |m, sz| (m / sz).ceil() * m)
930 .into();
931 Aabb { mins, maxs }
932 }
933
934 /// Iterates through every voxel intersecting the given aabb.
935 ///
936 /// Returns the voxel’s linearized id, center, and state.
937 pub fn voxels_intersecting_local_aabb(
938 &self,
939 aabb: &Aabb,
940 ) -> impl Iterator<Item = VoxelData> + '_ {
941 let [mins, maxs] = self.voxel_range_intersecting_local_aabb(aabb);
942 self.voxels_in_range(mins, maxs)
943 }
944
945 /// The center point of all the voxels in this shape (including empty ones).
946 ///
947 /// The voxel data associated to each center is provided to determine what kind of voxel
948 /// it is (and, in particular, if it is empty or full).
949 pub fn voxels(&self) -> impl Iterator<Item = VoxelData> + '_ {
950 let aabb = self.chunk_bvh.root_aabb();
951 self.voxels_in_range(
952 self.voxel_at_point(aabb.mins),
953 self.voxel_at_point(aabb.maxs),
954 )
955 }
956
957 /// Iterate through the data of all the voxels within the given (semi-open) voxel grid indices.
958 ///
959 /// Note that this yields both empty and non-empty voxels within the range. This does not
960 /// include any voxel that falls outside [`Self::domain`].
961 pub fn voxels_in_range(
962 &self,
963 mins: Point<i32>,
964 maxs: Point<i32>,
965 ) -> impl Iterator<Item = VoxelData> + '_ {
966 let range_aabb = Aabb::new(self.voxel_center(mins), self.voxel_center(maxs));
967
968 self.chunk_bvh
969 .leaves(move |node: &BvhNode| node.aabb().intersects(&range_aabb))
970 .flat_map(move |chunk_id| {
971 let chunk = self.chunk_ref(chunk_id);
972 chunk.voxels_in_range(mins, maxs)
973 })
974 }
975
976 fn voxel_to_chunk_key(voxel_key: Point<i32>) -> Point<i32> {
977 fn div_floor(a: i32, b: usize) -> i32 {
978 let sign = (a < 0) as i32;
979 (a + sign) / b as i32 - sign
980 }
981
982 voxel_key.map(|e| div_floor(e, VoxelsChunk::VOXELS_PER_CHUNK_DIM))
983 }
984
985 /// Given a voxel key, returns the key of the voxel chunk that contains it, as well as the
986 /// linear index of the voxel within that chunk.
987 #[cfg(feature = "dim2")]
988 pub(super) fn chunk_key_and_id_in_chunk(voxel_key: Point<i32>) -> (Point<i32>, usize) {
989 let chunk_key = Self::voxel_to_chunk_key(voxel_key);
990 // NOTE: always positive since we subtracted the smallest possible key on that chunk.
991 let voxel_key_in_chunk = voxel_key - chunk_key * VoxelsChunk::VOXELS_PER_CHUNK_DIM as i32;
992 let id_in_chunk = (voxel_key_in_chunk.x
993 + voxel_key_in_chunk.y * VoxelsChunk::VOXELS_PER_CHUNK_DIM as i32)
994 as usize;
995 (chunk_key, id_in_chunk)
996 }
997
998 /// Given a voxel key, returns the key of the voxel chunk that contains it, as well as the
999 /// linear index of the voxel within that chunk.
1000 #[cfg(feature = "dim3")]
1001 pub(super) fn chunk_key_and_id_in_chunk(voxel_key: Point<i32>) -> (Point<i32>, usize) {
1002 let chunk_key = Self::voxel_to_chunk_key(voxel_key);
1003 // NOTE: always positive since we subtracted the smallest possible key on that chunk.
1004 let voxel_key_in_chunk = voxel_key - chunk_key * VoxelsChunk::VOXELS_PER_CHUNK_DIM as i32;
1005 let id_in_chunk = (voxel_key_in_chunk.x
1006 + voxel_key_in_chunk.y * VoxelsChunk::VOXELS_PER_CHUNK_DIM as i32
1007 + voxel_key_in_chunk.z
1008 * VoxelsChunk::VOXELS_PER_CHUNK_DIM as i32
1009 * VoxelsChunk::VOXELS_PER_CHUNK_DIM as i32) as usize;
1010 (chunk_key, id_in_chunk)
1011 }
1012
1013 /// The linearized index associated to the given voxel key.
1014 pub fn linear_index(&self, voxel_key: Point<i32>) -> Option<VoxelIndex> {
1015 let (chunk_key, id_in_chunk) = Self::chunk_key_and_id_in_chunk(voxel_key);
1016 let chunk_id = self.chunk_headers.get(&chunk_key)?.id;
1017 Some(VoxelIndex {
1018 chunk_id,
1019 id_in_chunk,
1020 })
1021 }
1022
1023 /// The world-space center position of the voxel with the given grid coordinates.
1024 ///
1025 /// Returns the center point regardless of whether the voxel is actually filled.
1026 ///
1027 /// # Examples
1028 ///
1029 /// ```
1030 /// # #[cfg(all(feature = "dim3", feature = "f32"))] {
1031 /// use parry3d::shape::Voxels;
1032 /// use nalgebra::{Point3, Vector3};
1033 ///
1034 /// let voxels = Voxels::new(
1035 /// Vector3::new(1.0, 1.0, 1.0),
1036 /// &[Point3::new(0, 0, 0)],
1037 /// );
1038 ///
1039 /// // Center of voxel at origin
1040 /// assert_eq!(voxels.voxel_center(Point3::new(0, 0, 0)), Point3::new(0.5, 0.5, 0.5));
1041 ///
1042 /// // Center of voxel at (1, 2, 3)
1043 /// assert_eq!(voxels.voxel_center(Point3::new(1, 2, 3)), Point3::new(1.5, 2.5, 3.5));
1044 /// # }
1045 /// ```
1046 pub fn voxel_center(&self, key: Point<i32>) -> Point<Real> {
1047 (key.cast::<Real>() + Vector::repeat(0.5))
1048 .coords
1049 .component_mul(&self.voxel_size)
1050 .into()
1051 }
1052}