Struct MassProperties

Source
pub struct MassProperties {
    pub local_com: Point<f32>,
    pub inv_mass: f32,
    pub inv_principal_inertia: AngVector<f32>,
    pub principal_inertia_local_frame: Rotation<f32>,
}
Expand description

The mass properties of a rigid body.

Mass properties define how an object responds to forces and torques in physics simulation. They include the mass, center of mass, and angular inertia (resistance to rotation).

§Fields

  • local_com: Center of mass in the shape’s local coordinate system
  • inv_mass: Inverse mass (1/mass). Zero = infinite mass (immovable)
  • inv_principal_inertia: Inverse angular inertia along principal axes
  • principal_inertia_local_frame (3D only): Rotation to principal inertia axes

§Why Inverse Values?

Physics engines store inverse mass and inertia because:

  • Infinite mass/inertia (immovable objects) = zero inverse
  • Avoids division in the simulation loop (multiply by inverse instead)
  • More numerically stable for very heavy objects

§Angular Inertia

Angular inertia (moment of inertia) describes resistance to rotation:

  • Higher values: Harder to spin (like a heavy wheel)
  • Lower values: Easier to spin (like a light rod)
  • Different per axis: Objects resist rotation differently around different axes

§Principal Inertia

The inertia tensor is diagonalized to principal axes:

  • Rotation around principal axes is independent
  • Simplifies physics calculations
  • In 2D: Only one axis (perpendicular to the plane)
  • In 3D: Three orthogonal axes

§Example

use parry3d::mass_properties::MassProperties;
use parry3d::shape::{Ball, Shape};
use nalgebra::Point3;

// Compute mass properties for a unit ball with density 1.0
let ball = Ball::new(1.0);
let props = ball.mass_properties(1.0);

// Mass of a unit sphere with density 1.0
let mass = props.mass();
println!("Mass: {}", mass);

// Center of mass (at origin for a ball)
assert_eq!(props.local_com, Point3::origin());

// For simulation, use inverse values
if props.inv_mass > 0.0 {
    // Object has finite mass - can be moved
    println!("Can apply forces");
} else {
    // Object has infinite mass - immovable (like terrain)
    println!("Static/kinematic object");
}

§Combining Mass Properties

Mass properties can be added to create compound objects:

use parry3d::mass_properties::MassProperties;
use parry3d::shape::{Ball, Cuboid, Shape};
use nalgebra::Vector3;

let ball = Ball::new(1.0);
let cuboid = Cuboid::new(Vector3::new(1.0, 1.0, 1.0));

let ball_props = ball.mass_properties(1.0);
let cuboid_props = cuboid.mass_properties(1.0);

// Combined properties (ball + cuboid)
let combined = ball_props + cuboid_props;

// Total mass is sum of individual masses
let total_mass = combined.mass();
println!("Combined mass: {}", total_mass);

Fields§

§local_com: Point<f32>

The center of mass in local (shape-relative) coordinates.

This is the balance point of the object. For symmetric shapes, it’s typically at the geometric center. All angular inertia calculations are relative to this point.

§inv_mass: f32

The inverse of the mass (1 / mass).

  • Positive value: Normal object with finite mass
  • Zero: Infinite mass (immovable/static object)

To get the actual mass, use mass() method or compute 1.0 / inv_mass.

§inv_principal_inertia: AngVector<f32>

The inverse of the principal angular inertia values.

These are the angular inertia values along the principal inertia axes:

  • 2D: Single scalar value (rotation around perpendicular axis)
  • 3D: Vector of three values (rotation around X, Y, Z principal axes)

Angular inertia relative to the center of mass (local_com). Zero components indicate infinite inertia (no rotation) along that axis.

§principal_inertia_local_frame: Rotation<f32>

The rotation from local coordinates to principal inertia axes (3D only).

This rotation aligns the object’s coordinate system with its principal axes of inertia, where the inertia tensor is diagonal.

Implementations§

Source§

impl MassProperties

Source

pub fn new( local_com: Point<f32>, mass: f32, principal_inertia: AngVector<f32>, ) -> Self

Initializes the mass properties from the given center-of-mass, mass, and principal angular inertia.

The center-of-mass is specified in the local-space of the rigid-body. The principal angular inertia are the angular inertia along the coordinate axes in the local-space of the rigid-body.

Source

pub fn with_principal_inertia_frame( local_com: Point<f32>, mass: f32, principal_inertia: AngVector<f32>, principal_inertia_local_frame: Rotation<f32>, ) -> Self

Initializes the mass properties from the given center-of-mass, mass, and principal angular inertia.

The center-of-mass is specified in the local-space of the rigid-body. The principal angular inertia are the angular inertia along the coordinate axes defined by the principal_inertia_local_frame expressed in the local-space of the rigid-body.

Source

pub fn with_inertia_matrix( local_com: Point<f32>, mass: f32, inertia: Matrix3<f32>, ) -> Self

Initialize a new MassProperties from a given center-of-mass, mass, and angular inertia matrix.

The angular inertia matrix will be diagonalized in order to extract the principal inertia values and principal inertia frame.

Source

pub fn mass(&self) -> f32

The mass.

Source

pub fn principal_inertia(&self) -> AngVector<f32>

The angular inertia along the principal inertia axes and center of mass of the rigid-body.

Source

pub fn world_com(&self, pos: &Isometry<f32>) -> Point<f32>

The world-space center of mass of the rigid-body.

Source

pub fn world_inv_inertia(&self, rot: &Rotation<f32>) -> AngularInertia<f32>

The world-space inverse angular inertia tensor of the rigid-body.

Source

pub fn reconstruct_inverse_inertia_matrix(&self) -> Matrix3<f32>

Reconstructs the inverse angular inertia tensor of the rigid body from its principal inertia values and axes.

Source

pub fn reconstruct_inertia_matrix(&self) -> Matrix3<f32>

Reconstructs the angular inertia tensor of the rigid body from its principal inertia values and axes.

Source

pub fn transform_by(&self, m: &Isometry<f32>) -> Self

Transform each element of the mass properties.

Source

pub fn set_mass(&mut self, new_mass: f32, adjust_angular_inertia: bool)

Changes the mass on these mass-properties.

The adjust_angular_inertia argument should always be true, unless there are some specific reasons not to do so. Setting this to true will automatically adjust the angular inertia of self to account for the mass change (i.e. it will multiply the angular inertia by new_mass / prev_mass). Setting it to false will not change the current angular inertia.

Source§

impl MassProperties

Source

pub fn from_ball(density: f32, radius: f32) -> Self

Computes the mass properties of a ball (sphere in 3D, circle in 2D).

A ball is a perfectly round geometric shape defined by its radius. This function calculates the physical properties needed for physics simulation, including mass, center of mass, and angular inertia (resistance to rotation).

§Arguments
  • density - The material density (mass per unit volume/area). Higher values make heavier objects.
    • In 3D: units are typically kg/m³ (e.g., water = 1000, steel = 7850)
    • In 2D: units are typically kg/m² (mass per unit area)
  • radius - The radius of the ball (distance from center to surface)
§Returns

A MassProperties struct containing:

  • mass: Total mass calculated from volume and density
  • local_com: Center of mass at the origin (balls are perfectly symmetric)
  • inv_principal_inertia: Inverse angular inertia (resistance to spinning)
§Physics Background

Balls have uniform density and perfect symmetry, which means:

  • The center of mass is at the geometric center (origin)
  • All rotational axes have the same angular inertia (isotropic)
  • In 3D: moment of inertia = (2/5) * mass * radius²
  • In 2D: moment of inertia = (1/2) * mass * radius²
§Example (3D)
use parry3d::mass_properties::MassProperties;
use nalgebra::Point3;

// Create mass properties for a 0.5m radius ball with density 1000 kg/m³ (water density)
let radius = 0.5;
let density = 1000.0;
let ball_props = MassProperties::from_ball(density, radius);

// Volume of sphere: (4/3) * π * r³ = 0.524 m³
// Mass: volume * density = 524 kg
let mass = ball_props.mass();
assert!((mass - 523.6).abs() < 1.0); // Approximately 524 kg

// Center of mass is at the origin for symmetric shapes
assert_eq!(ball_props.local_com, Point3::origin());

// Check if object can be moved (finite mass)
assert!(ball_props.inv_mass > 0.0, "Ball has finite mass and can move");
§Example (2D)
use parry2d::mass_properties::MassProperties;
use nalgebra::Point2;

// Create a circular disc with 1.0m radius and density 100 kg/m²
let radius = 1.0;
let density = 100.0;
let circle_props = MassProperties::from_ball(density, radius);

// Area of circle: π * r² = 3.14 m²
// Mass: area * density = 314 kg
let mass = circle_props.mass();
assert!((mass - 314.159).abs() < 0.1); // Approximately 314 kg

println!("Circle mass: {:.2} kg", mass);
println!("Moment of inertia: {:.2}", circle_props.principal_inertia());
§Use Cases
  • Sports balls: Soccer balls, basketballs, bowling balls
  • Planets and celestial bodies: Spherical approximations
  • Particles: Point-like objects with rotational inertia
  • Wheels and gears: Cylindrical objects in 2D simulations
§Performance Note

This is a very fast computation (constant time) as it only involves basic arithmetic with the radius and density. Balls are the simplest shape for collision detection and physics simulation.

Source§

impl MassProperties

Source

pub fn from_capsule( density: f32, a: Point<f32>, b: Point<f32>, radius: f32, ) -> Self

Computes the mass properties of a capsule (pill-shaped object).

A capsule is a cylinder with hemispherical caps on both ends. It’s defined by two endpoint centers (a line segment) and a radius. Capsules are commonly used for character controllers and elongated objects because they provide smooth collision handling without sharp edges.

§Arguments
  • density - The material density (mass per unit volume/area). Higher values make heavier objects.
    • In 3D: units are typically kg/m³
    • In 2D: units are typically kg/m² (mass per unit area)
  • a - First endpoint of the capsule’s central axis (center of first hemisphere)
  • b - Second endpoint of the capsule’s central axis (center of second hemisphere)
  • radius - The radius of the capsule (distance from the axis to the surface)
§Returns

A MassProperties struct containing:

  • mass: Total mass calculated from volume and density
  • local_com: Center of mass at the midpoint between a and b
  • inv_principal_inertia: Inverse angular inertia (varies by axis)
  • principal_inertia_local_frame (3D only): Rotation aligning capsule axis with Y
§Physics Background

A capsule consists of:

  • A cylindrical body connecting the two endpoints
  • Two hemispherical caps (which together form one complete sphere)
  • The total length is: distance(a, b) + 2 * radius
  • Mass and inertia are computed by combining cylinder + sphere components
§Example (3D) - Character Controller
use parry3d::mass_properties::MassProperties;
use nalgebra::Point3;

// Create a capsule for a standing character (height ~2m, radius 0.3m)
// Endpoints at (0, 0, 0) and (0, 2, 0) form vertical capsule
let a = Point3::origin();
let b = Point3::new(0.0, 2.0, 0.0);
let radius = 0.3;
let density = 985.0; // Similar to human body density

let character_props = MassProperties::from_capsule(density, a, b, radius);

// Center of mass is at the midpoint
let expected_com = Point3::new(0.0, 1.0, 0.0);
assert!((character_props.local_com - expected_com).norm() < 0.01);

let mass = character_props.mass();
println!("Character mass: {:.2} kg", mass); // Approximately 70-80 kg

// Inertia is higher around horizontal axes (harder to tip over)
let inertia = character_props.principal_inertia();
println!("Inertia X: {:.2}, Y: {:.2}, Z: {:.2}", inertia.x, inertia.y, inertia.z);
§Example (3D) - Horizontal Capsule (Lying Down)
use parry3d::mass_properties::MassProperties;
use nalgebra::Point3;

// Create a horizontal capsule along the X-axis
let a = Point3::new(-1.0, 0.0, 0.0);
let b = Point3::new(1.0, 0.0, 0.0);
let radius = 0.5;
let density = 1000.0;

let capsule_props = MassProperties::from_capsule(density, a, b, radius);

// Center of mass at midpoint (origin)
assert_eq!(capsule_props.local_com, Point3::origin());

// Total length = distance + 2*radius = 2.0 + 1.0 = 3.0 meters
println!("Mass: {:.2} kg", capsule_props.mass());
§Example (2D) - Stadium Shape
use parry2d::mass_properties::MassProperties;
use nalgebra::Point2;

// Create a horizontal 2D capsule (stadium/discorectangle shape)
let a = Point2::new(-2.0, 0.0);
let b = Point2::new(2.0, 0.0);
let radius = 1.0;
let density = 100.0; // kg/m²

let stadium_props = MassProperties::from_capsule(density, a, b, radius);

println!("Stadium mass: {:.2} kg", stadium_props.mass());
println!("Moment of inertia: {:.2}", stadium_props.principal_inertia());
§Use Cases
  • Character controllers: Humanoid characters, NPCs
  • Vehicles: Simplified car or boat bodies
  • Projectiles: Bullets, missiles, arrows
  • Limbs: Arms, legs in ragdoll physics
  • Cylinders with rounded ends: Pipes, rods, poles
§Common Mistakes
  • Total length confusion: The visual length is distance(a, b) + 2 * radius, not just distance(a, b). The hemispheres add extra length.
  • Endpoint placement: Points a and b are centers of the hemispherical caps, not the extreme ends of the capsule.
§Performance Note

Capsules are very efficient for collision detection (almost as fast as spheres) and provide smooth rolling behavior. They’re preferred over cylinders for dynamic objects that need to move smoothly.

Source§

impl MassProperties

Source

pub fn from_compound( density: f32, shapes: &[(Isometry<f32>, SharedShape)], ) -> Self

Computes the mass properties of a compound shape (combination of multiple shapes).

A compound shape is a collection of sub-shapes, each with its own position and orientation. This function computes the mass properties of each sub-shape, transforms them to their local positions, and combines them using the parallel axis theorem to get the total mass properties.

§Arguments
  • density - The material density applied to all sub-shapes
    • In 3D: kg/m³ (mass per unit volume)
    • In 2D: kg/m² (mass per unit area)
  • shapes - Array of (position, shape) pairs
    • Each shape has an Isometry (position + rotation)
    • Shapes can be any type implementing the Shape trait
§Returns

A MassProperties struct containing:

  • mass: Sum of all sub-shape masses
  • local_com: Combined center of mass (mass-weighted average)
  • inv_principal_inertia: Combined angular inertia
§Physics Background

The parallel axis theorem is used to shift inertia tensors:

  • Each shape’s mass properties are computed in its local frame
  • Properties are transformed to the compound’s coordinate system
  • Center of mass is the mass-weighted average of all sub-shapes
  • Angular inertia accounts for both local rotation and offset from COM
§Example (3D) - Dumbbell
use parry3d::mass_properties::MassProperties;
use parry3d::shape::{Ball, SharedShape};
use nalgebra::{Isometry3, Vector3};

// Create a dumbbell: two balls connected by a bar
let ball = SharedShape::new(Ball::new(0.5));
let bar = SharedShape::new(parry3d::shape::Cuboid::new(Vector3::new(0.1, 1.0, 0.1)));

let shapes = vec![
    (Isometry3::translation(0.0, -1.0, 0.0), ball.clone()),  // Left ball
    (Isometry3::identity(), bar),                             // Center bar
    (Isometry3::translation(0.0, 1.0, 0.0), ball),            // Right ball
];

let density = 1000.0;
let dumbbell_props = MassProperties::from_compound(density, &shapes);

println!("Dumbbell mass: {:.2} kg", dumbbell_props.mass());
println!("Center of mass: {:?}", dumbbell_props.local_com);

// Dumbbell has high inertia around X and Z (hard to spin end-over-end)
// but low inertia around Y (easy to spin along the bar)
let inertia = dumbbell_props.principal_inertia();
println!("Inertia: X={:.3}, Y={:.3}, Z={:.3}", inertia.x, inertia.y, inertia.z);
§Example (2D) - Table
use parry2d::mass_properties::MassProperties;
use parry2d::shape::{Cuboid, SharedShape};
use nalgebra::{Isometry2, Vector2};

// Create a simple table: top surface + legs
let top = SharedShape::new(Cuboid::new(Vector2::new(2.0, 0.1)));    // Wide, thin top
let leg = SharedShape::new(Cuboid::new(Vector2::new(0.1, 0.5)));    // Narrow, tall leg

let shapes = vec![
    (Isometry2::translation(0.0, 0.6), top),                   // Table top
    (Isometry2::translation(-1.5, 0.0), leg.clone()),          // Left leg
    (Isometry2::translation(1.5, 0.0), leg),                   // Right leg
];

let density = 500.0; // Wood
let table_props = MassProperties::from_compound(density, &shapes);

println!("Table mass: {:.2} kg", table_props.mass());
§Example (3D) - Robot Arm
use parry3d::mass_properties::MassProperties;
use parry3d::shape::{Capsule, Cuboid, SharedShape};
use nalgebra::{Isometry3, Point3, Vector3};

// Simple robot arm with multiple segments
let base = SharedShape::new(Cuboid::new(Vector3::new(0.3, 0.2, 0.3)));
let upper_arm = SharedShape::new(Capsule::new(
    Point3::origin(),
    Point3::new(0.0, 1.0, 0.0),
    0.1
));
let forearm = SharedShape::new(Capsule::new(
    Point3::origin(),
    Point3::new(0.0, 0.8, 0.0),
    0.08
));

let shapes = vec![
    (Isometry3::identity(), base),
    (Isometry3::translation(0.0, 0.2, 0.0), upper_arm),
    (Isometry3::translation(0.0, 1.2, 0.0), forearm),
];

let density = 2700.0; // Aluminum
let arm_props = MassProperties::from_compound(density, &shapes);

println!("Robot arm mass: {:.2} kg", arm_props.mass());
println!("Arm center of mass: {:?}", arm_props.local_com);
§Use Cases
  • Complex objects: Multi-part objects (tables, chairs, vehicles)
  • Articulated bodies: Robot arms, character skeletons
  • Assemblies: Combining simple shapes into complex forms
  • Non-convex shapes: Convex decomposition results
  • Hierarchical structures: Nested compound shapes
§Different Densities

To use different densities for different parts:

// Compute each part separately with its own density
let heavy_part = ball_shape.mass_properties(5000.0).transform_by(&pos1);
let light_part = cuboid_shape.mass_properties(100.0).transform_by(&pos2);

// Combine manually
let total = heavy_part + light_part;
§Performance Note

The computation time is O(n) where n is the number of sub-shapes. Each shape’s mass properties are computed once and then combined. This is efficient even for large numbers of shapes.

§See Also
  • MassProperties::transform_by(): Transform mass properties to a new frame
  • Add trait: Combine mass properties with + operator
  • Sum trait: Sum an iterator of mass properties
Source§

impl MassProperties

Source

pub fn from_cone(density: f32, half_height: f32, radius: f32) -> Self

Computes the mass properties of a cone (3D only).

A cone is a 3D shape with a circular base and a point (apex) at the top, aligned along the Y-axis. The base is at y = -half_height, the apex is at y = +half_height, and the center of the base is at the origin.

§Arguments
  • density - The material density in kg/m³ (mass per unit volume)
  • half_height - Half the total height of the cone (center to apex/base)
  • radius - The radius of the circular base
§Returns

A MassProperties struct containing:

  • mass: Total mass calculated from volume and density
  • local_com: Center of mass at (0, -half_height/2, 0) - shifted toward the base
  • inv_principal_inertia: Inverse angular inertia (varies by axis)
  • principal_inertia_local_frame: Identity rotation (aligned with Y-axis)
§Physics Background

Cones have unique mass distribution due to tapering shape:

  • Volume = (1/3) × π × radius² × height
  • Center of mass is NOT at the geometric center
  • Center of mass is located 1/4 of the height from the base (toward the base)
  • The wider base contains more mass than the narrow top
  • Angular inertia around Y-axis (spinning): I_y = (3/10) × mass × radius²
  • Angular inertia around X/Z axes: includes both base radius and height terms
§Example - Traffic Cone
use parry3d::mass_properties::MassProperties;
use nalgebra::Point3;

// Standard traffic cone: 70cm tall, 30cm base diameter
// Made of flexible plastic, density ~950 kg/m³
let half_height = 0.35; // 70cm / 2 = 35cm
let radius = 0.15;      // 30cm / 2 = 15cm
let density = 950.0;

let cone_props = MassProperties::from_cone(density, half_height, radius);

let mass = cone_props.mass();
println!("Traffic cone mass: {:.3} kg", mass); // About 1-2 kg

// Center of mass is shifted toward the base (negative Y)
let com_y = cone_props.local_com.y;
println!("Center of mass Y: {:.3} m", com_y);
assert!(com_y < 0.0, "COM should be below origin, toward the base");
assert!((com_y - (-half_height / 2.0)).abs() < 0.01);
§Example - Ice Cream Cone
use parry3d::mass_properties::MassProperties;

// Small ice cream cone (wafer): 12cm tall, 5cm diameter
let half_height = 0.06; // 6cm
let radius = 0.025;     // 2.5cm
let density = 400.0;    // Wafer is light and porous

let wafer_props = MassProperties::from_cone(density, half_height, radius);

// Volume = (1/3) × π × (0.025)² × 0.12 ≈ 0.0000785 m³
let mass = wafer_props.mass();
println!("Wafer mass: {:.1} grams", mass * 1000.0); // About 30 grams
§Example - Center of Mass Position
use parry3d::mass_properties::MassProperties;

// Demonstrate that COM is 1/4 height from base
let half_height = 2.0;
let radius = 1.0;
let density = 1000.0;

let cone_props = MassProperties::from_cone(density, half_height, radius);

// Base is at y = -2.0, apex is at y = +2.0
// COM should be at y = -2.0 + (4.0 / 4.0) = -1.0
// Or equivalently: y = -half_height / 2 = -1.0
let expected_com_y = -half_height / 2.0;
assert!((cone_props.local_com.y - expected_com_y).abs() < 0.001);
println!("Base at: {}", -half_height);
println!("Apex at: {}", half_height);
println!("COM at: {:.3}", cone_props.local_com.y);
§Example - Cone vs Cylinder Comparison
use parry3d::mass_properties::MassProperties;

let half_height = 1.0;
let radius = 0.5;
let density = 1000.0;

let cone = MassProperties::from_cone(density, half_height, radius);
let cylinder = MassProperties::from_cylinder(density, half_height, radius);

// Cone has 1/3 the volume of a cylinder with same dimensions
println!("Cone mass: {:.2} kg", cone.mass());
println!("Cylinder mass: {:.2} kg", cylinder.mass());
assert!((cylinder.mass() / cone.mass() - 3.0).abs() < 0.1);

// Cone's COM is offset, cylinder's is at origin
println!("Cone COM Y: {:.3}", cone.local_com.y);
println!("Cylinder COM Y: {:.3}", cylinder.local_com.y);
§Use Cases
  • Traffic cones: Road safety markers
  • Funnels: Pouring devices
  • Party hats: Conical decorations
  • Volcanic mountains: Natural cone-shaped terrain
  • Rocket noses: Aerodynamic cone shapes
  • Drills and bits: Conical tool tips
§Important Notes
  • Orientation: Cone points upward (+Y), base is downward (-Y)
  • Asymmetric COM: Unlike cylinder or ball, center of mass is NOT at origin
  • Volume: Remember it’s only 1/3 of an equivalent cylinder’s volume
  • Base position: The base center is at the origin, not the geometric center
§Common Mistakes
  • Expecting COM at origin: The center of mass is shifted toward the base by half_height/2 in the negative Y direction
  • Confusing orientation: The apex points in +Y direction, base faces -Y
  • Volume estimation: Cone volume is much smaller than you might expect (only 1/3 of a cylinder with the same dimensions)
§Performance Note

Cone collision detection is moderately expensive due to the tapered shape and curved surface. For simpler simulations, consider using a cylinder or compound shape approximation.

Source§

impl MassProperties

Source

pub fn from_convex_polyhedron( density: f32, vertices: &[Point<f32>], indices: &[[u32; 3]], ) -> MassProperties

Computes the mass properties of a convex polyhedron (3D) or polygon (2D).

A convex polyhedron is a 3D solid where all faces are flat and all vertices point outward. This is a convenience function that delegates to from_trimesh(), which handles the actual computation by treating the polyhedron as a triangle mesh.

§Arguments
  • density - The material density
    • In 3D: kg/m³ (mass per unit volume)
    • In 2D: kg/m² (mass per unit area)
  • vertices - Array of vertex positions defining the polyhedron
  • indices - Array of triangle indices
    • In 3D: Each element is [u32; 3] indexing into vertices array
    • In 2D: Each element is [u32; 2] for line segments
§Returns

A MassProperties struct containing:

  • mass: Total mass calculated from volume/area and density
  • local_com: Center of mass (volume-weighted centroid)
  • inv_principal_inertia: Inverse angular inertia tensor
§Example (3D) - Tetrahedron
use parry3d::mass_properties::MassProperties;
use nalgebra::Point3;

// Create a regular tetrahedron (4 vertices, 4 triangular faces)
let vertices = vec![
    Point3::new(1.0, 0.0, 0.0),
    Point3::new(0.0, 1.0, 0.0),
    Point3::new(0.0, 0.0, 1.0),
    Point3::origin(),
];

let indices = vec![
    [0, 1, 2], // Face 1
    [0, 1, 3], // Face 2
    [0, 2, 3], // Face 3
    [1, 2, 3], // Face 4
];

let density = 1000.0;
let tetra_props = MassProperties::from_convex_polyhedron(density, &vertices, &indices);

println!("Tetrahedron mass: {:.4} kg", tetra_props.mass());
println!("Center of mass: {:?}", tetra_props.local_com);
§Example (3D) - Octahedron
use parry3d::mass_properties::MassProperties;
use nalgebra::Point3;

// Regular octahedron (6 vertices, 8 triangular faces)
let vertices = vec![
    Point3::new(1.0, 0.0, 0.0),   // +X
    Point3::new(-1.0, 0.0, 0.0),  // -X
    Point3::new(0.0, 1.0, 0.0),   // +Y
    Point3::new(0.0, -1.0, 0.0),  // -Y
    Point3::new(0.0, 0.0, 1.0),   // +Z
    Point3::new(0.0, 0.0, -1.0),  // -Z
];

let indices = vec![
    [0, 2, 4], [0, 4, 3], [0, 3, 5], [0, 5, 2],  // Right hemisphere
    [1, 4, 2], [1, 3, 4], [1, 5, 3], [1, 2, 5],  // Left hemisphere
];

let density = 800.0;
let octa_props = MassProperties::from_convex_polyhedron(density, &vertices, &indices);

println!("Octahedron mass: {:.2} kg", octa_props.mass());
§Use Cases
  • Custom 3D shapes: Game objects with specific polyhedral geometry
  • Crystalline structures: Geometric solids (tetrahedra, octahedra, dodecahedra)
  • Simplified models: Convex approximations of complex shapes
  • Gems and jewels: Faceted objects
  • Dice: Polyhedral game dice (d4, d6, d8, d12, d20)
§Requirements
  • Must be convex: All faces must be flat and point outward
  • Closed mesh: Triangles must form a watertight volume
  • Consistent winding: Triangle vertices should follow consistent order (counter-clockwise when viewed from outside)
  • Valid indices: All index values must be < vertices.len()
§Convex vs Non-Convex

This function assumes the shape is convex. For non-convex (concave) meshes:

  • The result may be incorrect
  • Consider using from_compound() with a convex decomposition
  • Or use from_trimesh() directly (handles both convex and concave)
§Implementation Note

This function is a thin wrapper around from_trimesh(). Both produce identical results. Use from_convex_polyhedron() when you know the shape is convex to make intent clear in code.

§See Also
  • from_trimesh(): For general triangle meshes (convex or concave)
  • from_convex_polygon(): For 2D convex polygons
  • from_compound(): For combining multiple convex shapes
Source§

impl MassProperties

Source

pub fn from_cuboid(density: f32, half_extents: Vector<f32>) -> Self

Computes the mass properties of a cuboid (box in 3D, rectangle in 2D).

A cuboid is a box-shaped object with three dimensions (or two in 2D), where each dimension can have a different size. The cuboid is centered at the origin, and half_extents define the distance from the center to each face.

§Arguments
  • density - The material density (mass per unit volume/area). Higher values make heavier objects.
    • In 3D: units are typically kg/m³ (e.g., wood = 500-900, concrete = 2400)
    • In 2D: units are typically kg/m² (mass per unit area)
  • half_extents - Half the size along each axis (center to face distance).
    • In 3D: Vector3::new(hx, hy, hz) creates a box with dimensions 2hx × 2hy × 2hz
    • In 2D: Vector2::new(hx, hy) creates a rectangle with dimensions 2hx × 2hy
§Returns

A MassProperties struct containing:

  • mass: Total mass calculated from volume and density
  • local_com: Center of mass at the origin (cuboids are symmetric)
  • inv_principal_inertia: Inverse angular inertia along each axis
§Physics Background

Cuboids have axis-aligned mass distribution:

  • Center of mass is at the geometric center (origin)
  • Angular inertia varies per axis based on dimensions
  • Longer dimensions increase inertia around perpendicular axes
  • In 3D, each axis has different inertia: I_x depends on y and z extents, etc.
§Example (3D) - Wooden Crate
use parry3d::mass_properties::MassProperties;
use nalgebra::{Point3, Vector3};

// Create a wooden crate: 2m × 1m × 1m (half_extents = 1.0, 0.5, 0.5)
// Wood density: approximately 600 kg/m³
let half_extents = Vector3::new(1.0, 0.5, 0.5);
let density = 600.0;
let crate_props = MassProperties::from_cuboid(density, half_extents);

// Volume = (2 * 1.0) × (2 * 0.5) × (2 * 0.5) = 2 m³
// Mass = volume × density = 1200 kg
let mass = crate_props.mass();
assert!((mass - 1200.0).abs() < 0.1);

// Longer dimension (x-axis) means higher inertia around y and z axes
let inertia = crate_props.principal_inertia();
println!("Inertia around x-axis: {:.2}", inertia.x); // Lowest (easier to spin around length)
println!("Inertia around y-axis: {:.2}", inertia.y); // Higher
println!("Inertia around z-axis: {:.2}", inertia.z); // Higher

// Center of mass is at the origin
assert_eq!(crate_props.local_com, Point3::origin());
§Example (3D) - Cube
use parry3d::mass_properties::MassProperties;
use nalgebra::Vector3;

// Create a 1m × 1m × 1m cube (half_extents = 0.5 on all axes)
let half_extents = Vector3::new(0.5, 0.5, 0.5);
let density = 1000.0; // Water density
let cube_props = MassProperties::from_cuboid(density, half_extents);

// Volume = 1 m³, Mass = 1000 kg
assert!((cube_props.mass() - 1000.0).abs() < 0.1);

// For a cube, all axes have equal inertia (symmetric)
let inertia = cube_props.principal_inertia();
assert!((inertia.x - inertia.y).abs() < 0.01);
assert!((inertia.y - inertia.z).abs() < 0.01);
§Example (2D) - Rectangular Platform
use parry2d::mass_properties::MassProperties;
use nalgebra::Vector2;

// Create a 4m × 2m rectangular platform (half_extents = 2.0, 1.0)
let half_extents = Vector2::new(2.0, 1.0);
let density = 500.0; // kg/m²
let platform_props = MassProperties::from_cuboid(density, half_extents);

// Area = (2 * 2.0) × (2 * 1.0) = 8 m²
// Mass = area × density = 4000 kg
let mass = platform_props.mass();
assert!((mass - 4000.0).abs() < 0.1);

println!("Platform mass: {:.2} kg", mass);
println!("Moment of inertia: {:.2}", platform_props.principal_inertia());
§Use Cases
  • Boxes and crates: Storage containers, shipping boxes
  • Building blocks: Walls, floors, platforms
  • Vehicles: Simplified car or truck bodies
  • Furniture: Tables, chairs, cabinets
  • Terrain: Rectangular ground segments
§Common Mistakes
  • Wrong dimensions: Remember that half_extents are HALF the total size. For a 2m × 2m × 2m box, use Vector3::new(1.0, 1.0, 1.0), not (2.0, 2.0, 2.0)
  • Unit confusion: Ensure density units match your distance units (kg/m³ with meters, kg/cm³ with centimeters, etc.)
§Performance Note

This is a very fast computation (constant time). Cuboids are the second simplest shape after balls and are highly efficient for collision detection.

Source§

impl MassProperties

Source

pub fn from_cylinder(density: f32, half_height: f32, radius: f32) -> Self

Computes the mass properties of a cylinder (3D only).

A cylinder is a 3D shape with circular cross-section and flat ends, aligned along the Y-axis and centered at the origin. Unlike a capsule, a cylinder has sharp edges at the top and bottom.

Note: In 2D, this function is used internally but cylinders don’t exist as a distinct 2D shape (rectangles are used instead).

§Arguments
  • density - The material density in kg/m³ (e.g., aluminum = 2700, plastic = 950)
  • half_height - Half the total height of the cylinder (center to top/bottom)
  • radius - The radius of the circular cross-section
§Returns

A MassProperties struct containing:

  • mass: Total mass calculated from volume and density
  • local_com: Center of mass at the origin (cylinders are symmetric)
  • inv_principal_inertia: Inverse angular inertia (different for each axis)
  • principal_inertia_local_frame: Identity rotation (aligned with Y-axis)
§Physics Background

Cylinders have rotational symmetry around the Y-axis:

  • Volume = π × radius² × height
  • Center of mass is at the geometric center (origin)
  • Angular inertia around Y-axis (spinning like a top): I_y = (1/2) × mass × radius²
  • Angular inertia around X/Z axes (tipping over): I_x = I_z = (1/12) × mass × (3×radius² + height²)
  • Easier to spin around the central axis than to tip over
§Example - Aluminum Can
use parry3d::mass_properties::MassProperties;
use nalgebra::Point3;

// Standard soda can: 12.3cm tall, 6.6cm diameter
// Aluminum density: ~2700 kg/m³
let half_height = 0.0615; // 6.15 cm in meters
let radius = 0.033;        // 3.3 cm in meters
let density = 2700.0;

let can_props = MassProperties::from_cylinder(density, half_height, radius);

let mass = can_props.mass();
println!("Can mass: {:.2} kg", mass); // Approximately 0.15 kg (150 grams)

// Center of mass at origin
assert_eq!(can_props.local_com, Point3::origin());

// Check inertia differences
let inertia = can_props.principal_inertia();
println!("Spin inertia (Y): {:.6}", inertia.y); // Low (easy to spin)
println!("Tip inertia (X): {:.6}", inertia.x);  // Higher (harder to tip)
assert!(inertia.y < inertia.x); // Easier to spin than tip
§Example - Concrete Column
use parry3d::mass_properties::MassProperties;

// Concrete support column: 3m tall, 0.5m diameter
// Concrete density: ~2400 kg/m³
let half_height = 1.5;  // 3m / 2
let radius = 0.25;      // 0.5m / 2
let density = 2400.0;

let column_props = MassProperties::from_cylinder(density, half_height, radius);

// Volume = π × (0.25)² × 3 = 0.589 m³
// Mass = 0.589 × 2400 = 1414 kg
let mass = column_props.mass();
assert!((mass - 1414.0).abs() < 10.0);

println!("Column mass: {:.0} kg", mass);
§Example - Comparing Cylinder vs Capsule
use parry3d::mass_properties::MassProperties;
use nalgebra::Point3;

let half_height = 1.0;
let radius = 0.5;
let density = 1000.0;

// Cylinder has flat ends (sharp edges)
let cylinder = MassProperties::from_cylinder(density, half_height, radius);

// Capsule has rounded ends (smooth)
let a = Point3::new(0.0, -half_height, 0.0);
let b = Point3::new(0.0, half_height, 0.0);
let capsule = MassProperties::from_capsule(density, a, b, radius);

// Capsule has more mass due to hemispherical caps
println!("Cylinder mass: {:.2} kg", cylinder.mass());
println!("Capsule mass: {:.2} kg", capsule.mass());
assert!(capsule.mass() > cylinder.mass());
§Use Cases
  • Structural elements: Columns, pillars, posts
  • Containers: Cans, drums, barrels, tanks
  • Mechanical parts: Shafts, pistons, rollers
  • Tree trunks: Natural cylindrical objects
  • Wheels: When viewed from the side (use with proper orientation)
§Cylinder vs Capsule

Use Cylinder when:

  • Sharp edges are acceptable or desired
  • Object is truly flat-ended (cans, pipes)
  • Static/kinematic objects (don’t need smooth rolling)

Use Capsule when:

  • Smooth collision response is needed
  • Object needs to roll or slide smoothly
  • Character controllers or dynamic objects
§Common Mistakes
  • Wrong axis: Cylinders are aligned with Y-axis by default. Use transform_by() or create with proper orientation if you need X or Z alignment.
  • Half height confusion: Total height is 2 × half_height, not just half_height
§Performance Note

Cylinder collision detection is more expensive than capsules due to sharp edges, but still reasonably efficient. For dynamic objects, prefer capsules.

Source§

impl MassProperties

Source

pub fn from_trimesh( density: f32, vertices: &[Point<f32>], indices: &[[u32; 3]], ) -> MassProperties

Computes the mass properties of a triangle mesh.

Source§

impl MassProperties

Source

pub fn from_voxels(density: f32, voxels: &Voxels) -> Self

Computes the mass properties of a voxel grid.

Voxels (volumetric pixels) represent a 3D shape as a grid of small cubes. This function treats each non-empty voxel as a small cuboid and combines their mass properties. It’s useful for volumetric data, destructible terrain, or shapes that are difficult to represent with traditional geometry.

§Arguments
  • density - The material density
    • In 3D: kg/m³ (mass per unit volume)
    • In 2D: kg/m² (mass per unit area)
  • voxels - A Voxels structure containing the voxel grid
    • Each voxel is a small cube/square of uniform size
    • Voxels can be empty or filled
    • Since v0.25.0, uses sparse storage internally for efficiency
§Returns

A MassProperties struct containing:

  • mass: Total mass of all non-empty voxels
  • local_com: Center of mass (weighted average of voxel centers)
  • inv_principal_inertia: Combined angular inertia
§Physics Background

The algorithm:

  1. Compute mass properties of a single voxel (small cuboid)
  2. For each non-empty voxel, shift its mass properties to its position
  3. Sum all contributions using parallel axis theorem
  4. Empty voxels contribute nothing (zero mass)
§Example (3D) - Simple Voxel Object
use parry3d::mass_properties::MassProperties;
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};

// Create a 3×3×3 voxel grid with 1m voxels
let voxel_size = Vector3::new(1.0, 1.0, 1.0);

// Fill some voxels to create an L-shape
let voxels = &[
    Point3::new(0, 0, 0), // Bottom bar
    Point3::new(1, 0, 0),
    Point3::new(2, 0, 0),
    Point3::new(0, 1, 0), // Vertical part
    Point3::new(0, 2, 0),
];
let voxels = Voxels::new(voxel_size, voxels);

let density = 1000.0; // Water density
let voxel_props = MassProperties::from_voxels(density, &voxels);

// 5 voxels × 1m³ each × 1000 kg/m³ = 5000 kg
println!("Voxel object mass: {:.2} kg", voxel_props.mass());
println!("Center of mass: {:?}", voxel_props.local_com);
§Example (3D) - Destructible Terrain
use parry3d::mass_properties::MassProperties;
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};

// Create a chunk of destructible terrain
let voxel_size = Vector3::new(0.5, 0.5, 0.5); // 50cm voxels
let mut voxels = vec![];

// Fill a 4×4×4 solid block
for x in 0..4 {
    for y in 0..4 {
        for z in 0..4 {
            voxels.push(Point3::new(x, y, z));
        }
    }
}

let mut terrain = Voxels::new(voxel_size, &voxels);

let density = 2400.0; // Concrete
let terrain_props = MassProperties::from_voxels(density, &terrain);

println!("Terrain chunk mass: {:.2} kg", terrain_props.mass());
§Example - Sparse Voxel Grid (Efficient)
use parry3d::mass_properties::MassProperties;
use parry3d::shape::Voxels;
use nalgebra::{Point3, Vector3};

// Large sparse grid (only stores filled voxels since v0.25.0)
let voxel_size = Vector3::new(0.1, 0.1, 0.1);

// Scatter some voxels in a large space (efficient with sparse storage)
let voxels = &[
    Point3::new(0, 0, 0),
    Point3::new(100, 50, 75),
    Point3::new(-50, 200, -30),
];
let voxels = Voxels::new(voxel_size, voxels);
let density = 1000.0;
let props = MassProperties::from_voxels(density, &voxels);

// Only 3 voxels contribute to mass
println!("Sparse voxel mass: {:.4} kg", props.mass());
§Use Cases
  • Destructible terrain: Voxel-based environments (Minecraft-style)
  • Medical imaging: CT scans, MRI data volumetric analysis
  • Procedural generation: Voxel-based world generation
  • Simulation: Granular materials, fluids represented as voxels
  • Dynamic shapes: Objects that change shape at runtime
  • Complex geometry: Shapes difficult to represent with meshes
§Performance Considerations
  • Sparse storage (v0.25.0+): Only filled voxels consume memory
  • Computation time: O(n) where n = number of filled voxels
  • For large grids: Prefer coarser voxel sizes when possible
  • Memory usage: Each voxel stores position and state
  • Alternative: For static shapes, consider using triangle meshes
§Voxel Size Trade-offs

Smaller voxels:

  • More accurate representation of curved surfaces
  • More voxels = longer computation time
  • Higher memory usage (more voxels to store)

Larger voxels:

  • Faster computation
  • Less memory
  • Blockier appearance (lower resolution)
§Accuracy Notes
  • Voxel representation is an approximation of the true shape
  • Smooth curves become staircase patterns
  • Mass properties accuracy depends on voxel resolution
  • For exact results with smooth shapes, use primitive shapes or meshes
§Empty vs Filled Voxels
  • Only non-empty voxels contribute to mass
  • Empty voxels are ignored (zero mass, no inertia)
  • The voxel state is checked using vox.state.is_empty()
§See Also
  • Voxels::new(): Create a new voxel grid
  • Voxels::set_voxel(): Add or remove voxels
  • from_trimesh(): Alternative for precise shapes
  • from_compound(): Combine multiple shapes efficiently

Trait Implementations§

Source§

impl AbsDiffEq for MassProperties

Source§

type Epsilon = f32

Used for specifying relative comparisons.
Source§

fn default_epsilon() -> Self::Epsilon

The default tolerance to use when testing values that are close together. Read more
Source§

fn abs_diff_eq(&self, other: &Self, epsilon: Self::Epsilon) -> bool

A test for equality that uses the absolute difference to compute the approximate equality of two numbers.
Source§

fn abs_diff_ne(&self, other: &Rhs, epsilon: Self::Epsilon) -> bool

The inverse of AbsDiffEq::abs_diff_eq.
Source§

impl Add for MassProperties

Source§

type Output = MassProperties

The resulting type after applying the + operator.
Source§

fn add(self, other: MassProperties) -> Self

Performs the + operation. Read more
Source§

impl AddAssign for MassProperties

Source§

fn add_assign(&mut self, rhs: MassProperties)

Performs the += operation. Read more
Source§

impl Clone for MassProperties

Source§

fn clone(&self) -> MassProperties

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for MassProperties

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Default for MassProperties

Source§

fn default() -> MassProperties

Returns the “default value” for a type. Read more
Source§

impl PartialEq for MassProperties

Source§

fn eq(&self, other: &MassProperties) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl RelativeEq for MassProperties

Source§

fn default_max_relative() -> Self::Epsilon

The default relative tolerance for testing values that are far-apart. Read more
Source§

fn relative_eq( &self, other: &Self, epsilon: Self::Epsilon, max_relative: Self::Epsilon, ) -> bool

A test for equality that uses a relative comparison if the values are far apart.
Source§

fn relative_ne( &self, other: &Rhs, epsilon: Self::Epsilon, max_relative: Self::Epsilon, ) -> bool

The inverse of RelativeEq::relative_eq.
Source§

impl Sub for MassProperties

Source§

type Output = MassProperties

The resulting type after applying the - operator.
Source§

fn sub(self, other: MassProperties) -> Self

Performs the - operation. Read more
Source§

impl SubAssign for MassProperties

Source§

fn sub_assign(&mut self, rhs: MassProperties)

Performs the -= operation. Read more
Source§

impl Sum for MassProperties

Source§

fn sum<I>(iter: I) -> Self
where I: Iterator<Item = Self>,

Takes an iterator and generates Self from the elements by “summing up” the items.
Source§

impl Zero for MassProperties

Source§

fn zero() -> Self

Returns the additive identity element of Self, 0. Read more
Source§

fn is_zero(&self) -> bool

Returns true if self is equal to the additive identity.
Source§

fn set_zero(&mut self)

Sets self to the additive identity element of Self, 0.
Source§

impl Copy for MassProperties

Source§

impl StructuralPartialEq for MassProperties

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> Downcast for T
where T: Any,

Source§

fn into_any(self: Box<T>) -> Box<dyn Any>

Converts 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>

Converts 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)

Converts &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)

Converts &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
where T: Any + Send,

Source§

fn into_any_send(self: Box<T>) -> Box<dyn Any + Send>

Converts Box<Trait> (where Trait: DowncastSend) to Box<dyn Any + Send>, which can then be downcast into Box<ConcreteType> where ConcreteType implements Trait.
Source§

impl<T> DowncastSync for T
where T: Any + Send + Sync,

Source§

fn into_any_sync(self: Box<T>) -> Box<dyn Any + Sync + Send>

Converts Box<Trait> (where Trait: DowncastSync) to Box<dyn Any + Send + Sync>, which can then be downcast into Box<ConcreteType> where ConcreteType implements Trait.
Source§

fn into_any_arc(self: Arc<T>) -> Arc<dyn Any + Sync + Send>

Converts Arc<Trait> (where Trait: DowncastSync) to Arc<Any>, which can then be downcast into Arc<ConcreteType> where ConcreteType implements Trait.
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> IntoEither for T

Source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts 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 more
Source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts 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 more
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<T, Right> ClosedAdd<Right> for T
where T: Add<Right, Output = T> + AddAssign<Right>,

Source§

impl<T, Right> ClosedAddAssign<Right> for T
where T: ClosedAdd<Right> + AddAssign<Right>,

Source§

impl<T, Right> ClosedSub<Right> for T
where T: Sub<Right, Output = T> + SubAssign<Right>,

Source§

impl<T, Right> ClosedSubAssign<Right> for T
where T: ClosedSub<Right> + SubAssign<Right>,

Source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,