Skip to content

API Reference

The interfaces below are defined in waldoctl, the abstraction layer that all backends implement. When you write from parol6 import RobotClient in a script, that RobotClient is a concrete subclass of waldoctl.RobotClient — it inherits the same methods documented here, plus any backend-specific extras. The same applies to Robot, tool specs, and status types.

In short: this reference covers everything available to your scripts regardless of which backend you're using.

Robot

waldoctl.Robot

Bases: ABC

Unified robot interface — the single entry point for any backend.

Combines identity, joint configuration, tool definitions, kinematics, lifecycle management, and client factories into one ABC.

Required methods are marked with @abstractmethod. Optional capabilities have concrete defaults that backends override as needed.

name: str abstractmethod property

Human-readable robot name, e.g. "PAROL6".

joints: JointsSpec abstractmethod property

Joint configuration: count, names, limits, home position.

tools: ToolsSpec abstractmethod property

Available end-effector tools and their capabilities.

cartesian_limits: CartesianKinodynamicLimits abstractmethod property

Jog-mode Cartesian velocity and acceleration limits.

position_unit: Literal['mm', 'm'] abstractmethod property

How this robot's users think about distance (display hint).

has_force_torque: bool property

Whether force / torque readout is available.

has_freedrive: bool property

Whether a freedrive / teach mode is available.

digital_outputs: int abstractmethod property

Number of digital output pins.

digital_inputs: int abstractmethod property

Number of digital input pins.

urdf_path: str abstractmethod property

Path to the URDF file for 3-D rendering.

mesh_dir: str abstractmethod property

Directory containing STL / mesh files referenced by the URDF.

joint_index_mapping: tuple[int, ...] abstractmethod property

Maps URDF joint indices to control joint indices.

motion_profiles: tuple[str, ...] property

Available motion profile names.

At least one profile is required. The default is ("linear",) which backends should override with their actual profiles.

cartesian_frames: tuple[str, ...] property

Available Cartesian reference frames for jogging.

Default includes both WRF and TRF which are required.

backend_package: str abstractmethod property

Python package used by user scripts and subprocess workers.

sync_client_class: type abstractmethod property

The synchronous client class (e.g. RobotClient).

Used for editor autocomplete discovery and stepping wrapper. Convention: backends export this class at their package level.

async_client_class: type abstractmethod property

The asynchronous client class (e.g. AsyncRobotClient).

Used for editor command discovery (introspecting available methods). Convention: backends export this class at their package level.

fk(q_rad: NDArray[np.float64], out: NDArray[np.float64]) -> NDArray[np.float64] abstractmethod

Forward kinematics.

q_rad: joint angles in radians (num_joints,). out: pre-allocated (6,) buffer to write the result into.

Returns out filled with [x, y, z, rx, ry, rz] in meters + radians.

ik(pose: NDArray[np.float64], q_seed_rad: NDArray[np.float64]) -> IKResult abstractmethod

Inverse kinematics.

pose: [x, y, z, rx, ry, rz] — meters + radians. q_seed_rad: current joint angles in radians (seed).

Returns an IKResult with q in radians.

set_active_tool(tool_key: str, tcp_offset_m: tuple[float, float, float] | None = None, variant_key: str | None = None) -> None abstractmethod

Apply tool transform to the local FK/IK model.

When set, fk() returns TCP position instead of flange position.

tcp_offset_m: optional (x, y, z) user offset in meters, composed on top of the tool's registered transform. variant_key: optional variant whose TCP overrides the tool default.

check_limits(q_rad: NDArray[np.float64]) -> bool abstractmethod

Return True if all joints are within limits.

fk_batch(joint_path_rad: NDArray[np.float64]) -> NDArray[np.float64] abstractmethod

Batch FK: (N, num_joints) radians -> (N, 6) poses (m + rad).

ik_batch(poses: NDArray[np.float64], q_start_rad: NDArray[np.float64]) -> list[IKResult] abstractmethod

Batch IK: (N, 6) poses -> list of IKResult (radians).

start(**kwargs: Any) -> None abstractmethod

Start the backend process / connection (blocking).

What "start" means is backend-specific: spawn a subprocess, connect to a remote server, launch a ROS node, etc.

stop() -> None abstractmethod

Stop the backend process and release resources.

is_available(**kwargs: Any) -> bool abstractmethod

Check if the backend is reachable / ready.

create_async_client(**kwargs: Any) -> RobotClient abstractmethod

Create an async client connected to this backend.

create_sync_client(**kwargs: Any) -> object abstractmethod

Create a synchronous client. Returns backend-specific type.

create_dry_run_client(**kwargs: Any) -> DryRunClient | None

Create an offline simulation client, or None if unsupported.

RobotClient

waldoctl.RobotClient

Bases: ABC

Generic async robot control interface.

Backends inherit from this ABC and implement the required abstract methods. Optional methods have concrete defaults that raise NotImplementedError.

Command palette integration: Methods that should appear in the editor's command palette must include Category: and Example: sections in their docstrings. The editor parses these at startup to build the palette.

  • Category: <name> — groups the command in the palette UI.
  • Example: — the first indented line becomes the insertion snippet.

tool: ToolSpec property

The active bound tool.

Raises RuntimeError if no tool has been set.

close() -> None abstractmethod async

Release resources and disconnect.

ping() -> PingResult | None abstractmethod async

Check connectivity. Returns None if unreachable.

Category: Query

Example

rbt.ping()

wait_ready(timeout: float = 5.0, interval: float = 0.05) -> bool abstractmethod async

Block until the robot backend is reachable or timeout expires.

stream_status() -> AsyncIterator[StatusBuffer] abstractmethod

Async iterator of real-time status snapshots (yields copies, safe to store).

stream_status_shared() -> AsyncIterator[StatusBuffer] abstractmethod

Async iterator of real-time status snapshots (shared buffer, zero-copy).

move_j(angles: list[float] | None = None, *, pose: list[float] | None = None, duration: float = 0.0, speed: float = 0.0, accel: float = 1.0, r: float = 0.0, rel: bool = False, wait: bool = False, timeout: float = 10.0, **wait_kwargs: Any) -> int abstractmethod async

Joint-space move. angles: joint angles in degrees.

If pose is given, performs joint-interpolated move to Cartesian target. Returns the command index (>= 0) on success, -1 on failure.

Category: Motion

Example

rbt.move_j(, speed=0.5)

move_l(pose: list[float], *, frame: Frame = 'WRF', duration: float = 0.0, speed: float = 0.0, accel: float = 1.0, r: float = 0, rel: bool = False, wait: bool = False, **wait_kwargs: Any) -> int abstractmethod async

Linear Cartesian move to [x, y, z, rx, ry, rz].

Returns the command index (>= 0) on success, -1 on failure.

Category: Motion

Example

rbt.move_l(, speed=0.5)

home(wait: bool = False, **wait_kwargs: Any) -> int abstractmethod async

Move to the robot's home position.

Returns the command index (>= 0) on success, -1 on failure.

Category: Motion

Example

rbt.home()

move_c(via: list[float], end: list[float], *, frame: Frame = 'WRF', duration: float | None = None, speed: float | None = None, accel: float = 1.0, r: float = 0, wait: bool = False, **wait_kwargs: Any) -> int async

Circular arc move through via to end.

Category: Motion

Example

rbt.move_c(, , speed=0.5)

move_s(waypoints: list[list[float]], *, frame: Frame = 'WRF', duration: float | None = None, speed: float | None = None, accel: float = 1.0, wait: bool = False, **wait_kwargs: Any) -> int async

Cubic spline move through waypoints.

Category: Motion

Example

rbt.move_s(, speed=0.5)

move_p(waypoints: list[list[float]], *, frame: Frame = 'WRF', duration: float | None = None, speed: float | None = None, accel: float = 1.0, wait: bool = False, **wait_kwargs: Any) -> int async

Process move with auto-blending through waypoints.

Category: Motion

Example

rbt.move_p(, speed=0.5)

servo_j(angles: list[float], *, pose: list[float] | None = None, speed: float = 1.0, accel: float = 1.0) -> int abstractmethod async

Streaming joint position target (fire-and-forget).

angles: joint angles in degrees (ignored if pose is set). If pose is given, dispatches to Cartesian target via IK.

Category: Streaming

Example

rbt.servo_j()

servo_l(pose: list[float], *, speed: float = 1.0, accel: float = 1.0) -> int abstractmethod async

Streaming linear Cartesian position target (fire-and-forget).

pose: [x, y, z, rx, ry, rz] in mm and degrees.

Category: Streaming

Example

rbt.servo_l()

jog_j(joint: int, speed: float = 0.0, duration: float = 0.1, *, joints: list[int] | None = None, speeds: list[float] | None = None, accel: float = 1.0) -> int abstractmethod async

Joint velocity jog. Single-joint or multi-joint.

Single joint: jog_j(0, 0.5, 1.0) Multi joint: jog_j(joints=[0, 1], speeds=[0.5, -0.3], duration=1.0)

Category: Jog

Example

rbt.jog_j(, speed=0.5, duration=1.0)

jog_l(frame: Frame, axis: Axis | None = None, speed: float = 0.0, duration: float = 0.1, *, axes: list[Axis] | None = None, speeds_list: list[float] | None = None, accel: float = 1.0) -> int abstractmethod async

Cartesian velocity jog. Single-axis or multi-axis.

Single axis: jog_l("WRF", "X", 0.5, 1.0) Multi axis: jog_l("WRF", axes=["X", "Y"], speeds_list=[0.5, -0.3])

Category: Jog

Example

rbt.jog_l("WRF", "X", speed=0.5, duration=1.0)

wait_motion(timeout: float = 10.0, **kwargs: Any) -> bool abstractmethod async

Block until the robot has stopped moving or timeout expires.

Category: Synchronization

Example

rbt.wait_motion()

wait_command(command_index: int, timeout: float = 10.0) -> bool abstractmethod async

Block until a specific command index has completed.

Category: Synchronization

Example

rbt.wait_command()

wait_status(predicate: Callable[[StatusBuffer], bool], timeout: float = 5.0) -> bool async

Block until predicate returns True for a status snapshot.

wait_checkpoint(label: str, timeout: float = 30.0) -> bool async

Block until a checkpoint with label is reached.

resume() -> int abstractmethod async

Re-enable the robot after an e-stop or disable.

Category: Control

Example

rbt.resume()

halt() -> int abstractmethod async

Immediate stop — halt all motion and disable.

Category: Control

Example

rbt.halt()

simulator(enabled: bool) -> int async

Enable or disable simulator mode.

Category: Control

Example

rbt.simulator(True)

is_simulator() -> bool async

Query whether simulator mode is active.

Category: Query

Example

active = rbt.is_simulator()

teleport(angles_deg: list[float], tool_positions: list[float] | None = None) -> int async

Instantly set joint angles and optional tool positions (simulator only).

Category: Control

Example

rbt.teleport([0, -90, 0, 0, 0, 0]) rbt.teleport([0, -90, 0, 0, 0, 0], tool_positions=[1.0])

freedrive(enabled: bool) -> int async

Enable or disable freedrive / teach mode.

is_freedrive() -> bool async

Query whether freedrive / teach mode is active.

angles() -> list[float] | None abstractmethod async

Current joint angles in degrees.

Category: Query

Example

angles = rbt.angles()

pose(frame: Frame = 'WRF') -> list[float] | None abstractmethod async

Current TCP pose as [x, y, z, rx, ry, rz] in mm and degrees.

Category: Query

Example

pose = rbt.pose()

joint_speeds() -> list[float] | None async

Current joint velocities.

Category: Query

Example

speeds = rbt.joint_speeds()

io() -> list[int] | None async

Digital I/O state.

Category: Query

Example

io = rbt.io()

status() -> object | None async

Aggregate status snapshot.

Category: Query

Example

status = rbt.status()

queue() -> list[str] | None async

Queued command list.

Category: Query

Example

queue = rbt.queue()

tools() -> ToolResult | None async

Current tool and available tools.

Category: Query

Example

tools = rbt.tools()

activity() -> ActivityResult | None async

What the robot is currently doing.

Returns state (idle/executing/error), current command name, parameters, and error description if applicable.

Category: Query

Example

act = rbt.activity()

reachable() -> object | None async

Remaining freedom of movement per joint/axis before hitting limits.

Category: Query

Example

en = rbt.reachable()

error() -> object | None async

Current error state, or None if no error.

Category: Query

Example

err = rbt.error()

profile() -> str | None async

Current motion profile name.

Category: Query

Example

profile = rbt.profile()

tcp_speed() -> float | None async

TCP linear velocity in mm/s.

Category: Query

Example

speed = rbt.tcp_speed()

connect_hardware(port_str: str) -> int async

Connect to robot hardware via serial port.

Category: Configuration

Example

rbt.connect_hardware("/dev/ttyUSB0")

select_profile(profile: str) -> int async

Set the motion profile (e.g. "TOPPRA").

Category: Configuration

Example

rbt.select_profile("TOPPRA")

select_tool(tool_name: str, variant_key: str = '') -> int async

Set the active end-effector tool on the controller.

Category: Configuration

Example

rbt.select_tool("PNEUMATIC")

set_tcp_offset(x: float = 0, y: float = 0, z: float = 0) -> int async

Set TCP offset in mm, composed on top of the current tool transform.

The offset shifts the effective TCP point in the tool's local frame. Subsequent motion (especially TRF relative moves) will use the new TCP. Call with (0, 0, 0) to reset. Changing tools resets the offset.

Category: Configuration

Example

rbt.set_tcp_offset(0, 0, -190)

tcp_offset() -> list[float] async

Query current TCP offset in mm [x, y, z].

Category: Configuration

Example

offset = rbt.tcp_offset()

write_io(index: int, value: int) -> int async

Set digital output by logical index (0 = first output pin).

Category: I/O

Example

rbt.write_io(0, 1) # Set first output HIGH

tool_action(tool_key: str, action: str, params: list[Any] | None = None, *, wait: bool = False, timeout: float = 10.0) -> int async

Invoke a tool-specific action by key.

tool_key: identifier of the attached tool (e.g. "ELECTRIC"). action: action name understood by the tool (e.g. "calibrate", "move"). params: optional positional parameters for the action.

Category: I/O

Example

rbt.tool_action("ELECTRIC", "calibrate")

reset() -> int async

Reset controller state.

Category: Control

Example

rbt.reset()

checkpoint(label: str) -> int async

Insert a checkpoint marker in the command queue.

Category: Synchronization

Example

rbt.checkpoint("pick_done")

delay(seconds: float) -> int async

Insert a non-blocking delay in the command queue.

Category: Synchronization

Example

rbt.delay(1.0)

DryRunClient

waldoctl.DryRunClient

Bases: Protocol

Offline motion client for path preview / dry-run simulation.

Concrete implementations run the real command pipeline against a simulated controller state without hardware. Each motion method returns a DryRunResult containing the TCP trajectory and final joint state.

Required methods: home(), move_j(), move_l(), angles(), pose(), flush().

Joint Configuration

waldoctl.JointsSpec(count: int, names: tuple[str, ...], limits: JointLimits, home: HomePosition) dataclass

Complete joint configuration for a robot.

All array properties have their first dimension equal to count.

count: int instance-attribute

Number of actuated joints.

names: tuple[str, ...] instance-attribute

Per-joint display names, length == count.

limits: JointLimits instance-attribute

Position and kinodynamic limits for all joints.

home: HomePosition instance-attribute

Home / standby position.

waldoctl.JointLimits(position: PositionLimits, hard: KinodynamicLimits, jog: KinodynamicLimits) dataclass

All joint limits — position and kinodynamic.

position: PositionLimits instance-attribute

Position limits in degrees and radians.

hard: KinodynamicLimits instance-attribute

Hardware kinodynamic limits (maximum capability).

jog: KinodynamicLimits instance-attribute

Jog kinodynamic limits (reduced for manual operation).

waldoctl.PositionLimits(deg: NDArray[np.float64], rad: NDArray[np.float64]) dataclass

Joint position limits in multiple unit systems.

All arrays have shape (num_joints, 2) where columns are [lower, upper].

deg: NDArray[np.float64] instance-attribute

(N, 2) — position limits in degrees.

rad: NDArray[np.float64] instance-attribute

(N, 2) — position limits in radians.

waldoctl.KinodynamicLimits(velocity: NDArray[np.float64], acceleration: NDArray[np.float64], jerk: NDArray[np.float64] | None = None) dataclass

Per-joint velocity, acceleration, and jerk limits.

All arrays have shape (num_joints,) in SI units (rad/s family).

velocity: NDArray[np.float64] instance-attribute

(N,) — max joint velocities in rad/s.

acceleration: NDArray[np.float64] instance-attribute

(N,) — max joint accelerations in rad/s².

jerk: NDArray[np.float64] | None = None class-attribute instance-attribute

(N,) — max joint jerks in rad/s³, or None.

waldoctl.HomePosition(deg: NDArray[np.float64], rad: NDArray[np.float64]) dataclass

Home / standby position in multiple unit systems.

All arrays have shape (num_joints,).

deg: NDArray[np.float64] instance-attribute

(N,) — home position in degrees.

rad: NDArray[np.float64] instance-attribute

(N,) — home position in radians.

waldoctl.CartesianKinodynamicLimits(velocity: LinearAngularLimits, acceleration: LinearAngularLimits) dataclass

Cartesian velocity and acceleration limits for jog mode.

velocity: LinearAngularLimits instance-attribute

Max Cartesian velocity (linear m/s, angular rad/s).

acceleration: LinearAngularLimits instance-attribute

Max Cartesian acceleration (linear m/s², angular rad/s²).

waldoctl.LinearAngularLimits(linear: float, angular: float) dataclass

Paired linear and angular limit values.

linear: float instance-attribute

Linear limit — m/s (velocity) or m/s² (acceleration).

angular: float instance-attribute

Angular limit — rad/s (velocity) or rad/s² (acceleration).

Results

waldoctl.IKResult

Bases: Protocol

Result of an inverse kinematics solve.

q: NDArray[np.float64] instance-attribute

Joint angles in radians.

success: bool instance-attribute

Whether the solver converged within tolerance.

violations: str | None instance-attribute

Description of limit violations, or None.

waldoctl.DryRunResult

Bases: Protocol

Result from a dry-run motion command (path preview).

tcp_poses: NDArray[np.float64] instance-attribute

(N, 6) — TCP trajectory [x, y, z, rx, ry, rz] in meters + radians.

end_joints_rad: NDArray[np.float64] instance-attribute

(num_joints,) — final joint angles in radians.

duration: float instance-attribute

Trajectory duration in seconds.

error: object | None instance-attribute

Structured error (e.g. RobotError), or None on success.

valid: NDArray[np.bool_] | None instance-attribute

(N,) per-pose IK validity; None means all poses are valid.

joint_trajectory_rad: NDArray[np.float64] | None instance-attribute

(N, num_joints) — full joint trajectory in radians, aligned with tcp_poses rows. None if unavailable.

waldoctl.IKResultData(q: NDArray[np.float64], success: bool, violations: str | None = None) dataclass

Concrete IKResult for use in tests and adapters.

waldoctl.DryRunResultData(tcp_poses: NDArray[np.float64], end_joints_rad: NDArray[np.float64], duration: float, error: object | None = None, valid: NDArray[np.bool_] | None = None, joint_trajectory_rad: NDArray[np.float64] | None = None) dataclass

Concrete DryRunResult for use in tests and adapters.

Status

waldoctl.StatusBuffer

Bases: Protocol

Status snapshot yielded by status_stream_shared().

Each field is a numpy array for zero-copy access in the hot path.

pose: np.ndarray instance-attribute

(16,) float64 — flattened 4x4 homogeneous transform.

angles: np.ndarray instance-attribute

(N,) float64 — joint angles in degrees.

speeds: np.ndarray instance-attribute

(N,) float64 — joint velocities in rad/s.

io: np.ndarray instance-attribute

(5,) int32 — [in1, in2, out1, out2, estop].

tool_status: ToolStatus instance-attribute

Universal EOAT status (key, state, positions, etc.).

joint_en: np.ndarray instance-attribute

(12,) int32 — joint enable envelope.

cart_en: dict[str, np.ndarray] instance-attribute

Frame name -> (12,) int32 Cartesian enable envelope.

action_current: str instance-attribute

Currently executing action name.

action_params: str instance-attribute

Brief serialization of current action parameters.

action_state: ActionState instance-attribute

State of the current action.

executing_index: int instance-attribute

Index of the command currently being executed (-1 if idle).

completed_index: int instance-attribute

Index of the last completed command (-1 if none).

last_checkpoint: str instance-attribute

Label of the last checkpoint reached (empty if none).

tcp_speed: float instance-attribute

TCP linear velocity in mm/s.

simulator_active: bool instance-attribute

Whether the controller is in simulator mode.

waldoctl.PingResult(hardware_connected: bool) dataclass

Result of a connectivity check.

hardware_connected: bool instance-attribute

Whether the controller has a live link to robot hardware (serial, socket, CAN, PLC, etc.).

waldoctl.ToolResult(tool: str, available: list[str]) dataclass

Result of a tool query.

tool: str instance-attribute

Currently active tool name.

available: list[str] instance-attribute

All available tool names.

waldoctl.ActionState

Bases: IntEnum

State of the currently executing action on the controller.

Tools

waldoctl.ToolSpec(*, key: str, display_name: str, tool_type: ToolType, tcp_origin: tuple[float, float, float], tcp_rpy: tuple[float, float, float], description: str = '', meshes: tuple[MeshSpec, ...] = (), motions: tuple[PartMotion, ...] = (), variants: tuple[ToolVariant, ...] = (), activation_type: ActivationType = ActivationType.PROGRESSIVE, action_l_labels: tuple[str, str] | None = None, action_l_icons: tuple[str, str] | None = None, action_l_mode: ToggleMode = ToggleMode.TOGGLE, adjust_step: int | None = None, adjust_labels: tuple[str, str] | None = None, adjust_icons: tuple[str, str] | None = None, action_r_labels: tuple[str, str] | None = None, action_r_icons: tuple[str, str] | None = None, action_r_mode: ToggleMode = ToggleMode.TRIGGER)

Bases: ABC

Base contract every tool must satisfy.

key is unique per tool instance (e.g. "pneumatic_left"). tool_type determines which GUI panel category the tool belongs to.

All tool configuration is immutable — fields are stored privately and exposed via read-only properties. Action methods (e.g. toggle) are abstract — backends provide concrete implementations.

key: str property

Unique instance identifier.

display_name: str property

Human-readable name for UI display.

tool_type: ToolType property

GUI category — determines which panel (if any) is shown.

tcp_origin: tuple[float, float, float] property

(x, y, z) translation from flange to TCP in meters.

tcp_rpy: tuple[float, float, float] property

(roll, pitch, yaw) orientation from flange to TCP in radians.

activation_type: ActivationType property

How the tool is activated — binary (on/off) or progressive (continuous).

description: str property

Short description of the tool.

meshes: tuple[MeshSpec, ...] property

Mesh descriptors for 3D visualization.

motions: tuple[PartMotion, ...] property

Physical motion descriptors for movable tool parts.

variants: tuple[ToolVariant, ...] property

Named mesh/motion variants (e.g. different jaw sets).

action_l_labels: tuple[str, str] | None property

(off_label, on_label) tooltip text for the left action button.

action_l_icons: tuple[str, str] | None property

(off_icon, on_icon) Material Icon names for the left action button.

action_l_mode: ToggleMode property

How the left action button behaves — stateful on/off or one-shot trigger.

adjust_step: int | None property

Step size for the +/- adjust buttons, or None if not supported.

adjust_labels: tuple[str, str] | None property

(decrease_label, increase_label) tooltip text for adjust buttons.

adjust_icons: tuple[str, str] | None property

(decrease_icon, increase_icon) Material Icon names for adjust buttons.

action_r_labels: tuple[str, str] | None property

(off_label, on_label) tooltip text for the right action button.

action_r_icons: tuple[str, str] | None property

(off_icon, on_icon) Material Icon names for the right action button.

action_r_mode: ToggleMode property

How the right action button behaves — stateful on/off or one-shot trigger.

channel_descriptors: tuple[ChannelDescriptor, ...] property

Descriptors for tool-specific process data channels.

action_l(engaged: bool) -> None async

Left action button handler.

Override in subclasses to define tool-specific behavior.

action_r(engaged: bool) -> None async

Right action button handler.

Override in subclasses to define tool-specific behavior.

status() -> ToolStatus async

Query current tool status from the controller.

Returns the live tool status (state, engaged, positions, channels). Only works on client-bound tools — raises RuntimeError if unbound.

waldoctl.ToolsSpec

Bases: ABC

Collection of available tools for a robot.

Supports membership testing by ToolType (category) or str (key).

available: tuple[ToolSpec, ...] abstractmethod property

All available tool specifications, ordered for display.

default: ToolSpec abstractmethod property

Default tool (typically bare flange / "NONE").

__getitem__(key: str) -> ToolSpec abstractmethod

Look up a tool by its key. Raises KeyError if not found.

__contains__(item: object) -> bool abstractmethod

Test membership by ToolType (any tool of that category?) or str (specific key exists?).

by_type(tool_type: ToolType) -> tuple[ToolSpec, ...] abstractmethod

Return all tools matching the given category.

waldoctl.GripperTool(**kwargs: Any)

Bases: ToolSpec

Base for all grippers.

All grippers support set_position() as the universal control method. Position is normalized: 0.0 = fully open, 1.0 = fully closed.

Action methods are abstract — backends provide concrete implementations.

gripper_type: GripperType abstractmethod property

Gripper sub-type.

set_position(position: float, **kwargs: float | int) -> int abstractmethod async

Set gripper position. 0.0 = fully open, 1.0 = fully closed.

Category: Tool

Example

rbt.tool.set_position(0.5)

calibrate(**kwargs: object) -> int async

Calibrate the gripper. Not all grippers support this.

Category: Tool

Example

rbt.tool.calibrate()

is_open(position: float) -> bool

Infer open/closed from normalized position. True = open.

action_l(engaged: bool) -> None async

Left action: open if engaged, close if not.

open(**kwargs: float | int) -> int abstractmethod async

Open the gripper.

Category: Tool

Example

rbt.tool.open()

close(**kwargs: float | int) -> int abstractmethod async

Close the gripper.

Category: Tool

Example

rbt.tool.close()

waldoctl.PneumaticGripperTool(*, io_port: int, **kwargs: Any)

Bases: GripperTool

Pneumatic gripper — binary open/close.

Action methods are abstract — backends provide concrete implementations.

io_port: int property

Digital I/O port number for open/close control.

waldoctl.ElectricGripperTool(*, position_range: tuple[float, float], speed_range: tuple[float, float], current_range: tuple[int, int], **kwargs: Any)

Bases: GripperTool

Electric gripper — continuous position with speed and current control.

Action methods and computed properties (adjust_step, channel_descriptors) are abstract — backends provide concrete implementations.

position_range: tuple[float, float] property

(min, max) position range (normalized 0..1).

speed_range: tuple[float, float] property

(min, max) speed range (normalized 0..1).

current_range: tuple[int, int] property

(min, max) current range in mA.

waldoctl.ToolType

Bases: Enum

Tool categories the web commander has GUI support for.

NONE = 'none' class-attribute instance-attribute

Bare flange or passive tool — TCP offset + 3D visual only, no panel.

GRIPPER = 'gripper' class-attribute instance-attribute

Dedicated gripper control panel.

waldoctl.GripperType

Bases: Enum

Gripper sub-types — each gets different UI controls.

waldoctl.ActivationType

Bases: Enum

How a tool is activated / controlled.

On/off only — no intermediate position feedback from hardware.

Tools with motion descriptors need estimated_speed fields so the simulator can animate transitions.

PROGRESSIVE: Continuous position control with real-time position feedback.

waldoctl.ToggleMode

Bases: Enum

How a tool's quick-action toggle behaves on the control panel.

TOGGLE = 'toggle' class-attribute instance-attribute

Stateful on/off (grippers open/close, vacuum on/off).

TRIGGER = 'trigger' class-attribute instance-attribute

One-shot cycle start (dispensers, welders).

waldoctl.ToolState

Bases: IntEnum

State of an end-of-arm tool.

waldoctl.ToolStatus(key: str = 'NONE', state: ToolState = ToolState.OFF, engaged: bool = False, part_detected: bool = False, fault_code: int = 0, positions: tuple[float, ...] = (), channels: tuple[float, ...] = ()) dataclass

Universal end-of-arm tool status.

Populated by the controller at the status broadcast rate (50 Hz). Consumers combine positions[i] with ToolSpec.motions[i] to reconstruct the physical state of each DOF without knowing the tool type. Tool-specific process data is in channels, described by the tool's channel_descriptors.

key: str = 'NONE' class-attribute instance-attribute

Attached tool key.

state: ToolState = ToolState.OFF class-attribute instance-attribute

Tool operational state.

engaged: bool = False class-attribute instance-attribute

Actively doing work (welding, gripping, dispensing).

part_detected: bool = False class-attribute instance-attribute

EOAT part/object presence confirmed.

fault_code: int = 0 class-attribute instance-attribute

0=no fault, nonzero=tool-specific error.

positions: tuple[float, ...] = () class-attribute instance-attribute

DOF positions 0..1, one per PartMotion.

channels: tuple[float, ...] = () class-attribute instance-attribute

Tool-specific process data, described by ChannelDescriptor.

waldoctl.ToolVariant(key: str, display_name: str, meshes: tuple[MeshSpec, ...] = (), motions: tuple[PartMotion, ...] = (), tcp_origin: tuple[float, float, float] | None = None, tcp_rpy: tuple[float, float, float] | None = None) dataclass

Named variant that replaces a tool's meshes and motions.

Each variant is self-contained — it provides a complete set of meshes and motions, so the scene swaps them wholesale without merge logic.

key: str instance-attribute

Unique identifier within the tool (e.g. "finger", "pinch").

display_name: str instance-attribute

Human-readable name for the UI dropdown.

meshes: tuple[MeshSpec, ...] = () class-attribute instance-attribute

Complete mesh set for this variant.

motions: tuple[PartMotion, ...] = () class-attribute instance-attribute

Complete motion descriptors for this variant.

tcp_origin: tuple[float, float, float] | None = None class-attribute instance-attribute

(x, y, z) TCP translation in meters, or None to use tool default.

tcp_rpy: tuple[float, float, float] | None = None class-attribute instance-attribute

(roll, pitch, yaw) TCP orientation in radians, or None to use tool default.

waldoctl.MeshSpec(file: str, origin: tuple[float, float, float] = (0.0, 0.0, 0.0), rpy: tuple[float, float, float] = (0.0, 0.0, 0.0), role: MeshRole = MeshRole.BODY) dataclass

Immutable descriptor for a single STL mesh in a tool assembly.

file: str instance-attribute

Filename of the STL mesh.

origin: tuple[float, float, float] = (0.0, 0.0, 0.0) class-attribute instance-attribute

(x, y, z) offset in meters.

rpy: tuple[float, float, float] = (0.0, 0.0, 0.0) class-attribute instance-attribute

(roll, pitch, yaw) orientation in radians.

role: MeshRole = MeshRole.BODY class-attribute instance-attribute

Which mesh group this belongs to.

waldoctl.MeshRole

Bases: Enum

Well-defined roles for tool mesh groups.

BODY = 'body' class-attribute instance-attribute

Static structural part.

JAW = 'jaw' class-attribute instance-attribute

Translating gripper jaw.

SPINDLE = 'spindle' class-attribute instance-attribute

Rotating part (drill bit, mill bit, etc.).

waldoctl.LinearMotion(role: MeshRole, axis: tuple[float, float, float], travel_m: float, symmetric: bool = True, estimated_speed_m_s: float | None = None, estimated_accel_m_s2: float | None = None) dataclass

Linear motion of tool parts (gripper jaws, press-fit rams).

role: MeshRole instance-attribute

Which mesh group moves.

axis: tuple[float, float, float] instance-attribute

Unit vector along which the motion occurs.

travel_m: float instance-attribute

Max displacement per side in meters.

symmetric: bool = True class-attribute instance-attribute

If True, paired parts (left/right) move in opposite directions.

estimated_speed_m_s: float | None = None class-attribute instance-attribute

Estimated travel speed in m/s (for binary-activation tools without position feedback).

estimated_accel_m_s2: float | None = None class-attribute instance-attribute

Estimated acceleration in m/s² (for binary-activation tools).

waldoctl.RotaryMotion(role: MeshRole, axis: tuple[float, float, float], travel_rad: float, symmetric: bool = True, estimated_speed_rad_s: float | None = None, estimated_accel_rad_s2: float | None = None) dataclass

Rotary motion of tool parts (spindle bits, drill chucks).

role: MeshRole instance-attribute

Which mesh group moves.

axis: tuple[float, float, float] instance-attribute

Unit vector for the rotation axis.

travel_rad: float instance-attribute

Max rotation in radians.

symmetric: bool = True class-attribute instance-attribute

If True, paired parts rotate in opposite directions.

estimated_speed_rad_s: float | None = None class-attribute instance-attribute

Estimated angular speed in rad/s (for binary-activation tools).

estimated_accel_rad_s2: float | None = None class-attribute instance-attribute

Estimated angular acceleration in rad/s² (for binary-activation tools).

waldoctl.ChannelDescriptor(name: str, unit: str, min: float = 0.0, max: float = 0.0) dataclass

Describes one process data channel reported by a tool.

The controller populates ToolStatus.channels positionally — index i in the channels tuple corresponds to channel_descriptors[i].

name: str instance-attribute

Human-readable name (e.g. "Force", "Current").

unit: str instance-attribute

SI unit symbol (e.g. "N", "mA", "bar").

min: float = 0.0 class-attribute instance-attribute

Minimum expected value (0 = auto-scale).

max: float = 0.0 class-attribute instance-attribute

Maximum expected value (0 = auto-scale).

Types

waldoctl.types.Frame = Union[Literal['WRF', 'TRF'], str] module-attribute

waldoctl.types.Axis = Literal['X', 'Y', 'Z', 'RX', 'RY', 'RZ'] module-attribute