API Reference¶
This page provides the auto-generated API documentation for the core classes in bard.
Robot Chain¶
Defines the core kinematic chain data structure for representing robots.
This module contains the Chain class, which is the central object for all
kinematics and dynamics calculations in the bard library. It processes a
robot’s structure, typically parsed from a URDF file, into an efficient,
indexed, and tensor-based representation. This class manages the robot’s
topology, joint properties, and tensor attributes like data type and device,
providing a unified interface for all other algorithm classes.
- class bard.core.chain.Chain(root_frame, floating_base=False, base_name='base', dtype=torch.float32, device='cpu')¶
Represents a robot’s kinematic structure as a tree of frames.
This class is the central object for all kinematics and dynamics calculations. It holds the robot’s structure, parsed from a URDF, and provides methods for querying frames, joints, and managing data types and devices. It supports both fixed-base and floating-base robots for vectorized batch operations.
Coordinate Conventions:
- Fixed-base robots:
Configuration
q:[joint_angles...](nq = n_joints)Velocity
v:[joint_velocities...](nv = n_joints)
- Floating-base robots:
Configuration
q:[tx, ty, tz, qw, qx, qy, qz, joint_angles...](nq = 7 + n_joints)Velocity
v:[vx, vy, vz, wx, wy, wz, joint_velocities...](nv = 6 + n_joints)
The base orientation is represented by a unit quaternion
[qw, qx, qy, qz].- has_floating_base¶
Trueif the robot has a 6-DOF floating base.- Type:
bool
- nq¶
The total dimension of the configuration space vector
q.- Type:
int
- nv¶
The total dimension of the velocity space vector
v.- Type:
int
- n_joints¶
The number of actuated (non-fixed) joints.
- Type:
int
- n_nodes¶
The total number of frames (links) in the kinematic tree.
- Type:
int
- dtype¶
The PyTorch data type used for all tensors.
- Type:
torch.dtype
- device¶
The PyTorch device (e.g., “cpu” or “cuda”) for all tensors.
- Type:
torch.device
- low¶
A tensor of lower position limits for all actuated joints.
- Type:
torch.Tensor
- high¶
A tensor of upper position limits for all actuated joints.
- Type:
torch.Tensor
- clamp(joint_values)¶
Clamps joint values to the robot’s defined joint position limits.
- Parameters:
joint_values (torch.Tensor) – A tensor of joint values, corresponding to the joint-space part of
q.- Returns:
The clamped joint values.
- Return type:
torch.Tensor
- ensure_tensor(value)¶
Converts various input types to a tensor in the correct joint order.
This utility handles conversion from numpy arrays, lists, or dictionaries (mapping joint names to values) into a
torch.Tensoron the chain’s device and dtype.- Parameters:
value (Union[torch.Tensor, np.ndarray, List, Dict]) – The input value. If a dictionary is provided, it must contain all actuated joint names as keys.
- Returns:
The converted tensor, on the correct device and dtype.
- Return type:
torch.Tensor
- Raises:
ValueError – If a dictionary input is missing values for some joints.
TypeError – If the input type is not supported.
- find_frame(name)¶
Finds a Frame object by its name in the kinematic tree.
- Parameters:
name (str) – The name of the frame to search for.
- Returns:
The Frame object if found, otherwise
None.- Return type:
Optional[Frame]
- get_frame_id(frame_name)¶
Gets the integer index for a frame name.
This index corresponds to the row/column in pre-computed data structures like
spatial_inertias.- Parameters:
frame_name (str) – The frame name.
- Returns:
A tensor containing the integer index.
- Return type:
torch.Tensor
- get_frame_names(exclude_fixed=True)¶
Returns all frame names in the chain in traversal order.
- Parameters:
exclude_fixed (bool, optional) – If
True, names of frames associated with fixed joints are omitted. Defaults toTrue.- Returns:
A list of all frame names.
- Return type:
List[str]
- get_generalized_coordinate_names(include_base=True)¶
Returns the ordered names for all configuration variables q.
- Parameters:
include_base (bool, optional) – If
Trueand the chain has a floating base, prepends the base coordinate names (e.g., “base_tx”, “base_qy”). Defaults toTrue.- Returns:
An ordered list of coordinate names.
- Return type:
List[str]
- get_generalized_velocity_names(include_base=True)¶
Returns the ordered names for all velocity variables v.
- Parameters:
include_base (bool, optional) – If
Trueand the chain has a floating base, prepends the base velocity names (e.g., “base_vx”, “base_wz”). Defaults toTrue.- Returns:
An ordered list of velocity names.
- Return type:
List[str]
- get_joint_effort_limits()¶
Returns the effort (torque/force) limits (low, high) for all actuated joints.
- Return type:
tuple[List[float],List[float]]
- get_joint_limits()¶
Returns the position limits (low, high) for all actuated joints.
- Return type:
tuple[List[float],List[float]]
- get_joint_parameter_names(exclude_fixed=True)¶
Returns the ordered list of actuated joint names.
This order defines the canonical layout of the joint components in the q and v vectors and is used consistently across all calculations.
- Parameters:
exclude_fixed (bool, optional) – If
True, names of fixed joints are omitted. This is the standard behavior. Defaults toTrue.- Returns:
An ordered list of actuated joint names.
- Return type:
List[str]
- get_joint_velocity_limits()¶
Returns the velocity limits (low, high) for all actuated joints.
- Return type:
tuple[List[float],List[float]]
- get_joints(exclude_fixed=True)¶
Returns all Joint objects in the chain.
- Parameters:
exclude_fixed (bool, optional) – If True, fixed joints are omitted from the list. Defaults to True.
- Returns:
A list of Joint objects.
- Return type:
List[Joint]
- pack_q(q_base, q_joints)¶
Combines base and joint positions into a single q vector.
- Parameters:
q_base (Optional[torch.Tensor]) – Base position of shape
(..., 7)[tx,ty,tz,qw,qx,qy,qz], orNonefor fixed-base robots.q_joints (torch.Tensor) – Joint positions of shape
(..., n_joints).
- Returns:
The full generalized coordinate vector q of shape
(..., nq).- Return type:
torch.Tensor
- pack_v(v_base, v_joints)¶
Combines base and joint velocities into a single v vector.
- Parameters:
v_base (Optional[torch.Tensor]) – Base velocity of shape
(..., 6)[vx,vy,vz,wx,wy,wz], orNonefor fixed-base robots.v_joints (torch.Tensor) – Joint velocities of shape
(..., n_joints).
- Returns:
The full generalized velocity vector v of shape
(..., nv).- Return type:
torch.Tensor
- to(dtype=None, device=None)¶
Moves all tensors in the chain to the specified dtype and/or device.
This is an in-place operation that modifies the chain’s internal tensors. It is useful for switching between CPU and GPU computation or changing floating-point precision.
- Parameters:
dtype (torch.dtype, optional) – The target data type. If
None, the current dtype is preserved.device (Union[str, torch.device], optional) – The target device. If
None, the current device is preserved.
- Returns:
The instance itself, allowing for method chaining.
- Return type:
- unpack_q(q)¶
Splits generalized coordinates q into base and joint components.
- Parameters:
q (torch.Tensor) – Generalized coordinates of shape
(..., nq).- Returns:
A tuple
(q_base, q_joints).q_basehas shape(..., 7)or isNonefor fixed-base robots.q_jointshas shape(..., n_joints).- Return type:
tuple[Optional[torch.Tensor], torch.Tensor]
- unpack_v(v)¶
Splits generalized velocities v into base and joint components.
- Parameters:
v (torch.Tensor) – Generalized velocities of shape
(..., nv).- Returns:
A tuple
(v_base, v_joints).v_basehas shape(..., 6)or isNonefor fixed-base robots.v_jointshas shape(..., n_joints).- Return type:
tuple[Optional[torch.Tensor], torch.Tensor]
Kinematics¶
Optimized class-based kinematic computations with pre-allocated memory.
This module provides classes for core kinematic calculations:
- ForwardKinematics: Computes the world-frame pose of any link.
- SpatialAcceleration: Computes the spatial acceleration of any link.
Optimized with JIT-compiled utility functions for better performance, making them suitable for use in computationally intensive loops, such as in reinforcement learning or trajectory optimization.
- class bard.core.kinematics.ForwardKinematics(chain, max_batch_size=1024, compile_enabled=False, compile_kwargs=None)¶
Forward kinematics computation with pre-allocated memory.
This class computes the forward kinematics for a given frame (link) in the robot’s kinematic chain. It determines the 4x4 homogeneous transformation matrix that represents the pose of the frame in the world coordinate system.
To achieve high performance, this class avoids runtime memory allocation by pre-computing static data. An instance should be created once per robot chain and reused for all subsequent computations.
- Parameters:
chain (chain.Chain) – The robot’s kinematic chain definition.
max_batch_size (int, optional) – The maximum batch size the instance will support. Defaults to 1024.
compile_enabled (bool, optional) – If
True, the core computation will be JIT-compiled withtorch.compile. Defaults toFalse.compile_kwargs (Dict[str, Any], optional) – A dictionary of keyword arguments to pass to
torch.compile. Defaults toNone.
- chain¶
The robot kinematic chain.
- Type:
- max_batch_size¶
The maximum supported batch size.
- Type:
int
- dtype¶
The data type of the tensors.
- Type:
torch.dtype
- device¶
The device where tensors are stored.
- Type:
torch.device
Example
# Create an FK instance once fk = ForwardKinematics(robot_chain, max_batch_size=128) eef_frame_id = robot_chain.get_frame_id("end_effector_link") # Use in a loop for efficient computation for q in data_loader: T_world_eef = fk.calc(q, eef_frame_id) position = T_world_eef[:, :3, 3] # ... use the computed pose ...
- calc(q, frame_id)¶
Compute forward kinematics for a specific frame.
- Parameters:
q (torch.Tensor) –
A batch of generalized positions.
For fixed-base robots, shape is
(B, n_joints).For floating-base robots, shape is
(B, 7 + n_joints), where the first 7 elements are[tx, ty, tz, qw, qx, qy, qz].
frame_id (int) – The integer index of the target frame (link).
- Returns:
A batch of
(B, 4, 4)homogeneous transformation matrices representing the world-frame pose of the target frame.- Return type:
torch.Tensor
- Raises:
ValueError – If the input batch size
Bexceedsself.max_batch_size.
- enable_compilation(enabled=True, **compile_kwargs)¶
Enable or disable
torch.compilefor the core computation.- Parameters:
enabled (bool, optional) – If
True, compilation is enabled. Defaults toTrue.**compile_kwargs – Additional keyword arguments to pass to
torch.compile.
- to(dtype=None, device=None)¶
Move all internal buffers to a specified dtype and/or device.
This is an in-place operation.
- Parameters:
dtype (torch.dtype, optional) – The target data type. Defaults to
None.device (torch.device, optional) – The target device. Defaults to
None.
- Returns:
The instance itself for method chaining.
- Return type:
- class bard.core.kinematics.SpatialAcceleration(chain, max_batch_size=1024, compile_enabled=False, compile_kwargs={'mode': 'reduce-overhead'})¶
End-effector spatial acceleration computation with pre-allocated memory.
This class implements the forward pass of the RNEA algorithm to compute the 6D spatial acceleration (linear and angular) of a specific frame. It is essential for tasks requiring acceleration-level analysis, such as operational space control.
All necessary buffers are pre-allocated for maximum performance, making it efficient for use in control loops or other performance-sensitive code.
- Parameters:
chain (chain.Chain) – The robot’s kinematic chain definition.
max_batch_size (int, optional) – The maximum batch size the instance will support. Defaults to 1024.
compile_enabled (bool, optional) – If
True, the core computation will be JIT-compiled withtorch.compile. Defaults toFalse.compile_kwargs (Dict[str, Any], optional) – A dictionary of keyword arguments to pass to
torch.compile. Defaults to{"mode": "reduce-overhead"}.
- chain¶
The robot kinematic chain.
- Type:
- max_batch_size¶
The maximum supported batch size.
- Type:
int
- dtype¶
The data type of the tensors.
- Type:
torch.dtype
- device¶
The device where tensors are stored.
- Type:
torch.device
Example
# Create an acceleration instance once accel = SpatialAcceleration(robot_chain, max_batch_size=128) eef_frame_id = robot_chain.get_frame_id("end_effector_link") # Use in a loop for q, qd, qdd in data_loader: a_world = accel.calc(q, qd, qdd, eef_frame_id, reference_frame="world") linear_accel = a_world[:, :3] # ... use the computed acceleration ...
- calc(q, qd, qdd, frame_id, reference_frame)¶
Compute the spatial acceleration of a frame.
- Parameters:
q (torch.Tensor) – A batch of generalized positions. - For fixed-base robots, shape is
(B, n_joints). - For floating-base robots, shape is(B, 7 + n_joints).qd (torch.Tensor) – A batch of generalized velocities. - For fixed-base robots, shape is
(B, n_joints). - For floating-base robots, shape is(B, 6 + n_joints).qdd (torch.Tensor) – A batch of generalized accelerations, with the same shape as
qd.frame_id (int) – The integer index of the target frame.
reference_frame (str) – The frame of reference for the output acceleration. Can be
"world"or"local"(the frame’s own coordinate system).
- Returns:
The spatial acceleration
[linear; angular]of the target frame, with shape(B, 6).- Return type:
torch.Tensor
- Raises:
ValueError – If the input batch size
Bexceedsself.max_batch_size.
- enable_compilation(enabled=True, **compile_kwargs)¶
Enable or disable
torch.compilefor the core computation.- Parameters:
enabled (bool, optional) – If
True, compilation is enabled. Defaults toTrue.**compile_kwargs – Additional keyword arguments to pass to
torch.compile.
- to(dtype=None, device=None)¶
Move all internal buffers to a specified dtype and/or device.
This is an in-place operation.
- Parameters:
dtype (torch.dtype, optional) – The target data type. Defaults to
None.device (torch.device, optional) – The target device. Defaults to
None.
- Returns:
The instance itself for method chaining.
- Return type:
Jacobian¶
Optimized Jacobian computation with pre-allocated memory.
This module provides efficient Jacobian matrix computation for robot kinematics, optimized with JIT-compiled utility functions and pre-allocated memory buffers.
- class bard.core.jacobian.Jacobian(chain, max_batch_size=1024, compile_enabled=False, compile_kwargs={'mode': 'reduce-overhead'})¶
Optimized Jacobian matrix computation with pre-allocated memory.
This class computes the geometric Jacobian matrix that relates joint velocities to end-effector spatial velocity. The Jacobian can be computed in either the world frame or the local (body) frame.
- Parameters:
chain (chain.Chain) – The robot’s kinematic chain definition.
max_batch_size (int, optional) – The maximum batch size the instance will support. Defaults to 1024.
compile_enabled (bool, optional) – If
True, the core computation will be JIT-compiled withtorch.compile. Defaults toFalse.compile_kwargs (Dict[str, Any], optional) – A dictionary of keyword arguments to pass to
torch.compile. Defaults to{"mode": "reduce-overhead"}.
- chain¶
The robot kinematic chain.
- Type:
- max_batch_size¶
The maximum supported batch size.
- Type:
int
- dtype¶
The data type of the tensors.
- Type:
torch.dtype
- device¶
The device where tensors are stored.
- Type:
torch.device
- nv¶
The dimension of velocity space.
- Type:
int
Example
# Create a Jacobian instance once jac = Jacobian(robot_chain, max_batch_size=128) eef_frame_id = robot_chain.get_frame_id("end_effector_link") # Use in a loop for efficient computation for q in data_loader: J_world = jac.calc(q, eef_frame_id, reference_frame="world") # ... use the Jacobian ...
- calc(q, frame_id, reference_frame, return_eef_pose=False)¶
Compute the Jacobian matrix for a specific frame.
- Parameters:
q (torch.Tensor) – A batch of generalized positions. - For fixed-base robots, shape is
(B, n_joints). - For floating-base robots, shape is(B, 7 + n_joints).frame_id (int) – The integer index of the target frame.
reference_frame (str) – The frame of reference for the Jacobian. Can be
"world"or"local".return_eef_pose (bool, optional) – If
True, also returns the world-frame pose of the target frame. Defaults toFalse.
- Returns:
If
return_eef_pose=False: The Jacobian matrix of shape(B, 6, nv).If
return_eef_pose=True: A tuple(J, T_world_to_frame)whereJis the Jacobian andT_world_to_frameis the pose matrix of shape(B, 4, 4).
- Return type:
torch.Tensor or Tuple[torch.Tensor, torch.Tensor]
- Raises:
ValueError – If the input batch size
Bexceedsself.max_batch_size.
- enable_compilation(enabled=True, **compile_kwargs)¶
Enable or disable
torch.compilefor the core computation.- Parameters:
enabled (bool, optional) – If
True, compilation is enabled. Defaults toTrue.**compile_kwargs – Additional keyword arguments to pass to
torch.compile.
- to(dtype=None, device=None)¶
Move all internal buffers to a specified dtype and/or device.
This is an in-place operation.
- Parameters:
dtype (torch.dtype, optional) – The target data type. Defaults to
None.device (torch.device, optional) – The target device. Defaults to
None.
- Returns:
The instance itself for method chaining.
- Return type:
Dynamics¶
Class-based robot dynamics algorithms with pre-allocated memory.
This module implements the core dynamics algorithms for the bard library.
It includes class-based, optimized implementations of the Recursive Newton-Euler
Algorithm (RNEA) for inverse dynamics and the Composite Rigid Body Algorithm (CRBA)
for calculating the mass matrix.
- class bard.core.dynamics.CRBA(chain, max_batch_size=1024, compile_enabled=False, compile_kwargs={'mode': 'reduce-overhead'})¶
Composite Rigid Body Algorithm with pre-allocated memory.
This class provides an efficient, batched implementation of the CRBA algorithm to compute the joint-space inertia matrix (mass matrix)
M. The mass matrix relates joint accelerations to joint torques via the equation \(\tau = M(q) \ddot{q} + C(q, \dot{q})\).All temporary storage needed for the computation is pre-allocated upon instantiation, which eliminates runtime memory allocation overhead. This makes it ideal for high-performance scenarios. An instance should be created once per robot chain and reused for all subsequent computations.
- Parameters:
chain (chain.Chain) – The robot’s kinematic chain definition.
max_batch_size (int, optional) – The maximum batch size the instance will support. Defaults to 1024.
compile_enabled (bool, optional) – If
True, the core computation will be JIT-compiled withtorch.compile. Defaults toFalse.compile_kwargs (Dict[str, Any], optional) – A dictionary of keyword arguments to pass to
torch.compile. Defaults to{"mode": "reduce-overhead"}.
- chain¶
The robot kinematic chain.
- Type:
- max_batch_size¶
The maximum supported batch size.
- Type:
int
- dtype¶
The data type of the tensors.
- Type:
torch.dtype
- device¶
The device where tensors are stored.
- Type:
torch.device
Example
# Create a CRBA instance once crba = CRBA(robot_chain, max_batch_size=128) # Use in a loop for efficient computation for q in data_loader: M = crba.calc(q) # ... use the computed mass matrix ...
- calc(q)¶
Compute the mass matrix
Mvia the CRBA algorithm.- Parameters:
q (torch.Tensor) –
A batch of generalized positions.
For fixed-base robots, shape is
(B, n_joints).For floating-base robots, shape is
(B, 7 + n_joints), where the first 7 elements are[tx, ty, tz, qw, qx, qy, qz].
- Returns:
The batched mass matrix
M.For fixed-base robots, shape is
(B, n_joints, n_joints).For floating-base robots, shape is
(B, 6 + n_joints, 6 + n_joints).
- Return type:
torch.Tensor
- Raises:
ValueError – If the input batch size
Bexceedsself.max_batch_size.
- enable_compilation(enabled=True, **compile_kwargs)¶
Enable or disable
torch.compilefor the core computation.- Parameters:
enabled (bool, optional) – If
True, compilation is enabled. Defaults toTrue.**compile_kwargs – Additional keyword arguments to pass to
torch.compile.
- to(dtype=None, device=None)¶
Move all internal buffers to a specified dtype and/or device.
This is an in-place operation.
- Parameters:
dtype (torch.dtype, optional) – The target data type. Defaults to
None.device (torch.device, optional) – The target device. Defaults to
None.
- Returns:
The instance itself for method chaining.
- Return type:
- class bard.core.dynamics.RNEA(chain, max_batch_size=1024, compile_enabled=False, compile_kwargs=None)¶
Recursive Newton-Euler Algorithm with pre-allocated memory.
This class provides an efficient, batched implementation of the RNEA algorithm to compute inverse dynamics. It calculates the generalized forces (torques) required to produce a given state of joint positions, velocities, and accelerations.
All temporary storage needed for the computation is pre-allocated upon instantiation, which eliminates runtime memory allocation overhead. This makes it ideal for high-performance scenarios. An instance should be created once per robot chain and reused for all subsequent computations.
- Parameters:
chain (chain.Chain) – The robot’s kinematic chain definition.
max_batch_size (int, optional) – The maximum batch size the instance will support. Defaults to 1024.
compile_enabled (bool, optional) – If
True, the core computation will be JIT-compiled withtorch.compile. Defaults toFalse.compile_kwargs (Dict[str, Any], optional) – A dictionary of keyword arguments to pass to
torch.compile. Defaults toNone.
- chain¶
The robot kinematic chain.
- Type:
- max_batch_size¶
The maximum supported batch size.
- Type:
int
- dtype¶
The data type of the tensors.
- Type:
torch.dtype
- device¶
The device where tensors are stored.
- Type:
torch.device
Example
# Create an RNEA instance once rnea = RNEA(robot_chain, max_batch_size=128) # Use in a loop for efficient computation for q, qd, qdd in data_loader: tau = rnea.calc(q, qd, qdd) # ... use the computed torques ...
- calc(q, qd, qdd, gravity=None)¶
Compute generalized forces (torques) via the RNEA algorithm.
- Parameters:
q (torch.Tensor) –
A batch of generalized positions.
For fixed-base robots, shape is
(B, n_joints).For floating-base robots, shape is
(B, 7 + n_joints), where the first 7 elements are[tx, ty, tz, qw, qx, qy, qz].
qd (torch.Tensor) –
A batch of generalized velocities.
For fixed-base robots, shape is
(B, n_joints).For floating-base robots, shape is
(B, 6 + n_joints), where the first 6 elements represent the base’s spatial velocity[vx, vy, vz, wx, wy, wz].
qdd (torch.Tensor) – A batch of generalized accelerations. Must have the same shape as
qd.gravity (torch.Tensor, optional) – A 3-element gravity vector in the world frame. If
None, defaults to[0, 0, -9.81].
- Returns:
A batch of generalized forces
tau.For fixed-base robots, shape is
(B, n_joints).For floating-base robots, shape is
(B, 6 + n_joints).
- Return type:
torch.Tensor
- Raises:
ValueError – If the input batch size
Bexceedsself.max_batch_size.
- enable_compilation(enabled=True, **compile_kwargs)¶
Enable or disable
torch.compilefor the core computation.- Parameters:
enabled (bool, optional) – If
True, compilation is enabled. Defaults toTrue.**compile_kwargs – Additional keyword arguments to pass to
torch.compile.
- to(dtype=None, device=None)¶
Move all internal buffers to a specified dtype and/or device.
This is an in-place operation.
- Parameters:
dtype (torch.dtype, optional) – The target data type. Defaults to
None.device (torch.device, optional) – The target device. Defaults to
None.
- Returns:
The instance itself for method chaining.
- Return type:
URDF Parsing¶
URDF parser for building a bard kinematic Chain.
This module provides the build_chain_from_urdf function, which serves as the primary entry point for creating a robot model from a URDF file’s content. It handles parsing of links, joints, and inertial properties, and supports the creation of both fixed-base and floating-base robot representations.
- bard.parsers.urdf.build_chain_from_urdf(path, *, floating_base=False, base_frame_name='floating_base', dtype=torch.float32, device='cpu')¶
Builds a bard Chain object from a URDF file.
- Parameters:
path (str | os.PathLike) – Filesystem path to the URDF file.
floating_base (bool, optional) – If True, a 6-DOF floating base is prepended to the root of the kinematic tree. Defaults to False.
base_frame_name (str, optional) – The name assigned to the synthetic base frame when floating_base is True. Defaults to “floating_base”.
dtype (torch.dtype, optional) – PyTorch dtype for the chain’s tensors. Defaults to torch.float32.
device (str | torch.device, optional) – PyTorch device for the chain’s tensors. Defaults to “cpu”.
- Returns:
bard.core.chain.Chain
- Raises:
FileNotFoundError – If the file does not exist.
ValueError – If a root link cannot be determined from the URDF.
Data Structures¶
Frame representation for kinematic tree nodes.
- class bard.structures.frame.Frame(name=None, link=None, joint=None, children=None)¶
A node in the robot kinematic tree, containing joint and link information.
A frame represents a coordinate system attached to a part of the robot. The kinematic tree is built by connecting these frames in parent-child relationships, forming a chain from the root to the end-effectors.
- name¶
The unique identifier for this frame.
- Type:
str
- link¶
The link object associated with this frame, containing physical properties like mass and inertia.
- Type:
- joint¶
The joint that connects this frame to its parent, defining the motion between them.
- Type:
- add_child(child)¶
Adds a child frame to this frame’s list of children.
- Parameters:
child (Frame) – The child frame to add.
- Return type:
None
- count_joints(exclude_fixed=True)¶
Counts the number of joints in the subtree starting from this frame.
- Parameters:
exclude_fixed (bool, optional) – If True, fixed joints are not counted. Defaults to True.
- Returns:
The total number of joints.
- Return type:
int
- find_by_name(target_name)¶
Finds a frame by name within this frame’s subtree.
- Parameters:
target_name (str) – The name of the frame to find.
- Returns:
The Frame object if found, otherwise None.
- Return type:
Optional[‘Frame’]
- get_all_frames()¶
Returns a list of all frames in the subtree starting from this frame.
- Returns:
A list of all frames in depth-first order.
- Return type:
List[Frame]
- get_transform(theta)¶
Computes the transformation for the joint associated with this frame.
This transform represents the motion of the joint given a joint angle theta. It is composed with the joint’s static offset.
- Parameters:
theta (torch.Tensor) – The joint position(s). Can be a scalar or a batched tensor of shape (B,).
- Returns:
A Transform3d object representing the batched joint motion.
- Return type:
tf.Transform3d
- is_end_effector()¶
Checks if this frame is a leaf node in the kinematic tree.
- Returns:
True if the frame has no children, otherwise False.
- Return type:
bool
- to(dtype=None, device=None)¶
Moves all tensor data in the frame and its children to a specified device/dtype.
- Parameters:
dtype (Optional[torch.dtype], optional) – The target data type. Defaults to None.
device (Optional[torch.device], optional) – The target device. Defaults to None.
- Returns:
Returns self for method chaining.
- Return type:
Joint representation for robot kinematic chains.
- class bard.structures.joint.Joint(name=None, offset=None, joint_type='fixed', axis=(0.0, 0.0, 1.0), dtype=torch.float32, device='cpu', limits=None, velocity_limits=None, effort_limits=None)¶
Represents a robot joint, defining the motion between two links.
This class stores the properties of a single joint, such as its type (revolute, prismatic, fixed), axis of motion, and physical limits.
- name¶
The unique identifier for the joint.
- Type:
str
- offset¶
The static transform from the parent link’s frame to the joint’s frame.
- Type:
Transform3d
- joint_type¶
The type of joint, one of ‘fixed’, ‘revolute’, ‘prismatic’.
- Type:
str
- axis¶
A 3D unit vector representing the axis of motion in the joint’s own frame.
- Type:
torch.Tensor
- limits¶
A tuple of (lower, upper) position limits in radians or meters. None if unbounded.
- Type:
Optional[Tuple[float, float]]
- velocity_limits¶
A tuple of (lower, upper) velocity limits. None if unbounded.
- Type:
Optional[Tuple[float, float]]
- effort_limits¶
A tuple of (lower, upper) force or torque limits. None if unbounded.
- Type:
Optional[Tuple[float, float]]
- clamp(joint_position)¶
Clamps a given joint position to the joint’s defined limits.
If the joint has no limits, the input position is returned unchanged.
- Parameters:
joint_position (torch.Tensor) – The current joint position(s) to clamp.
- Returns:
The clamped joint position(s).
- Return type:
torch.Tensor
Robot link representation with inertial and visual properties.
- class bard.structures.link.Link(name=None, offset=None, inertial=None, visuals=())¶
Represents a rigid body in the robot’s kinematic chain.
A link holds the physical properties of a robot segment, including its mass, inertia, and visual geometries for rendering.
- name¶
The unique identifier for the link.
- Type:
str
- offset¶
The static transform from the parent joint frame to this link’s reference frame.
- Type:
Transform3d
- inertial¶
A tuple containing the link’s inertial properties: (Center of Mass offset, mass, 3x3 inertia tensor). None for massless links.
- Type:
Optional[Tuple[object, float, torch.Tensor]]
- visuals¶
A list of Visual objects for rendering.
- Type:
List[Visual]