pub struct Voxels { /* private fields */ }Expand description
A shape made of axis-aligned, uniformly sized cubes (aka. voxels).
§What are Voxels?
Voxels (volumetric pixels) are 3D cubes (or 2D squares) arranged on a regular grid. Think of them as 3D building blocks, like LEGO bricks or Minecraft blocks. Each voxel has:
- A position on an integer grid (e.g.,
(0, 0, 0),(1, 2, 3)) - A uniform size (e.g., 1.0 × 1.0 × 1.0 meters)
- A state: filled (solid) or empty (air)
§When to Use Voxels?
Voxels are ideal for:
- Minecraft-style worlds: Block-based terrain and structures
- Destructible environments: Easy to add/remove individual blocks
- Procedural generation: Grid-based algorithms for caves, terrain, dungeons
- Volumetric data: Medical imaging, scientific simulations
- Retro aesthetics: Pixel art style in 3D
Voxels may NOT be ideal for:
- Smooth organic shapes (use meshes instead)
- Very large sparse worlds (consider octrees or chunk-based systems)
- Scenes requiring fine geometric detail at all scales
§The Internal Edges Problem
When an object slides across a flat surface made of voxels, it can snag on the edges between
adjacent voxels, causing jerky motion. Parry’s Voxels shape solves this by tracking neighbor
relationships: it knows which voxel faces are internal (adjacent to another voxel) vs external
(exposed to air), allowing smooth collision response.
§Memory Efficiency
The internal storage uses sparse chunks, storing only one byte per voxel for neighborhood information. Empty regions consume minimal memory. This is much more efficient than storing a triangle mesh representation of all voxel surfaces.
§Examples
§Basic Usage: Creating a Voxel Shape
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
// Create a simple 3×3×3 cube of voxels
let voxel_size = Vector3::new(1.0, 1.0, 1.0);
let mut coords = Vec::new();
for x in 0..3 {
for y in 0..3 {
for z in 0..3 {
coords.push(Point3::new(x, y, z));
}
}
}
let voxels = Voxels::new(voxel_size, &coords);
println!("Created voxel shape with {} voxels", coords.len());§Creating Voxels from World-Space Points
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
// Sample points in world space (e.g., from a point cloud)
let points = vec![
Point3::new(0.1, 0.2, 0.3),
Point3::new(1.5, 2.1, 3.7),
Point3::new(0.8, 0.9, 1.2),
];
// Create voxels with 0.5 unit size - nearby points merge into same voxel
let voxels = Voxels::from_points(Vector3::new(0.5, 0.5, 0.5), &points);
println!("Created voxel shape from {} points", points.len());§Querying Voxel State
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0), Point3::new(1, 0, 0)],
);
// Check if a specific grid position is filled
if let Some(state) = voxels.voxel_state(Point3::new(0, 0, 0)) {
println!("Voxel is filled!");
println!("Type: {:?}", state.voxel_type());
println!("Free faces: {:?}", state.free_faces());
} else {
println!("Voxel is empty or outside the domain");
}
// Convert world-space point to grid coordinates
let world_point = Point3::new(1.3, 0.7, 0.2);
let grid_coord = voxels.voxel_at_point(world_point);
println!("Point at {:?} is in voxel {:?}", world_point, grid_coord);§Iterating Through Voxels
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let voxels = Voxels::new(
Vector3::new(0.5, 0.5, 0.5),
&[Point3::new(0, 0, 0), Point3::new(1, 0, 0), Point3::new(0, 1, 0)],
);
// Iterate through all non-empty voxels
for voxel in voxels.voxels() {
if !voxel.state.is_empty() {
println!("Voxel at grid {:?}, world center {:?}",
voxel.grid_coords, voxel.center);
}
}§Modifying Voxels Dynamically
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let mut voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0)],
);
// Add a new voxel
voxels.set_voxel(Point3::new(1, 0, 0), true);
// Remove a voxel
voxels.set_voxel(Point3::new(0, 0, 0), false);
// Check the result
assert!(voxels.voxel_state(Point3::new(0, 0, 0)).unwrap().is_empty());
assert!(!voxels.voxel_state(Point3::new(1, 0, 0)).unwrap().is_empty());§Spatial Queries
use parry3d::shape::Voxels;
use parry3d::bounding_volume::Aabb;
use nalgebra::{Point3, Vector3};
let voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0), Point3::new(1, 0, 0), Point3::new(2, 0, 0)],
);
// Find voxels intersecting an AABB
let query_aabb = Aabb::new(Point3::new(-0.5, -0.5, -0.5), Point3::new(1.5, 1.5, 1.5));
let count = voxels.voxels_intersecting_local_aabb(&query_aabb)
.filter(|v| !v.state.is_empty())
.count();
println!("Found {} voxels in AABB", count);
// Get the overall domain bounds
let [mins, maxs] = voxels.domain();
println!("Voxel grid spans from {:?} to {:?}", mins, maxs);§See Also
VoxelState: Information about a voxel’s neighborsVoxelType: Classification of voxels by their topologyVoxelData: Complete information about a single voxelcrate::transformation::voxelization: Convert meshes to voxels
Implementations§
Source§impl Voxels
impl Voxels
Sourcepub fn bounding_sphere(&self, pos: &Isometry<f32>) -> BoundingSphere
pub fn bounding_sphere(&self, pos: &Isometry<f32>) -> BoundingSphere
Computes the world-space bounding sphere of this set of voxels, transformed by pos.
Sourcepub fn local_bounding_sphere(&self) -> BoundingSphere
pub fn local_bounding_sphere(&self) -> BoundingSphere
Computes the local-space bounding sphere of this set of voxels.
Source§impl Voxels
impl Voxels
Sourcepub fn new(voxel_size: Vector<f32>, grid_coordinates: &[Point<i32>]) -> Self
pub fn new(voxel_size: Vector<f32>, grid_coordinates: &[Point<i32>]) -> Self
Initializes a voxel shape from grid coordinates.
This is the primary constructor for creating a Voxels shape. You provide:
voxel_size: The physical dimensions of each voxel (e.g.,1.0 × 1.0 × 1.0meters)grid_coordinates: Integer grid positions for each filled voxel
§Coordinate System
Each voxel with grid coordinates (x, y, z) will be positioned such that:
- Its minimum corner (bottom-left-back) is at
(x, y, z) * voxel_size - Its center is at
((x, y, z) + 0.5) * voxel_size - Its maximum corner is at
((x, y, z) + 1) * voxel_size
For example, with voxel_size = 2.0 and grid coord (1, 0, 0):
- Minimum corner:
(2.0, 0.0, 0.0) - Center:
(3.0, 1.0, 1.0) - Maximum corner:
(4.0, 2.0, 2.0)
§Examples
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
// Create a 2×2×2 cube of voxels with 1.0 unit size
let voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[
Point3::new(0, 0, 0), Point3::new(1, 0, 0),
Point3::new(0, 1, 0), Point3::new(1, 1, 0),
Point3::new(0, 0, 1), Point3::new(1, 0, 1),
Point3::new(0, 1, 1), Point3::new(1, 1, 1),
],
);
// Verify the first voxel's center position
let center = voxels.voxel_center(Point3::new(0, 0, 0));
assert_eq!(center, Point3::new(0.5, 0.5, 0.5));use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
// Create a line of voxels along the X axis
let voxels = Voxels::new(
Vector3::new(0.5, 0.5, 0.5),
&[Point3::new(0, 0, 0), Point3::new(1, 0, 0), Point3::new(2, 0, 0)],
);
// Query the domain (bounding grid coordinates)
// Note: domain is aligned to internal chunk boundaries for efficiency
let [mins, maxs] = voxels.domain();
assert_eq!(mins, Point3::new(0, 0, 0));
// maxs will be chunk-aligned (chunks are 8x8x8), so it includes more space
assert!(maxs.x >= 3 && maxs.y >= 1 && maxs.z >= 1);Sourcepub fn from_points(voxel_size: Vector<f32>, points: &[Point<f32>]) -> Self
pub fn from_points(voxel_size: Vector<f32>, points: &[Point<f32>]) -> Self
Computes a voxel shape from a set of world-space points.
This constructor converts continuous world-space coordinates into discrete grid coordinates by snapping each point to the voxel grid. Multiple points can map to the same voxel.
§How it Works
Each point is converted to grid coordinates by:
- Dividing the point’s coordinates by
voxel_size - Taking the floor to get integer grid coordinates
- Removing duplicates (multiple points in the same voxel become one voxel)
For example, with voxel_size = 1.0:
- Point
(0.3, 0.7, 0.9)→ Grid(0, 0, 0) - Point
(1.1, 0.2, 0.5)→ Grid(1, 0, 0) - Point
(0.9, 0.1, 0.8)→ Grid(0, 0, 0)(merges with first)
§Use Cases
- Converting point clouds into voxel representations
- Creating voxel shapes from scattered data
- Simplifying complex point sets into uniform grids
§Examples
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
// Sample points in world space
let points = vec![
Point3::new(0.1, 0.2, 0.3), // → Grid (0, 0, 0)
Point3::new(0.7, 0.8, 0.9), // → Grid (0, 0, 0) - same voxel!
Point3::new(1.2, 0.3, 0.1), // → Grid (1, 0, 0)
Point3::new(0.5, 1.5, 0.2), // → Grid (0, 1, 0)
];
// Create voxels with 1.0 unit size
let voxels = Voxels::from_points(Vector3::new(1.0, 1.0, 1.0), &points);
// Only 3 unique voxels created (first two points merged)
let filled_count = voxels.voxels()
.filter(|v| !v.state.is_empty())
.count();
assert_eq!(filled_count, 3);use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
// Higher resolution voxelization
let points = vec![
Point3::origin(),
Point3::new(1.0, 1.0, 1.0),
];
// Smaller voxels = finer detail
let voxels = Voxels::from_points(Vector3::new(0.5, 0.5, 0.5), &points);
// First point at grid (0,0,0), second at grid (2,2,2) due to smaller voxel size
assert!(voxels.voxel_state(Point3::new(0, 0, 0)).is_some());
assert!(voxels.voxel_state(Point3::new(2, 2, 2)).is_some());Sourcepub fn domain(&self) -> [Point<i32>; 2]
pub fn domain(&self) -> [Point<i32>; 2]
The semi-open range of grid coordinates covered by this voxel shape.
Returns [mins, maxs] where the domain is the semi-open interval [mins, maxs),
meaning mins is included but maxs is excluded. This provides conservative bounds
on the range of voxel grid coordinates that might be filled.
This is useful for:
- Determining the spatial extent of the voxel shape
- Pre-allocating storage for processing voxels
- Clipping operations to valid regions
§Examples
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0), Point3::new(2, 3, 1)],
);
let [mins, maxs] = voxels.domain();
assert_eq!(mins, Point3::new(0, 0, 0));
// Domain is conservative and chunk-aligned
assert!(maxs.x > 2 && maxs.y > 3 && maxs.z > 1);
// Iterate through filled voxels (more efficient than iterating domain)
for voxel in voxels.voxels() {
if !voxel.state.is_empty() {
println!("Filled voxel at {:?}", voxel.grid_coords);
}
}Sourcepub fn voxel_size(&self) -> Vector<f32>
pub fn voxel_size(&self) -> Vector<f32>
The size of each voxel part this Voxels shape.
Sourcepub fn chunk_ref(&self, chunk_id: u32) -> VoxelsChunkRef<'_>
pub fn chunk_ref(&self, chunk_id: u32) -> VoxelsChunkRef<'_>
A reference to the chunk with id chunk_id.
Panics if the chunk doesn’t exist.
Sourcepub fn voxel_aabb(&self, key: Point<i32>) -> Aabb
pub fn voxel_aabb(&self, key: Point<i32>) -> Aabb
The AABB of the voxel with the given quantized key.
Sourcepub fn voxel_state(&self, key: Point<i32>) -> Option<VoxelState>
pub fn voxel_state(&self, key: Point<i32>) -> Option<VoxelState>
Returns the state of the voxel at the given grid coordinates.
Returns None if the voxel doesn’t exist in this shape’s internal storage,
or Some(VoxelState) containing information about whether the voxel is filled
and which of its neighbors are also filled.
§Examples
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0), Point3::new(1, 0, 0)],
);
// Query an existing voxel
if let Some(state) = voxels.voxel_state(Point3::new(0, 0, 0)) {
assert!(!state.is_empty());
println!("Voxel type: {:?}", state.voxel_type());
}
// Query a non-existent voxel
assert!(voxels.voxel_state(Point3::new(10, 10, 10)).is_none());Sourcepub fn voxel_at_point(&self, point: Point<f32>) -> Point<i32>
pub fn voxel_at_point(&self, point: Point<f32>) -> Point<i32>
Calculates the grid coordinates of the voxel containing the given world-space point.
This conversion is independent of whether the voxel is actually filled or empty - it simply determines which grid cell the point falls into based on the voxel size.
§Examples
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0)],
);
// Point in first voxel (center at 0.5, 0.5, 0.5)
assert_eq!(voxels.voxel_at_point(Point3::new(0.3, 0.7, 0.2)), Point3::new(0, 0, 0));
// Point just inside second voxel boundary
assert_eq!(voxels.voxel_at_point(Point3::new(1.0, 0.0, 0.0)), Point3::new(1, 0, 0));
// Negative coordinates work too
assert_eq!(voxels.voxel_at_point(Point3::new(-0.5, -0.5, -0.5)), Point3::new(-1, -1, -1));use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
// With non-uniform voxel size
let voxels = Voxels::new(
Vector3::new(2.0, 0.5, 1.0),
&[],
);
// X coordinate divided by 2.0, Y by 0.5, Z by 1.0
assert_eq!(voxels.voxel_at_point(Point3::new(3.0, 1.2, 0.8)), Point3::new(1, 2, 0));Sourcepub fn voxel_at_flat_id(&self, id: u32) -> Option<Point<i32>>
pub fn voxel_at_flat_id(&self, id: u32) -> Option<Point<i32>>
Gets the voxel at the given flat voxel index.
Sourcepub fn voxel_range_intersecting_local_aabb(
&self,
aabb: &Aabb,
) -> [Point<i32>; 2]
pub fn voxel_range_intersecting_local_aabb( &self, aabb: &Aabb, ) -> [Point<i32>; 2]
The range of grid coordinates of voxels intersecting the given AABB.
The returned range covers both empty and non-empty voxels, and is not limited to the
bounds defined by Self::domain.
The range is semi, open, i.e., the range along each dimension i is understood as
the semi-open interval: range[0][i]..range[1][i].
Sourcepub fn voxel_range_aabb(&self, mins: Point<i32>, maxs: Point<i32>) -> Aabb
pub fn voxel_range_aabb(&self, mins: Point<i32>, maxs: Point<i32>) -> Aabb
The AABB of a given range of voxels.
The AABB is computed independently of Self::domain and independently of whether
the voxels contained within are empty or not.
Sourcepub fn align_aabb_to_grid(&self, aabb: &Aabb) -> Aabb
pub fn align_aabb_to_grid(&self, aabb: &Aabb) -> Aabb
Aligns the given AABB with the voxelized grid.
The aligned is calculated such that the returned AABB has corners lying at the grid
intersections (i.e. matches voxel corners) and fully contains the input aabb.
Sourcepub fn voxels_intersecting_local_aabb(
&self,
aabb: &Aabb,
) -> impl Iterator<Item = VoxelData> + '_
pub fn voxels_intersecting_local_aabb( &self, aabb: &Aabb, ) -> impl Iterator<Item = VoxelData> + '_
Iterates through every voxel intersecting the given aabb.
Returns the voxel’s linearized id, center, and state.
Sourcepub fn voxels(&self) -> impl Iterator<Item = VoxelData> + '_
pub fn voxels(&self) -> impl Iterator<Item = VoxelData> + '_
The center point of all the voxels in this shape (including empty ones).
The voxel data associated to each center is provided to determine what kind of voxel it is (and, in particular, if it is empty or full).
Sourcepub fn voxels_in_range(
&self,
mins: Point<i32>,
maxs: Point<i32>,
) -> impl Iterator<Item = VoxelData> + '_
pub fn voxels_in_range( &self, mins: Point<i32>, maxs: Point<i32>, ) -> impl Iterator<Item = VoxelData> + '_
Iterate through the data of all the voxels within the given (semi-open) voxel grid indices.
Note that this yields both empty and non-empty voxels within the range. This does not
include any voxel that falls outside Self::domain.
Sourcepub fn linear_index(&self, voxel_key: Point<i32>) -> Option<VoxelIndex>
pub fn linear_index(&self, voxel_key: Point<i32>) -> Option<VoxelIndex>
The linearized index associated to the given voxel key.
Sourcepub fn voxel_center(&self, key: Point<i32>) -> Point<f32>
pub fn voxel_center(&self, key: Point<i32>) -> Point<f32>
The world-space center position of the voxel with the given grid coordinates.
Returns the center point regardless of whether the voxel is actually filled.
§Examples
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0)],
);
// Center of voxel at origin
assert_eq!(voxels.voxel_center(Point3::new(0, 0, 0)), Point3::new(0.5, 0.5, 0.5));
// Center of voxel at (1, 2, 3)
assert_eq!(voxels.voxel_center(Point3::new(1, 2, 3)), Point3::new(1.5, 2.5, 3.5));Source§impl Voxels
impl Voxels
Sourcepub fn set_voxel_size(&mut self, new_size: Vector<f32>)
pub fn set_voxel_size(&mut self, new_size: Vector<f32>)
Sets the size of each voxel along each local coordinate axis.
Since the internal spatial acceleration structure needs to be updated, this
operation runs in O(n) time, where n is the number of voxels.
Sourcepub fn set_voxel(&mut self, key: Point<i32>, is_filled: bool) -> VoxelState
pub fn set_voxel(&mut self, key: Point<i32>, is_filled: bool) -> VoxelState
Adds or removes a voxel at the specified grid coordinates.
This is the primary method for dynamically modifying a voxel shape. It can:
- Add a new voxel by setting
is_filled = true - Remove an existing voxel by setting
is_filled = false
The method automatically updates the neighborhood information for the affected voxel and all its neighbors to maintain correct collision detection behavior.
§Returns
The previous VoxelState of the voxel before modification. This allows you to
detect whether the operation actually changed anything.
§Examples
§Adding Voxels
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let mut voxels = Voxels::new(Vector3::new(1.0, 1.0, 1.0), &[]);
// Add a voxel at (0, 0, 0)
let prev_state = voxels.set_voxel(Point3::new(0, 0, 0), true);
assert!(prev_state.is_empty()); // Was empty before
// Verify it was added
let state = voxels.voxel_state(Point3::new(0, 0, 0)).unwrap();
assert!(!state.is_empty());§Removing Voxels
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let mut voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0), Point3::new(1, 0, 0)],
);
// Remove the voxel at (0, 0, 0)
voxels.set_voxel(Point3::new(0, 0, 0), false);
// Verify it was removed
let state = voxels.voxel_state(Point3::new(0, 0, 0)).unwrap();
assert!(state.is_empty());§Building Shapes Dynamically
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let mut voxels = Voxels::new(Vector3::new(1.0, 1.0, 1.0), &[]);
// Build a 3×3 floor
for x in 0..3 {
for z in 0..3 {
voxels.set_voxel(Point3::new(x, 0, z), true);
}
}
// Count filled voxels
let filled = voxels.voxels()
.filter(|v| !v.state.is_empty())
.count();
assert_eq!(filled, 9);§Detecting Changes
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let mut voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[Point3::new(0, 0, 0)],
);
// Try to add a voxel that already exists
let prev = voxels.set_voxel(Point3::new(0, 0, 0), true);
if !prev.is_empty() {
println!("Voxel was already filled!");
}Sourcepub fn crop(&mut self, domain_mins: Point<i32>, domain_maxs: Point<i32>)
pub fn crop(&mut self, domain_mins: Point<i32>, domain_maxs: Point<i32>)
Crops the voxel shape in-place to a rectangular region.
Removes all voxels outside the specified grid coordinate bounds [domain_mins, domain_maxs]
(inclusive on both ends). This is useful for:
- Extracting a sub-region of a larger voxel world
- Removing voxels outside a region of interest
- Implementing chunk-based world management
§Examples
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};
let mut voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[
Point3::new(0, 0, 0),
Point3::new(1, 0, 0),
Point3::new(2, 0, 0),
Point3::new(3, 0, 0),
],
);
// Keep only voxels in the range [1, 2]
voxels.crop(Point3::new(1, 0, 0), Point3::new(2, 0, 0));
// Only two voxels remain
let count = voxels.voxels()
.filter(|v| !v.state.is_empty())
.count();
assert_eq!(count, 2);Sourcepub fn cropped(
&self,
domain_mins: Point<i32>,
domain_maxs: Point<i32>,
) -> Option<Self>
pub fn cropped( &self, domain_mins: Point<i32>, domain_maxs: Point<i32>, ) -> Option<Self>
Returns a cropped version of this voxel shape with a rectangular domain.
This removes every voxels out of the [domain_mins, domain_maxs] bounds.
Sourcepub fn split_with_box(&self, aabb: &Aabb) -> (Option<Self>, Option<Self>)
pub fn split_with_box(&self, aabb: &Aabb) -> (Option<Self>, Option<Self>)
Splits this voxel shape into two separate shapes based on an AABB.
Partitions the voxels into two groups:
- Inside: Voxels whose centers fall inside the given
aabb - Outside: All remaining voxels
Returns (Some(inside), Some(outside)), or None for either if that partition is empty.
§Use Cases
- Spatial partitioning for physics simulation
- Implementing destructible objects (remove the “inside” part on explosion)
- Chunk-based world management
- Level-of-detail systems
§Examples
use parry3d::shape::Voxels;
use parry3d::bounding_volume::Aabb;
use nalgebra::{Point3, Vector3};
let voxels = Voxels::new(
Vector3::new(1.0, 1.0, 1.0),
&[
Point3::new(0, 0, 0), // Center at (0.5, 0.5, 0.5)
Point3::new(2, 0, 0), // Center at (2.5, 0.5, 0.5)
Point3::new(4, 0, 0), // Center at (4.5, 0.5, 0.5)
],
);
// Split at X = 3.0
let split_box = Aabb::new(
Point3::new(-10.0, -10.0, -10.0),
Point3::new(3.0, 10.0, 10.0),
);
let (inside, outside) = voxels.split_with_box(&split_box);
// First two voxels inside, last one outside
assert!(inside.is_some());
assert!(outside.is_some());Source§impl Voxels
impl Voxels
Sourcepub fn propagate_voxel_change(
&mut self,
other: &mut Self,
voxel: Point<i32>,
origin_shift: Vector<i32>,
)
pub fn propagate_voxel_change( &mut self, other: &mut Self, voxel: Point<i32>, origin_shift: Vector<i32>, )
Merges voxel state (neighborhood) information of a given voxel (and all its neighbors)
from self and other, to account for a recent change to the given voxel in self.
This is designed to be called after self was modified with Voxels::set_voxel.
This is the same as Voxels::combine_voxel_states but localized to a single voxel and its
neighbors.
Sourcepub fn combine_voxel_states(
&mut self,
other: &mut Self,
origin_shift: Vector<i32>,
)
pub fn combine_voxel_states( &mut self, other: &mut Self, origin_shift: Vector<i32>, )
Merges voxel state (neighborhood) information of each voxel from self and other.
This allows each voxel from one shape to be aware of the presence of neighbors belonging to the other so that collision detection is capable of transitioning between the boundaries of one shape to the other without hitting an internal edge.
Both voxels shapes are assumed to have the same Self::voxel_size.
If other lives in a coordinate space with a different origin than self, then
origin_shift represents the distance (as a multiple of the voxel_size) from the origin
of self to the origin of other. Therefore, a voxel with coordinates key on other
will have coordinates key + origin_shift on self.
Source§impl Voxels
impl Voxels
Sourcepub fn total_memory_size(&self) -> usize
pub fn total_memory_size(&self) -> usize
An approximation of the memory usage (in bytes) for this struct plus the memory it allocates dynamically.
Sourcepub fn heap_memory_size(&self) -> usize
pub fn heap_memory_size(&self) -> usize
An approximation of the memory dynamically-allocated by this struct.
Trait Implementations§
Source§impl PointQuery for Voxels
impl PointQuery for Voxels
Source§fn project_local_point(&self, pt: &Point<f32>, solid: bool) -> PointProjection
fn project_local_point(&self, pt: &Point<f32>, solid: bool) -> PointProjection
self. Read moreSource§fn project_local_point_and_get_feature(
&self,
pt: &Point<f32>,
) -> (PointProjection, FeatureId)
fn project_local_point_and_get_feature( &self, pt: &Point<f32>, ) -> (PointProjection, FeatureId)
self and returns the id of the
feature the point was projected on.Source§fn project_local_point_with_max_dist(
&self,
pt: &Point<f32>,
solid: bool,
max_dist: f32,
) -> Option<PointProjection>
fn project_local_point_with_max_dist( &self, pt: &Point<f32>, solid: bool, max_dist: f32, ) -> Option<PointProjection>
Source§fn project_point_with_max_dist(
&self,
m: &Isometry<f32>,
pt: &Point<f32>,
solid: bool,
max_dist: f32,
) -> Option<PointProjection>
fn project_point_with_max_dist( &self, m: &Isometry<f32>, pt: &Point<f32>, solid: bool, max_dist: f32, ) -> Option<PointProjection>
self transformed by m, unless the projection lies further than the given max distance.Source§fn distance_to_local_point(&self, pt: &Point<f32>, solid: bool) -> f32
fn distance_to_local_point(&self, pt: &Point<f32>, solid: bool) -> f32
self.Source§fn contains_local_point(&self, pt: &Point<f32>) -> bool
fn contains_local_point(&self, pt: &Point<f32>) -> bool
self.Source§fn project_point(
&self,
m: &Isometry<f32>,
pt: &Point<f32>,
solid: bool,
) -> PointProjection
fn project_point( &self, m: &Isometry<f32>, pt: &Point<f32>, solid: bool, ) -> PointProjection
self transformed by m.Source§fn distance_to_point(
&self,
m: &Isometry<f32>,
pt: &Point<f32>,
solid: bool,
) -> f32
fn distance_to_point( &self, m: &Isometry<f32>, pt: &Point<f32>, solid: bool, ) -> f32
self transformed by m.Source§fn project_point_and_get_feature(
&self,
m: &Isometry<f32>,
pt: &Point<f32>,
) -> (PointProjection, FeatureId)
fn project_point_and_get_feature( &self, m: &Isometry<f32>, pt: &Point<f32>, ) -> (PointProjection, FeatureId)
self transformed by m and returns the id of the
feature the point was projected on.Source§impl RayCast for Voxels
impl RayCast for Voxels
Source§fn cast_local_ray_and_get_normal(
&self,
ray: &Ray,
max_time_of_impact: f32,
solid: bool,
) -> Option<RayIntersection>
fn cast_local_ray_and_get_normal( &self, ray: &Ray, max_time_of_impact: f32, solid: bool, ) -> Option<RayIntersection>
Source§fn cast_local_ray(
&self,
ray: &Ray,
max_time_of_impact: f32,
solid: bool,
) -> Option<f32>
fn cast_local_ray( &self, ray: &Ray, max_time_of_impact: f32, solid: bool, ) -> Option<f32>
Source§fn intersects_local_ray(&self, ray: &Ray, max_time_of_impact: f32) -> bool
fn intersects_local_ray(&self, ray: &Ray, max_time_of_impact: f32) -> bool
Source§fn cast_ray(
&self,
m: &Isometry<f32>,
ray: &Ray,
max_time_of_impact: f32,
solid: bool,
) -> Option<f32>
fn cast_ray( &self, m: &Isometry<f32>, ray: &Ray, max_time_of_impact: f32, solid: bool, ) -> Option<f32>
Source§fn cast_ray_and_get_normal(
&self,
m: &Isometry<f32>,
ray: &Ray,
max_time_of_impact: f32,
solid: bool,
) -> Option<RayIntersection>
fn cast_ray_and_get_normal( &self, m: &Isometry<f32>, ray: &Ray, max_time_of_impact: f32, solid: bool, ) -> Option<RayIntersection>
Source§impl Shape for Voxels
impl Shape for Voxels
Source§fn compute_local_aabb(&self) -> Aabb
fn compute_local_aabb(&self) -> Aabb
Aabb of this shape.Source§fn compute_local_bounding_sphere(&self) -> BoundingSphere
fn compute_local_bounding_sphere(&self) -> BoundingSphere
Source§fn scale_dyn(
&self,
scale: &Vector<f32>,
_num_subdivisions: u32,
) -> Option<Box<dyn Shape>>
fn scale_dyn( &self, scale: &Vector<f32>, _num_subdivisions: u32, ) -> Option<Box<dyn Shape>>
scale into a boxed trait-object. Read moreSource§fn mass_properties(&self, density: f32) -> MassProperties
fn mass_properties(&self, density: f32) -> MassProperties
Source§fn shape_type(&self) -> ShapeType
fn shape_type(&self) -> ShapeType
Source§fn as_typed_shape(&self) -> TypedShape<'_>
fn as_typed_shape(&self) -> TypedShape<'_>
fn ccd_thickness(&self) -> f32
fn ccd_angular_thickness(&self) -> f32
Source§fn clone_box(&self) -> Box<dyn Shape>
fn clone_box(&self) -> Box<dyn Shape>
clone_dynSource§fn compute_aabb(&self, position: &Isometry<f32>) -> Aabb
fn compute_aabb(&self, position: &Isometry<f32>) -> Aabb
Aabb of this shape with the given position.Source§fn compute_bounding_sphere(&self, position: &Isometry<f32>) -> BoundingSphere
fn compute_bounding_sphere(&self, position: &Isometry<f32>) -> BoundingSphere
Source§fn as_support_map(&self) -> Option<&dyn SupportMap>
fn as_support_map(&self) -> Option<&dyn SupportMap>
fn as_composite_shape(&self) -> Option<&dyn CompositeShape>
Source§fn as_polygonal_feature_map(&self) -> Option<(&dyn PolygonalFeatureMap, f32)>
fn as_polygonal_feature_map(&self) -> Option<(&dyn PolygonalFeatureMap, f32)>
Auto Trait Implementations§
impl Freeze for Voxels
impl RefUnwindSafe for Voxels
impl Send for Voxels
impl Sync for Voxels
impl Unpin for Voxels
impl UnwindSafe for Voxels
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<T> Downcast for Twhere
T: Any,
impl<T> Downcast for Twhere
T: Any,
Source§fn into_any(self: Box<T>) -> Box<dyn Any>
fn into_any(self: Box<T>) -> Box<dyn Any>
Box<dyn Trait> (where Trait: Downcast) to Box<dyn Any>, which can then be
downcast into Box<dyn ConcreteType> where ConcreteType implements Trait.Source§fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
Rc<Trait> (where Trait: Downcast) to Rc<Any>, which can then be further
downcast into Rc<ConcreteType> where ConcreteType implements Trait.Source§fn as_any(&self) -> &(dyn Any + 'static)
fn as_any(&self) -> &(dyn Any + 'static)
&Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot
generate &Any’s vtable from &Trait’s.Source§fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
&mut Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot
generate &mut Any’s vtable from &mut Trait’s.Source§impl<T> DowncastSend for T
impl<T> DowncastSend for T
Source§impl<T> DowncastSync for T
impl<T> DowncastSync for T
Source§impl<T> IntoEither for T
impl<T> IntoEither for T
Source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
self into a Left variant of Either<Self, Self>
if into_left is true.
Converts self into a Right variant of Either<Self, Self>
otherwise. Read moreSource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
self into a Left variant of Either<Self, Self>
if into_left(&self) returns true.
Converts self into a Right variant of Either<Self, Self>
otherwise. Read moreSource§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self is actually part of its subset T (and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self to the equivalent element of its superset.