LinkForge Composer API

The Composer provides a high-level, fluent API for programmatically constructing and assembling robot models. It is designed to be ergonomic, human-readable, and robust.

RobotBuilder

The main entry point for constructing a robot model.

Tip

Context Managers & Cloning RobotBuilder supports deep cloning via .clone(), allowing you to use a base builder as a template and fork it into multiple variations. Additionally, LinkBuilder supports context managers (with builder.link(...)) to automatically set the parent context for nested links, removing the need to manually specify the parent= argument.

class linkforge.core.RobotBuilder(name=None, robot=None)[source]

Bases: object

A high-level API to compose robots programmatically.

This class serves as the entry point for building robots. It can create new robots from scratch or modify existing ones by adding links or attaching sub-components.

Parameters:
__init__(name=None, robot=None)[source]

Initialize a new robot builder.

Parameters:
  • name (str | None) – Name of the new robot (required if robot is None).

  • robot (Robot | None) – Existing robot model to build upon.

Raises:

RobotModelError – If neither name nor robot is provided.

Start building a new link programmatically.

Parameters:
  • name (str) – Unique name for the link.

  • parent (str | None) – Optional parent link name to connect to immediately.

  • joint_name (str | None) – Optional explicit name for the connecting joint.

Return type:

LinkBuilder

Returns:

A LinkBuilder instance for fluent construction.

attach(component, at_link, joint_name=None, prefix='', joint_type=JointType.FIXED, xyz=(0, 0, 0), rpy=(0, 0, 0), axis=None, limits=None, disable_collision=False, reason='Adjacent')[source]

Merge another robot or assembly into the current one.

Parameters:
  • component (Robot | IComposer) – The Robot or IComposer (e.g. RobotBuilder) to attach.

  • at_link (str) – The link in the current robot to attach to.

  • joint_name (str | None) – Optional name for the connecting joint.

  • prefix (str) – Optional prefix for all links/joints in the component.

  • joint_type (JointType) – Type of connecting joint.

  • xyz (tuple[float, float, float]) – Joint origin translation.

  • rpy (tuple[float, float, float]) – Joint origin rotation.

  • axis (tuple[float, float, float] | None) – Optional joint axis (automatically normalized).

  • limits (tuple[float, float] | None) – Optional (lower, upper) joint limits.

  • disable_collision (bool) – Whether to disable collision checking at the interface.

  • reason (str) – Semantic reason for disabling collisions (e.g., β€œAdjacent”).

Return type:

RobotBuilder

Returns:

The RobotBuilder instance.

material(name, color=None)[source]

Define a global material that can be reused by multiple links.

Parameters:
Return type:

RobotBuilder

Returns:

The RobotBuilder instance.

ros2_control(name, hardware_plugin, control_type='system', parameters=None)[source]

Add a global ros2_control system configuration.

Parameters:
  • name (str) – Unique system name.

  • hardware_plugin (str) – The hardware interface plugin (e.g. β€˜fake_components/GenericSystem’).

  • control_type (str) – Type of control (usually β€˜system’).

  • parameters (dict[str, Any] | None) – Key-value parameters for the hardware interface.

Return type:

RobotBuilder

Returns:

The RobotBuilder instance.

property semantic: SemanticBuilder

Access the semantic (SRDF/MoveIt) construction API.

Example

>>> builder.semantic.group("arm", links=["link1", "link2"])
clone()[source]

Create a deep copy of the builder and its robot state.

Return type:

RobotBuilder

Returns:

A new independent RobotBuilder instance with cloned state.

build(validate=True)[source]

Finalize the assembly and return the completed Robot model.

Parameters:

validate (bool) – If True, performs a kinematic check for disconnected links or cycles.

Return type:

Robot

Returns:

The completed Robot object.

Raises:

RobotValidationError – If validation is requested and the robot is invalid.

export_urdf(validate=True, pretty_print=True)[source]

Generate the URDF XML representation of the robot.

Parameters:
  • validate (bool) – Whether to run internal LinkForge validation.

  • pretty_print (bool) – Whether to format the XML with indentation.

Return type:

str

Returns:

A URDF XML string.

export_srdf(validate=True, pretty_print=True)[source]

Generate the SRDF XML representation of the robot.

Parameters:
  • validate (bool) – Whether to validate the semantic description.

  • pretty_print (bool) – Whether to format the XML with indentation.

Return type:

str

Returns:

An SRDF XML string.

LinkBuilder

A staged builder for configuring individual links and their parent joints.

class linkforge.core.LinkBuilder(builder, name, parent=None, joint_name=None)[source]

Bases: object

Staged fluent builder for programmatic link and joint construction.

This builder accumulates link and joint properties in stages. It is usually returned by builder.link() or link_builder.child().

Parameters:
__init__(builder, name, parent=None, joint_name=None)[source]

Initialize a new LinkBuilder. Internal use only.

Parameters:
__enter__()[source]

Enter the context of this link.

Pushes this link’s name onto the parent stack, making it the default parent for any links created within this block.

Return type:

LinkBuilder

__exit__(exc_type, exc_val, exc_tb)[source]

Exit the context of this link.

Pops this link’s name from the parent stack and automatically commits the link to flush its configured properties if no exception occurred.

Parameters:
Return type:

None

visual(geometry, xyz=(0, 0, 0), rpy=(0, 0, 0), material=None, name=None)[source]

Add a visual representation to the link.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance for chaining.

collision(geometry=None, xyz=None, rpy=None, name=None)[source]

Add a collision geometry to the link.

If no arguments are provided, it automatically clones the last added visual element’s geometry and origin.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

mass(value, origin_xyz=None, origin_rpy=None, inertia=None)[source]

Define the mass and center of gravity for the link.

If no inertia is provided, LinkForge will automatically calculate the inertia tensor based on the link’s geometry and mass during commit().

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

inertia(ixx, iyy, izz, ixy=0, ixz=0, iyz=0)[source]

Manually specify the inertia tensor components.

Parameters:
  • ixx (float) – Moments of inertia.

  • iyy (float) – Moments of inertia.

  • izz (float) – Moments of inertia.

  • ixy (float) – Products of inertia.

  • ixz (float) – Products of inertia.

  • iyz (float) – Products of inertia.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

at_origin(xyz=(0, 0, 0), rpy=(0, 0, 0))[source]

Set the transform from the parent link to this link’s frame.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

fixed(name=None, xyz=None, rpy=None)[source]

Configure the connection as a FIXED joint.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

revolute(axis, limits, name=None, xyz=None, rpy=None, effort=10.0, velocity=1.0)[source]

Configure the connection as a REVOLUTE (limited rotation) joint.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

continuous(axis, name=None, xyz=None, rpy=None, effort=10.0, velocity=1.0)[source]

Configure the connection as a CONTINUOUS (unlimited rotation) joint.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

prismatic(axis, limits, name=None, xyz=None, rpy=None, effort=10.0, velocity=1.0)[source]

Configure the connection as a PRISMATIC (linear sliding) joint.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

floating(name=None, xyz=None, rpy=None)[source]

Configure the connection as a FLOATING (6 DOF) joint.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

planar(axis, name=None, xyz=None, rpy=None)[source]

Configure the connection as a PLANAR joint.

Parameters:
Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

dynamics(damping=0.0, friction=0.0)[source]

Set the physical dynamics for the joint.

Parameters:
  • damping (float) – Damping coefficient.

  • friction (float) – Friction coefficient.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

mimic(joint, multiplier=1.0, offset=0.0)[source]

Set this joint to mimic another joint’s movement.

Parameters:
  • joint (str) – Name of the joint to mimic.

  • multiplier (float) – Scaling factor for the movement.

  • offset (float) – Offset in radians/meters.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

safety(soft_lower=None, soft_upper=None, k_position=None, k_velocity=0.0)[source]

Define a safety controller for the joint.

Parameters:
  • soft_lower (float | None) – Software limits.

  • soft_upper (float | None) – Software limits.

  • k_position (float | None) – Controller gains.

  • k_velocity (float) – Controller gains.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

calibration(rising=None, falling=None)[source]

Set calibration offsets for the joint.

Parameters:
  • rising (float | None) – Rising edge offset.

  • falling (float | None) – Falling edge offset.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

physics(**kwargs)[source]

Set surface and contact physics properties for this link.

Supports both typed LinkPhysics fields and raw engine-specific parameters.

Common arguments:

self_collide (bool): Enable self-collision. gravity (bool): Enable gravity. mu, mu2 (float): Friction coefficients. kp, kd (float): Contact stiffness and damping.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

Parameters:

kwargs (Any)

transmission(reduction=1.0, interface='effort', actuator=None, name=None)[source]

Define a transmission (mechanical reduction) for the current joint.

Parameters:
  • reduction (float) – Mechanical reduction ratio.

  • interface (str) – Hardware interface (effort, position, velocity).

  • actuator (str | None) – Optional name for the actuator.

  • name (str | None) – Optional transmission name.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

ros2_control(command_interfaces, state_interfaces, parameters=None, system_name=None)[source]

Configure ros2_control interfaces for the current joint.

Parameters:
  • command_interfaces (list[str]) – List of allowed commands (e.g. [β€˜position’]).

  • state_interfaces (list[str]) – List of exposed states (e.g. [β€˜position’, β€˜velocity’]).

  • parameters (dict[str, Any] | None) – Key-value parameters for the joint control.

  • system_name (str | None) – Optional name of the specific ros2_control system to attach to.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

camera(name, fov=1.047, width=640, height=480, xyz=(0, 0, 0), rpy=(0, 0, 0))[source]

Attach a camera sensor to this link.

Parameters:
  • name (str) – Unique sensor name.

  • fov (float) – Horizontal field of view in radians.

  • width (int) – Resolution in pixels.

  • height (int) – Resolution in pixels.

  • xyz (tuple[float, float, float]) – Position/Orientation relative to link frame.

  • rpy (tuple[float, float, float]) – Position/Orientation relative to link frame.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

lidar(name, range_min=0.1, range_max=10.0, samples=640, xyz=(0, 0, 0), rpy=(0, 0, 0))[source]

Attach a 1D/2D lidar sensor to this link.

Parameters:
  • name (str) – Unique sensor name.

  • range_min (float) – Distance limits in meters.

  • range_max (float) – Distance limits in meters.

  • samples (int) – Number of rays per scan.

  • xyz (tuple[float, float, float]) – Position/Orientation relative to link frame.

  • rpy (tuple[float, float, float]) – Position/Orientation relative to link frame.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

gpu_lidar(name, range_min=0.1, range_max=10.0, samples=640, xyz=(0, 0, 0), rpy=(0, 0, 0))[source]

Attach a high-performance GPU-accelerated lidar sensor to this link.

Parameters:
  • name (str) – Unique sensor name.

  • range_min (float) – Distance limits in meters.

  • range_max (float) – Distance limits in meters.

  • samples (int) – Number of rays per scan.

  • xyz (tuple[float, float, float]) – Position/Orientation relative to link frame.

  • rpy (tuple[float, float, float]) – Position/Orientation relative to link frame.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

imu(name, update_rate=100.0, xyz=(0, 0, 0), rpy=(0, 0, 0))[source]

Attach an IMU (Inertial Measurement Unit) to this link.

Parameters:
  • name (str) – Unique sensor name.

  • update_rate (float) – Sampling rate in Hz.

  • xyz (tuple[float, float, float]) – Position/Orientation relative to link frame.

  • rpy (tuple[float, float, float]) – Position/Orientation relative to link frame.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

gps(name, update_rate=5.0, xyz=(0, 0, 0), rpy=(0, 0, 0))[source]

Attach a GPS sensor to this link.

Parameters:
  • name (str) – Unique sensor name.

  • update_rate (float) – Sampling rate in Hz.

  • xyz (tuple[float, float, float]) – Position/Orientation relative to link frame.

  • rpy (tuple[float, float, float]) – Position/Orientation relative to link frame.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

force_torque(name, update_rate=100.0, xyz=(0, 0, 0), rpy=(0, 0, 0))[source]

Attach a force-torque sensor to this link.

Parameters:
  • name (str) – Unique sensor name.

  • update_rate (float) – Sampling rate in Hz.

  • xyz (tuple[float, float, float]) – Position/Orientation relative to link frame.

  • rpy (tuple[float, float, float]) – Position/Orientation relative to link frame.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

contact(name, collision, update_rate=50.0)[source]

Attach a contact sensor to this link.

Parameters:
  • name (str) – Unique sensor name.

  • collision (str) – The name of the collision element to monitor.

  • update_rate (float) – Sampling rate in Hz.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

sensor(sensor)[source]

Attach a pre-configured Sensor object to this link.

Parameters:

sensor (Sensor) – Pre-configured Sensor model.

Return type:

LinkBuilder

Returns:

The LinkBuilder instance.

child(name, joint_name=None)[source]

Finalize this link and start building a new child link attached to it.

Parameters:
  • name (str) – Name of the new child link.

  • joint_name (str | None) – Optional explicit name for the connecting joint.

Return type:

LinkBuilder

Returns:

A new LinkBuilder instance for the child link.

commit()[source]

Finalize this link and return to the main RobotBuilder.

Return type:

IComposer

Returns:

The parent RobotBuilder instance.

root()[source]

Finalize this link as the robot’s root link (no joint).

Raises:

RobotValidationError – If the link already has a parent assigned.

Return type:

IComposer

Returns:

The parent RobotBuilder instance.

build()[source]

Finalize this link and return the completed Robot model.

Return type:

Robot

Returns:

The completed Robot model.

SemanticBuilder

A namespace for SRDF and MoveIt planning groups, named states, and self-collision settings.

class linkforge.core.composer.semantic_builder.SemanticBuilder(builder)[source]

Bases: object

Namespace for SRDF and MoveIt-specific semantic properties.

Accessed via RobotBuilder.semantic.

Parameters:

builder (IComposer)

__init__(builder)[source]

Initialize semantic builder.

Parameters:

builder (IComposer)

done()[source]

Return to the parent RobotBuilder.

Return type:

IComposer

group(name, links=None, joints=None, chains=None, subgroups=None, base_link=None, tip_link=None)[source]

Define a planning group for MoveIt.

Parameters:
  • name (str) – Unique name for the group.

  • links (list[str] | None) – List of link names to include.

  • joints (list[str] | None) – List of joint names to include.

  • chains (list[Chain] | None) – List of (base, tip) tuples for kinematic chains.

  • subgroups (list[str] | None) – List of other planning group names to include.

  • base_link (str | None) – Optional shorthand for chain base.

  • tip_link (str | None) – Optional shorthand for chain tip.

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

group_state(name, group, values)[source]

Define a named state (e.g. β€˜home’) for a planning group.

Parameters:
  • name (str) – Unique name for the state.

  • group (str) – The group this state belongs to.

  • values (dict[str, float | tuple[float, ...]]) – Dictionary of joint names and their positions.

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

end_effector(name, group, parent_link, parent_group=None)[source]

Define an end effector for MoveIt.

Parameters:
  • name (str) – Unique name for the end effector.

  • group (str) – The planning group representing the end effector.

  • parent_link (str) – The link it is attached to.

  • parent_group (str | None) – Optional parent group (e.g. β€˜arm’).

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

passive_joint(name)[source]

Mark a joint as passive (not actuated) for MoveIt.

Parameters:

name (str) – Name of the joint to mark as passive.

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

virtual_joint(name, child_link, parent_frame='world', joint_type='fixed')[source]

Define a virtual joint connecting the robot to the world frame.

Parameters:
  • name (str) – Unique joint name.

  • child_link (str) – The root link of the robot.

  • parent_frame (str) – The external frame (e.g., β€˜world’, β€˜map’).

  • joint_type (str) – Joint type (fixed, floating, planar).

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

disable_collisions(link1, link2, reason='Adjacent')[source]

Instruct MoveIt to ignore collisions between two specific links.

Parameters:
  • link1 (str) – Names of the links.

  • link2 (str) – Names of the links.

  • reason (str) – Explanation for disabling (e.g. β€˜Adjacent’, β€˜Never’).

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

enable_collisions(link1, link2, reason=None)[source]

Explicitly re-enable collision checking between two specific links.

Parameters:
  • link1 (str) – Names of the links.

  • link2 (str) – Names of the links.

  • reason (str | None) – Optional explanation for enabling.

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

disable_default_collisions(link)[source]

Disable all default collisions for a specific link.

Parameters:

link (str) – Name of the link.

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

joint_property(joint_name, property_name, value)[source]

Add a custom property/metadata to a joint.

Parameters:
  • joint_name (str) – Name of the joint.

  • property_name (str) – Name of the property.

  • value (str) – Property value as string.

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

Add sphere-based collision approximation for a link.

Parameters:
  • link (str) – Name of the link.

  • spheres (list[SrdfSphere]) – List of SrdfSphere objects.

Return type:

SemanticBuilder

Returns:

The parent RobotBuilder instance.

Interfaces

class linkforge.core.composer.interfaces.IComposer(*args, **kwargs)[source]

Bases: Protocol

Interface for a builder that can contain and manage links.

robot: Robot

Start building a new link.

Parameters:
Return type:

LinkBuilder

material(name, color=None)[source]

Define a global material.

Parameters:
Return type:

IComposer

build(validate=True)[source]

Finalize the assembly and return the completed Robot model.

Parameters:

validate (bool)

Return type:

Robot

__init__(*args, **kwargs)