yapcad.kinematics package
Submodules
yapcad.kinematics.chain module
Kinematic chain (tree of parts) with world transform computation.
Copyright (c) 2026 yapCAD contributors License: MIT
- class yapcad.kinematics.chain.KinematicChain(name: str = 'assembly')[source]
Bases:
objectTree of kinematic parts with world transform computation.
A KinematicChain manages a hierarchy of parts connected by joints. It provides efficient world transform computation with caching and supports JSON import/export.
The chain has a virtual root node called GLOBAL_DATUM at the world origin. All root parts (parent=None) are implicitly attached to GLOBAL_DATUM.
- name
Name of this kinematic chain/assembly
- parts
Dict mapping part names to KinematicPart objects
- DATUM_NAME
Name of the virtual root node (“GLOBAL_DATUM”)
Example:
chain = KinematicChain("robot_arm") # Add parts chain.add_part(KinematicPart(name="BASE")) chain.add_part(KinematicPart( name="LINK1", parent="BASE", joint=Joint("j1", JointType.REVOLUTE), )) # Set joint values chain.set_joint_value("LINK1", 45.0) # Get world transforms world_tf = chain.get_world_transform("LINK1") # Export to JSON chain.export_json("positions.json")
- DATUM_NAME = 'GLOBAL_DATUM'
- add_part(part: KinematicPart) KinematicPart[source]
Add a part to the kinematic chain.
- Parameters:
part – Part to add
- Returns:
The added part (for chaining)
- Raises:
ValueError – If part name already exists or parent not found
Parts with parent=None are attached to GLOBAL_DATUM.
- export_json(filepath: str, include_world_transforms: bool = True) None[source]
Export chain to JSON file.
- Parameters:
filepath – Output file path
include_world_transforms – If True, include computed world transforms
- classmethod from_dict(data: dict) KinematicChain[source]
Create chain from dictionary.
- Parameters:
data – Dictionary with chain data
- Returns:
New KinematicChain
- classmethod from_json(filepath: str) KinematicChain[source]
Load chain from JSON file.
- Parameters:
filepath – Input file path
- Returns:
Loaded KinematicChain
- get_all_descendants(part_name: str) List[str][source]
Get all descendants of a part (recursive).
- Parameters:
part_name – Root part
- Returns:
List of all descendant part names
- get_all_world_transforms() Dict[str, Transform][source]
Compute world transforms for all parts.
- Returns:
Dict mapping part names to world transforms
- get_chain_to_root(part_name: str) List[str][source]
Get ancestor chain from part to root.
- Parameters:
part_name – Starting part
- Returns:
List of part names [part, parent, grandparent, …, GLOBAL_DATUM]
- get_children(part_name: str) List[str][source]
Get direct children of a part.
- Parameters:
part_name – Parent part name
- Returns:
List of child part names
- get_joint_value(part_name: str) float[source]
Get current joint value for a part.
- Parameters:
part_name – Part to query
- Returns:
Current joint value
- get_relative_transform(from_part: str, to_part: str, from_frame: str = 'ORIGIN', to_frame: str = 'ORIGIN') Transform[source]
Compute transform from one part/frame to another.
- Parameters:
from_part – Source part name
to_part – Target part name
from_frame – Frame on source part
to_frame – Frame on target part
- Returns:
Transform from source to target
- get_world_transform(part_name: str, frame_name: str = 'ORIGIN') Transform[source]
Compute world transform for a part frame.
- Parameters:
part_name – Part to get transform for
frame_name – Frame on the part (default “ORIGIN”)
- Returns:
World transform (from global origin to part frame)
This method uses caching for efficiency. Transform is recomputed only when a joint value changes in the ancestor chain.
- set_joint_value(part_name: str, value: float, clamp: bool = True) None[source]
Set joint value for a part and invalidate descendant caches.
- Parameters:
part_name – Part whose joint to modify
value – New joint value (degrees for revolute, mm for prismatic)
clamp – If True, clamp to joint limits
yapcad.kinematics.frame module
Coordinate frames for kinematic parts.
Copyright (c) 2026 yapCAD contributors License: MIT
- class yapcad.kinematics.frame.CoordinateFrame(name: str, transform: Transform | None = None, datum_source: str | None = None, datum_name: str | None = None, description: str = '', _cached_transform: Transform | None = None, _cache_valid: bool = False)[source]
Bases:
objectNamed reference frame on a kinematic part.
A coordinate frame defines a local coordinate system on a part that can be used for attaching child parts or defining features.
- Frames can be defined via:
Explicit transform (transform field)
External datum lookup (datum_source + datum_name)
- transform
Explicit transform from part origin to frame
- Type:
Example:
# Explicit frame mount = CoordinateFrame( name="SERVO_MOUNT", transform=Transform.from_translation(0, 0, 50), description="Servo mounting face" ) # Frame from external datum (lazy lookup) from_datum = CoordinateFrame( name="HORN_FACE", datum_source="cots/servo.json", datum_name="output_shaft", )
- classmethod from_dict(data: dict) CoordinateFrame[source]
Create frame from dictionary.
- get_transform() Transform[source]
Get frame transform (with caching for external lookups).
- Returns:
Transform from part origin to this frame
If transform is set explicitly, returns it directly. If datum_source/datum_name are set, attempts external lookup. Falls back to identity transform if lookup fails.
yapcad.kinematics.joint module
Joint types and Joint class for kinematic connections.
Copyright (c) 2026 yapCAD contributors License: MIT
- class yapcad.kinematics.joint.Joint(name: str, joint_type: JointType = JointType.FIXED, base_transform: Transform = <factory>, axis: Tuple[float, float, float]=(0.0, 0.0, 1.0), value: float = 0.0, min_limit: float = -180.0, max_limit: float = 180.0)[source]
Bases:
objectConnection between kinematic parts.
A joint defines how a child part connects to its parent part, including the base transform (fixed offset) and any articulated motion (rotation or translation along an axis).
- joint_type
Type of joint (FIXED, REVOLUTE, etc.)
- base_transform
Fixed transform from parent frame to joint origin
Example:
# Fixed joint (no motion) fixed = Joint("mount", JointType.FIXED) # Revolute joint about Z axis revolute = Joint( name="shoulder", joint_type=JointType.REVOLUTE, axis=(0, 0, 1), min_limit=-90, max_limit=90, ) revolute.value = 45.0 # Set current angle # Get total transform tf = revolute.get_transform() # base_transform @ rotation(45°)
- clamp_value(value: float) float[source]
Clamp value to joint limits.
- Parameters:
value – Unclamped joint value
- Returns:
Value clamped to [min_limit, max_limit]
- get_transform() Transform[source]
Compute total joint transform (base + motion).
- Returns:
Transform from parent frame to child origin
For FIXED joints, returns just the base_transform. For REVOLUTE joints, adds rotation about axis. For PRISMATIC joints, adds translation along axis.
- class yapcad.kinematics.joint.JointType(*values)[source]
Bases:
EnumTypes of kinematic joints.
- FIXED
No relative motion (rigid attachment)
- REVOLUTE
Rotation about single axis
- PRISMATIC
Translation along single axis
- CYLINDRICAL
Rotation + translation about same axis
- SPHERICAL
Ball joint (3 rotational DOF)
- CYLINDRICAL = 'cylindrical'
- FIXED = 'fixed'
- PRISMATIC = 'prismatic'
- REVOLUTE = 'revolute'
- SPHERICAL = 'spherical'
yapcad.kinematics.part module
Kinematic part (tree node) for kinematic chains.
Copyright (c) 2026 yapCAD contributors License: MIT
- class yapcad.kinematics.part.KinematicPart(name: str, parent: str | None = None, parent_frame: str = 'ORIGIN', joint: Joint = <factory>, frames: Dict[str, ~yapcad.kinematics.frame.CoordinateFrame]=<factory>, stl_path: str | None = None, is_printable: bool = True, material: str = 'PETG', color: Tuple[float, float, float]=(0.5, 0.5, 0.5), description: str = '', _world_transform: Transform | None = None, _transform_dirty: bool = True)[source]
Bases:
objectNode in a kinematic tree.
A KinematicPart represents a rigid body in an articulated assembly. It connects to a parent part via a joint and can have multiple named coordinate frames for attaching children or defining features.
- joint
Joint connecting to parent
- frames
Dict of named coordinate frames on this part
- Type:
Example:
# Create a part with frames link = KinematicPart( name="LINK1", parent="BASE", parent_frame="MOUNT", joint=Joint("joint1", JointType.REVOLUTE), ) # Add frames for child attachments link.add_frame( "END_EFFECTOR", Transform.from_translation(100, 0, 0), "Tool attachment point" )
- add_frame(name: str, transform: Transform, description: str = '') CoordinateFrame[source]
Add a coordinate frame to this part.
- Parameters:
name – Unique frame name
transform – Transform from part origin to frame
description – Human-readable description
- Returns:
The created frame
- frames: Dict[str, CoordinateFrame]
- classmethod from_dict(data: dict) KinematicPart[source]
Create part from dictionary.
- get_frame(name: str) CoordinateFrame | None[source]
Get a coordinate frame by name.
- Parameters:
name – Frame name
- Returns:
CoordinateFrame or None if not found
yapcad.kinematics.transform module
4x4 Homogeneous Transformation Matrix.
This module provides the Transform class for representing rigid body transformations in 3D space using 4x4 homogeneous matrices.
Copyright (c) 2026 yapCAD contributors License: MIT
- class yapcad.kinematics.transform.Transform(matrix: ndarray = <factory>)[source]
Bases:
object4x4 homogeneous transformation matrix.
Represents a rigid body transformation (rotation + translation) in 3D space. The matrix format is:
[R11 R12 R13 Tx] [R21 R22 R23 Ty] [R31 R32 R33 Tz] [0 0 0 1 ]
Where the upper-left 3x3 is the rotation matrix and the right column (top 3 elements) is the translation vector.
Transforms can be composed via matrix multiplication using the @ operator:
world_T_tool = world_T_base @ base_T_link @ link_T_tool
- matrix
4x4 numpy array representing the transform
- Type:
Example:
# Create transforms t1 = Transform.from_translation(10, 0, 0) t2 = Transform.from_rotation_z(45) # degrees # Compose (t2 applied after t1) t3 = t1 @ t2 # Get components pos = t3.translation # (x, y, z) R = t3.rotation_matrix # 3x3
- classmethod from_axis_angle(axis: Tuple[float, float, float], angle_deg: float) Transform[source]
Create rotation from axis-angle representation.
Uses Rodrigues’ rotation formula.
- Parameters:
axis – Unit rotation axis (x, y, z)
angle_deg – Rotation angle in degrees
- Returns:
Transform with specified rotation
- classmethod from_dict(data: dict) Transform[source]
Create transform from dictionary.
- Parameters:
data – Dict with ‘matrix’ key (4x4 list)
- Returns:
Transform from matrix
- classmethod from_euler_xyz(rx_deg: float, ry_deg: float, rz_deg: float) Transform[source]
Create rotation from Euler angles (intrinsic XYZ order).
- Parameters:
rx_deg – Rotation about X axis in degrees
ry_deg – Rotation about Y axis in degrees
rz_deg – Rotation about Z axis in degrees
- Returns:
Transform with combined rotation
- classmethod from_matrix(matrix: Any) Transform[source]
Create transform from 4x4 matrix (numpy array or nested list).
- Parameters:
matrix – 4x4 array-like
- Returns:
Transform wrapping the matrix
- classmethod from_position_rpy(x: float, y: float, z: float, roll_deg: float, pitch_deg: float, yaw_deg: float) Transform[source]
Create transform from position and roll-pitch-yaw angles.
- Parameters:
x – X position
y – Y position
z – Z position
roll_deg – Roll angle (rotation about X) in degrees
pitch_deg – Pitch angle (rotation about Y) in degrees
yaw_deg – Yaw angle (rotation about Z) in degrees
- Returns:
Combined transform
- classmethod from_rotation_x(angle_deg: float) Transform[source]
Create rotation about X axis.
- Parameters:
angle_deg – Rotation angle in degrees
- Returns:
Transform with rotation about X
- classmethod from_rotation_y(angle_deg: float) Transform[source]
Create rotation about Y axis.
- Parameters:
angle_deg – Rotation angle in degrees
- Returns:
Transform with rotation about Y
- classmethod from_rotation_z(angle_deg: float) Transform[source]
Create rotation about Z axis.
- Parameters:
angle_deg – Rotation angle in degrees
- Returns:
Transform with rotation about Z
- classmethod from_translation(x: float, y: float, z: float) Transform[source]
Create translation-only transform.
- Parameters:
x – Translation along X axis
y – Translation along Y axis
z – Translation along Z axis
- Returns:
Transform with specified translation
- inverse() Transform[source]
Compute inverse transform.
- Returns:
Transform T^-1 such that T @ T^-1 = I
For rigid transforms, this is computed efficiently as:
R^T | -R^T * t ----+---------- 0 | 1
- to_dict() dict[source]
Convert to dictionary for JSON serialization.
- Returns:
Dict with translation, rotation_xyz, and matrix
- to_euler_xyz() Tuple[float, float, float][source]
Extract Euler angles (intrinsic XYZ order) in degrees.
- Returns:
(rx, ry, rz) rotation angles in degrees
Note: May have gimbal lock issues when pitch is near ±90°.
- transform_point(point: Tuple[float, float, float]) Tuple[float, float, float][source]
Transform a point (applies rotation + translation).
- Parameters:
point – Point as (x, y, z)
- Returns:
Transformed point as (x, y, z)
Module contents
Kinematic Chain System for Multi-Body Assemblies.
OVERVIEW
This package provides a complete kinematic tree system for representing articulated assemblies with joints, frames, and transforms. It forms the foundation for computing world positions of parts in multi-body mechatronic assemblies.
- Key Concepts:
Transform: 4x4 homogeneous matrix for 6DOF positioning
Joint: Connection between parts (fixed, revolute, prismatic, etc.)
CoordinateFrame: Named reference frame on a part
KinematicPart: Tree node with parent, frames, and joint
KinematicChain: Tree container with world transform computation
Quick Start:
from yapcad.kinematics import (
KinematicChain, KinematicPart, Joint, JointType, Transform
)
# Create a kinematic chain
chain = KinematicChain("my_robot")
# Add base part (attached to world origin)
base = KinematicPart(
name="BASE",
parent=None,
joint=Joint("base_joint", JointType.FIXED),
)
chain.add_part(base)
# Add link with revolute joint
link = KinematicPart(
name="LINK1",
parent="BASE",
parent_frame="MOUNT",
joint=Joint("joint1", JointType.REVOLUTE, axis=(0, 0, 1)),
)
chain.add_part(link)
# Set joint angle and get world transform
chain.set_joint_value("LINK1", 45.0) # degrees
world_tf = chain.get_world_transform("LINK1")
# Export to JSON
chain.export_json("positions.json")
Kinematic chain system contributed by Jeremy Mika.
Copyright (c) 2026 yapCAD contributors License: MIT
- class yapcad.kinematics.CoordinateFrame(name: str, transform: Transform | None = None, datum_source: str | None = None, datum_name: str | None = None, description: str = '', _cached_transform: Transform | None = None, _cache_valid: bool = False)[source]
Bases:
objectNamed reference frame on a kinematic part.
A coordinate frame defines a local coordinate system on a part that can be used for attaching child parts or defining features.
- Frames can be defined via:
Explicit transform (transform field)
External datum lookup (datum_source + datum_name)
- transform
Explicit transform from part origin to frame
- Type:
Example:
# Explicit frame mount = CoordinateFrame( name="SERVO_MOUNT", transform=Transform.from_translation(0, 0, 50), description="Servo mounting face" ) # Frame from external datum (lazy lookup) from_datum = CoordinateFrame( name="HORN_FACE", datum_source="cots/servo.json", datum_name="output_shaft", )
- classmethod from_dict(data: dict) CoordinateFrame[source]
Create frame from dictionary.
- get_transform() Transform[source]
Get frame transform (with caching for external lookups).
- Returns:
Transform from part origin to this frame
If transform is set explicitly, returns it directly. If datum_source/datum_name are set, attempts external lookup. Falls back to identity transform if lookup fails.
- class yapcad.kinematics.Joint(name: str, joint_type: JointType = JointType.FIXED, base_transform: Transform = <factory>, axis: Tuple[float, float, float]=(0.0, 0.0, 1.0), value: float = 0.0, min_limit: float = -180.0, max_limit: float = 180.0)[source]
Bases:
objectConnection between kinematic parts.
A joint defines how a child part connects to its parent part, including the base transform (fixed offset) and any articulated motion (rotation or translation along an axis).
- joint_type
Type of joint (FIXED, REVOLUTE, etc.)
- base_transform
Fixed transform from parent frame to joint origin
Example:
# Fixed joint (no motion) fixed = Joint("mount", JointType.FIXED) # Revolute joint about Z axis revolute = Joint( name="shoulder", joint_type=JointType.REVOLUTE, axis=(0, 0, 1), min_limit=-90, max_limit=90, ) revolute.value = 45.0 # Set current angle # Get total transform tf = revolute.get_transform() # base_transform @ rotation(45°)
- clamp_value(value: float) float[source]
Clamp value to joint limits.
- Parameters:
value – Unclamped joint value
- Returns:
Value clamped to [min_limit, max_limit]
- get_transform() Transform[source]
Compute total joint transform (base + motion).
- Returns:
Transform from parent frame to child origin
For FIXED joints, returns just the base_transform. For REVOLUTE joints, adds rotation about axis. For PRISMATIC joints, adds translation along axis.
- class yapcad.kinematics.JointType(*values)[source]
Bases:
EnumTypes of kinematic joints.
- FIXED
No relative motion (rigid attachment)
- REVOLUTE
Rotation about single axis
- PRISMATIC
Translation along single axis
- CYLINDRICAL
Rotation + translation about same axis
- SPHERICAL
Ball joint (3 rotational DOF)
- CYLINDRICAL = 'cylindrical'
- FIXED = 'fixed'
- PRISMATIC = 'prismatic'
- REVOLUTE = 'revolute'
- SPHERICAL = 'spherical'
- class yapcad.kinematics.KinematicChain(name: str = 'assembly')[source]
Bases:
objectTree of kinematic parts with world transform computation.
A KinematicChain manages a hierarchy of parts connected by joints. It provides efficient world transform computation with caching and supports JSON import/export.
The chain has a virtual root node called GLOBAL_DATUM at the world origin. All root parts (parent=None) are implicitly attached to GLOBAL_DATUM.
- name
Name of this kinematic chain/assembly
- parts
Dict mapping part names to KinematicPart objects
- Type:
- DATUM_NAME
Name of the virtual root node (“GLOBAL_DATUM”)
Example:
chain = KinematicChain("robot_arm") # Add parts chain.add_part(KinematicPart(name="BASE")) chain.add_part(KinematicPart( name="LINK1", parent="BASE", joint=Joint("j1", JointType.REVOLUTE), )) # Set joint values chain.set_joint_value("LINK1", 45.0) # Get world transforms world_tf = chain.get_world_transform("LINK1") # Export to JSON chain.export_json("positions.json")
- DATUM_NAME = 'GLOBAL_DATUM'
- add_part(part: KinematicPart) KinematicPart[source]
Add a part to the kinematic chain.
- Parameters:
part – Part to add
- Returns:
The added part (for chaining)
- Raises:
ValueError – If part name already exists or parent not found
Parts with parent=None are attached to GLOBAL_DATUM.
- export_json(filepath: str, include_world_transforms: bool = True) None[source]
Export chain to JSON file.
- Parameters:
filepath – Output file path
include_world_transforms – If True, include computed world transforms
- classmethod from_dict(data: dict) KinematicChain[source]
Create chain from dictionary.
- Parameters:
data – Dictionary with chain data
- Returns:
New KinematicChain
- classmethod from_json(filepath: str) KinematicChain[source]
Load chain from JSON file.
- Parameters:
filepath – Input file path
- Returns:
Loaded KinematicChain
- get_all_descendants(part_name: str) List[str][source]
Get all descendants of a part (recursive).
- Parameters:
part_name – Root part
- Returns:
List of all descendant part names
- get_all_world_transforms() Dict[str, Transform][source]
Compute world transforms for all parts.
- Returns:
Dict mapping part names to world transforms
- get_chain_to_root(part_name: str) List[str][source]
Get ancestor chain from part to root.
- Parameters:
part_name – Starting part
- Returns:
List of part names [part, parent, grandparent, …, GLOBAL_DATUM]
- get_children(part_name: str) List[str][source]
Get direct children of a part.
- Parameters:
part_name – Parent part name
- Returns:
List of child part names
- get_joint_value(part_name: str) float[source]
Get current joint value for a part.
- Parameters:
part_name – Part to query
- Returns:
Current joint value
- get_relative_transform(from_part: str, to_part: str, from_frame: str = 'ORIGIN', to_frame: str = 'ORIGIN') Transform[source]
Compute transform from one part/frame to another.
- Parameters:
from_part – Source part name
to_part – Target part name
from_frame – Frame on source part
to_frame – Frame on target part
- Returns:
Transform from source to target
- get_world_transform(part_name: str, frame_name: str = 'ORIGIN') Transform[source]
Compute world transform for a part frame.
- Parameters:
part_name – Part to get transform for
frame_name – Frame on the part (default “ORIGIN”)
- Returns:
World transform (from global origin to part frame)
This method uses caching for efficiency. Transform is recomputed only when a joint value changes in the ancestor chain.
- parts: Dict[str, KinematicPart]
- set_joint_value(part_name: str, value: float, clamp: bool = True) None[source]
Set joint value for a part and invalidate descendant caches.
- Parameters:
part_name – Part whose joint to modify
value – New joint value (degrees for revolute, mm for prismatic)
clamp – If True, clamp to joint limits
- class yapcad.kinematics.KinematicPart(name: str, parent: str | None = None, parent_frame: str = 'ORIGIN', joint: Joint = <factory>, frames: Dict[str, ~yapcad.kinematics.frame.CoordinateFrame]=<factory>, stl_path: str | None = None, is_printable: bool = True, material: str = 'PETG', color: Tuple[float, float, float]=(0.5, 0.5, 0.5), description: str = '', _world_transform: Transform | None = None, _transform_dirty: bool = True)[source]
Bases:
objectNode in a kinematic tree.
A KinematicPart represents a rigid body in an articulated assembly. It connects to a parent part via a joint and can have multiple named coordinate frames for attaching children or defining features.
- joint
Joint connecting to parent
- frames
Dict of named coordinate frames on this part
- Type:
Example:
# Create a part with frames link = KinematicPart( name="LINK1", parent="BASE", parent_frame="MOUNT", joint=Joint("joint1", JointType.REVOLUTE), ) # Add frames for child attachments link.add_frame( "END_EFFECTOR", Transform.from_translation(100, 0, 0), "Tool attachment point" )
- add_frame(name: str, transform: Transform, description: str = '') CoordinateFrame[source]
Add a coordinate frame to this part.
- Parameters:
name – Unique frame name
transform – Transform from part origin to frame
description – Human-readable description
- Returns:
The created frame
- frames: Dict[str, CoordinateFrame]
- classmethod from_dict(data: dict) KinematicPart[source]
Create part from dictionary.
- get_frame(name: str) CoordinateFrame | None[source]
Get a coordinate frame by name.
- Parameters:
name – Frame name
- Returns:
CoordinateFrame or None if not found
- class yapcad.kinematics.Transform(matrix: ndarray = <factory>)[source]
Bases:
object4x4 homogeneous transformation matrix.
Represents a rigid body transformation (rotation + translation) in 3D space. The matrix format is:
[R11 R12 R13 Tx] [R21 R22 R23 Ty] [R31 R32 R33 Tz] [0 0 0 1 ]
Where the upper-left 3x3 is the rotation matrix and the right column (top 3 elements) is the translation vector.
Transforms can be composed via matrix multiplication using the @ operator:
world_T_tool = world_T_base @ base_T_link @ link_T_tool
- matrix
4x4 numpy array representing the transform
- Type:
Example:
# Create transforms t1 = Transform.from_translation(10, 0, 0) t2 = Transform.from_rotation_z(45) # degrees # Compose (t2 applied after t1) t3 = t1 @ t2 # Get components pos = t3.translation # (x, y, z) R = t3.rotation_matrix # 3x3
- classmethod from_axis_angle(axis: Tuple[float, float, float], angle_deg: float) Transform[source]
Create rotation from axis-angle representation.
Uses Rodrigues’ rotation formula.
- Parameters:
axis – Unit rotation axis (x, y, z)
angle_deg – Rotation angle in degrees
- Returns:
Transform with specified rotation
- classmethod from_dict(data: dict) Transform[source]
Create transform from dictionary.
- Parameters:
data – Dict with ‘matrix’ key (4x4 list)
- Returns:
Transform from matrix
- classmethod from_euler_xyz(rx_deg: float, ry_deg: float, rz_deg: float) Transform[source]
Create rotation from Euler angles (intrinsic XYZ order).
- Parameters:
rx_deg – Rotation about X axis in degrees
ry_deg – Rotation about Y axis in degrees
rz_deg – Rotation about Z axis in degrees
- Returns:
Transform with combined rotation
- classmethod from_matrix(matrix: Any) Transform[source]
Create transform from 4x4 matrix (numpy array or nested list).
- Parameters:
matrix – 4x4 array-like
- Returns:
Transform wrapping the matrix
- classmethod from_position_rpy(x: float, y: float, z: float, roll_deg: float, pitch_deg: float, yaw_deg: float) Transform[source]
Create transform from position and roll-pitch-yaw angles.
- Parameters:
x – X position
y – Y position
z – Z position
roll_deg – Roll angle (rotation about X) in degrees
pitch_deg – Pitch angle (rotation about Y) in degrees
yaw_deg – Yaw angle (rotation about Z) in degrees
- Returns:
Combined transform
- classmethod from_rotation_x(angle_deg: float) Transform[source]
Create rotation about X axis.
- Parameters:
angle_deg – Rotation angle in degrees
- Returns:
Transform with rotation about X
- classmethod from_rotation_y(angle_deg: float) Transform[source]
Create rotation about Y axis.
- Parameters:
angle_deg – Rotation angle in degrees
- Returns:
Transform with rotation about Y
- classmethod from_rotation_z(angle_deg: float) Transform[source]
Create rotation about Z axis.
- Parameters:
angle_deg – Rotation angle in degrees
- Returns:
Transform with rotation about Z
- classmethod from_translation(x: float, y: float, z: float) Transform[source]
Create translation-only transform.
- Parameters:
x – Translation along X axis
y – Translation along Y axis
z – Translation along Z axis
- Returns:
Transform with specified translation
- inverse() Transform[source]
Compute inverse transform.
- Returns:
Transform T^-1 such that T @ T^-1 = I
For rigid transforms, this is computed efficiently as:
R^T | -R^T * t ----+---------- 0 | 1
- to_dict() dict[source]
Convert to dictionary for JSON serialization.
- Returns:
Dict with translation, rotation_xyz, and matrix
- to_euler_xyz() Tuple[float, float, float][source]
Extract Euler angles (intrinsic XYZ order) in degrees.
- Returns:
(rx, ry, rz) rotation angles in degrees
Note: May have gimbal lock issues when pitch is near ±90°.
- transform_point(point: Tuple[float, float, float]) Tuple[float, float, float][source]
Transform a point (applies rotation + translation).
- Parameters:
point – Point as (x, y, z)
- Returns:
Transformed point as (x, y, z)