src.robots package

Submodules

src.robots.ecm module

class src.robots.ecm.CameraPose(position, focal_point, viewup)[source]

Bases: object

focal_point: ndarray
position: ndarray
viewup: ndarray
class src.robots.ecm.ECM(robot_root='../urdfs/ecm', world_link='world', base_transform=None)[source]

Bases: UrdfRobot

Endoscope Camera Manipulator (ECM) robot with camera-pose helpers.

Extends UrdfRobot with:

  • An optional base_transform that maps the robot’s local FK frame into the world frame.

  • scope_camera_pose() / scope_stereo_camera_poses() for computing PyVista camera parameters directly from the ECM joint state.

  • from_camera_pose() class method to construct an ECM whose base transform is chosen so the scope tip matches a desired world pose.

Parameters:
  • robot_root (str | Path) – Directory containing ecm.urdf and meshes/.

  • world_link (str) – Name of the root link in the URDF tree.

  • base_transform (Optional[ndarray]) – Optional 4×4 transform from the robot base frame to the world frame. If None, identity is used.

base_transform: ndarray | None
classmethod from_camera_pose(camera_world_tf, robot_root='../urdfs/ecm', world_link='world', initial_q=None)[source]

Construct an ECM whose scope tip is placed at camera_world_tf.

Computes the required base_transform by inverting the FK at initial_q:

\[T_{\text{base}}^{\text{world}} = T_{\text{cam}}^{\text{world}} \cdot \bigl(T_{\text{FK}}(q_0)\bigr)^{-1}\]
Parameters:
  • camera_world_tf (ndarray) – 4×4 desired scope-tip pose in the world frame.

  • robot_root (str | Path) – Directory containing the ECM URDF and meshes.

  • world_link (str) – Name of the root link in the URDF tree.

  • initial_q (Optional[ndarray]) – (dof,) joint configuration at which the scope tip should coincide with camera_world_tf. Defaults to all-zeros.

Return type:

ECM

Returns:

ECM instance with base_transform set accordingly.

scope_camera_pose(theta=None, base_transform=None, optical_tilt_deg=0.0, focus_distance=0.2)[source]

Compute a monocular camera pose from the current ECM joint state.

The camera is placed at the scope tip with camera-frame convention tied to the scope frame: right \(+X\), up \(-Z\), forward \(+Y\). A tilt about local \(+X\) (optical tilt) rotates forward/up:

\[\begin{split}\hat{f} &= c\,\hat{y} + s\,\hat{z} \\ \hat{u} &= s\,\hat{y} - c\,\hat{z}\end{split}\]

where \(c = \cos(\alpha)\), \(s = \sin(\alpha)\), \(\alpha = \text{optical_tilt_deg}\).

Parameters:
  • theta (Union[ndarray, List[float], None]) – (dof,) joint configuration. Defaults to the stored state.

  • base_transform (Optional[ndarray]) – Optional base-to-world override.

  • optical_tilt_deg (float) – Optical tilt angle around the scope X axis (degrees). Typically 0° or 30° for 0°/30° scopes.

  • focus_distance (float) – Distance (metres) from the camera origin to the focal point along the viewing direction.

Return type:

CameraPose

Returns:

CameraPose with position, focal_point, and viewup vectors.

scope_stereo_camera_poses(theta=None, base_transform=None, optical_tilt_deg=0.0, baseline=0.008, focus_distance=0.2)[source]

Compute a parallel stereo camera pair from the current ECM joint state.

Left and right cameras are translated by \(\pm \text{baseline}/2\) along the local \(+X\) axis of the scope tip while sharing the same forward direction and viewup:

\[\begin{split}p_{\text{left}} &= p_{\text{center}} - \tfrac{d}{2}\,\hat{x} \\ p_{\text{right}} &= p_{\text{center}} + \tfrac{d}{2}\,\hat{x}\end{split}\]

where \(d\) is baseline.

Parameters:
  • theta (Union[ndarray, List[float], None]) – (dof,) joint configuration. Defaults to the stored state.

  • base_transform (Optional[ndarray]) – Optional base-to-world override.

  • optical_tilt_deg (float) – Optical tilt angle (degrees) applied before the stereo split.

  • baseline (float) – Stereo baseline (metres), i.e. inter-camera separation.

  • focus_distance (float) – Distance (metres) to the focal point along the shared viewing direction.

Return type:

Tuple[CameraPose, CameraPose]

Returns:

(left_pose, right_pose) — each a CameraPose.

tool_transform_world(theta=None, base_transform=None)[source]

Return the scope-tip (tool) pose in the world frame.

Applies the optional base_transform on top of the URDF tree FK:

\[T_{\text{tool}}^{\text{world}} = T_{\text{base}}^{\text{world}} \cdot T_{\text{FK}}(\theta)\]
Parameters:
  • theta (Union[ndarray, List[float], None]) – (dof,) joint configuration. Defaults to the current stored joint state.

  • base_transform (Optional[ndarray]) – Override for self.base_transform. If both are None, the FK result is returned unchanged.

Return type:

ndarray

Returns:

4×4 homogeneous scope-tip pose in the world frame.

src.robots.mtm module

class src.robots.mtm.MTM(robot_root='../urdfs/mtm', world_link='world')[source]

Bases: UrdfRobot

Master Tool Manipulator (MTM) robot.

Loads mtm.urdf from robot_root and uses ee_link as the end-effector link.

Parameters:
  • robot_root (str | Path) – Directory containing mtm.urdf and meshes/.

  • world_link (str) – Name of the root/world link in the URDF tree.

src.robots.phantom module

class src.robots.phantom.Phantom(robot_root='../urdfs/phantom_touch', world_link='base')[source]

Bases: UrdfRobot

Phantom Touch haptic device modelled as a passive robot.

Loads phantom_touch.urdf from robot_root and uses stylus_point as the end-effector link. The world link is set to 'base' to match the Phantom URDF convention.

Parameters:
  • robot_root (str | Path) – Directory containing phantom_touch.urdf and meshes/.

  • world_link (str) – Name of the root link in the URDF tree (default 'base').

src.robots.protocols module

class src.robots.protocols.JointStateLike(*args, **kwargs)[source]

Bases: Protocol

Minimal protocol for objects that expose a joint-angle sequence.

property joints: Sequence[float]
class src.robots.protocols.RobotTreeLike(*args, **kwargs)[source]

Bases: Protocol

Structural protocol for robots that expose a kinematic tree.

Used by link_transforms() and related FK helpers so they can operate on any compliant robot object without inheriting from a concrete base class.

property dof: int
expand_theta(theta=None)[source]
Return type:

Mapping[str, float]

get_child_joints(link)[source]
Return type:

Sequence[str]

get_joint(name)[source]
Return type:

JointInfo

get_theta()[source]
Return type:

ndarray

class src.robots.protocols.ToolKinematicsRobotLike(*args, **kwargs)[source]

Bases: RobotTreeLike, Protocol

Protocol for robots that can compute their own forward kinematics.

Used by tool_transform_world().

forward_kinematics(theta=None, link_name=None)[source]
Return type:

ndarray

class src.robots.protocols.VisualRobotLike(*args, **kwargs)[source]

Bases: RobotTreeLike, Protocol

Extended protocol for robots that also expose visual (mesh) information.

Used by visual_transforms() and the DvrkRealtimeViz viewer.

property active_joint_names: Sequence[str]
Return type:

Sequence[LinkVisual]

src.robots.psm module

class src.robots.psm.PSM(robot_root='../urdfs/psm', world_link='world')[source]

Bases: UrdfRobot

Patient Side Manipulator (PSM) robot.

Loads psm.urdf from robot_root, sets tool_yaw_link as the end-effector link, and uses the default active-joint selection (all non-fixed, non-mimic joints).

Parameters:
  • robot_root (str | Path) – Directory containing psm.urdf and meshes/.

  • world_link (str) – Name of the root/world link in the URDF tree.

src.robots.robot module

class src.robots.robot.JointInfo(name, joint_type, parent, child, origin_xyz, origin_rpy, axis, limit=None, mimic=None)[source]

Bases: object

Parsed representation of a single URDF joint.

name

Joint name from the URDF.

joint_type

One of 'revolute', 'prismatic', or 'fixed'.

parent

Name of the parent link.

child

Name of the child link.

origin_xyz

(3,) translation of the joint frame relative to the parent link frame (metres).

origin_rpy

(3,) roll-pitch-yaw orientation of the joint frame relative to the parent link frame (radians).

axis

(3,) joint motion axis expressed in the joint local frame.

limit

Optional joint position limits; None for fixed joints.

mimic

Optional mimic relationship; None for non-mimic joints.

axis: ndarray
child: str
joint_type: str
limit: JointLimit | None = None
mimic: Mimic | None = None
name: str
origin_rpy: ndarray
origin_xyz: ndarray
parent: str
class src.robots.robot.JointLimit(lower, upper)[source]

Bases: object

URDF joint position limits.

lower

Lower joint position limit (radians or metres).

upper

Upper joint position limit (radians or metres).

lower: float
upper: float
class src.robots.robot.LinkVisual(link_name, mesh_path, origin_xyz, origin_rpy)[source]

Bases: object

Path and local origin of a single visual mesh element for a URDF link.

Name of the parent link.

mesh_path

Absolute path to the mesh file (STL preferred over DAE).

origin_xyz

(3,) local translation of the visual in the link frame.

origin_rpy

(3,) local roll-pitch-yaw orientation of the visual in the link frame (radians).

link_name: str
mesh_path: str
origin_rpy: ndarray
origin_xyz: ndarray
class src.robots.robot.Mimic(joint, multiplier=1.0, offset=0.0)[source]

Bases: object

URDF <mimic> specification linking one joint to another.

The mimicking joint value is computed as:

\[q_{\text{mimic}} = \text{multiplier} \cdot q_{\text{source}} + \text{offset}\]
joint

Name of the source (master) joint.

multiplier

Linear gain applied to the source joint value.

offset

Constant offset added after scaling.

joint: str
multiplier: float = 1.0
offset: float = 0.0
class src.robots.robot.Robot(name, robot_root, base_link, tool_link, world_link='world')[source]

Bases: ABC

Base interface for dVRK robots (PSM, ECM, MTM).

Responsibilities: - store robot structure (links, joints, visuals) - manage joint state (theta) - provide metadata access

NOT responsible for: - forward kinematics - inverse kinematics - Jacobians - rendering

active_joint_names: List[str]
add_joint(joint, active=False)[source]
Return type:

None

Return type:

None

add_visual(visual)[source]
Return type:

None

abstractmethod build()[source]

Populate links, joints, visuals, and active_joint_names.

Return type:

None

build_kinematic_model()[source]
clamp_theta(theta)[source]

Return a copy of theta with each joint clamped to its URDF limits.

Joints without a <limit> tag are left unchanged.

Parameters:

theta (Union[ndarray, List[float]]) – (dof,) joint configuration to clamp.

Raises:

ValueError – If len(theta) != dof.

Return type:

ndarray

Returns:

(dof,) clamped joint configuration.

property dof: int
expand_theta(theta=None)[source]

Expand active-joint vector to a full joint dictionary including mimic joints.

Mimic joints are resolved iteratively using the formula:

\[q_{\text{mimic}} = \text{multiplier} \cdot q_{\text{source}} + \text{offset}\]

Revolute and prismatic joints not covered by active or mimic rules default to 0.

Parameters:

theta (Union[ndarray, List[float], None]) – (dof,) active-joint vector. Defaults to self.theta.

Raises:

ValueError – If len(theta) != dof.

Return type:

Dict[str, float]

Returns:

Dictionary mapping every non-fixed joint name to its float value.

finalize()[source]

Call after build(). Initializes joint state.

Return type:

None

forward_kinematics(theta=None, link_name=None)[source]
get_active_joints()[source]
Return type:

List[JointInfo]

get_child_joints(link)[source]
Return type:

List[str]

get_joint(name)[source]
Return type:

JointInfo

Return type:

List[LinkVisual]

get_theta()[source]

Return a copy of the current active joint vector.

Return type:

ndarray

joint_limits()[source]
Return type:

Dict[str, Tuple[float, float]]

property joint_names: List[str]
joints: Dict[str, JointInfo]
resolve_mesh_path(filename)[source]
Return type:

Path

set_theta(theta)[source]

Set the active joint vector, validating its size.

Parameters:

theta (Union[ndarray, List[float]]) – (dof,) joint configuration.

Raises:

ValueError – If len(theta) != dof.

Return type:

None

summary()[source]
Return type:

dict

visualize(theta=None, show_frames=False, alpha=1.0)[source]

Render this robot in a simple interactive viewer.

Parameters:
  • theta (ndarray | None) – Optional active-joint configuration, shape (dof,).

  • show_frames (bool) – Whether to draw joint frames.

  • alpha (float) – Robot mesh opacity in [0, 1].

Return type:

None

visuals: Dict[str, List[LinkVisual]]
zero_theta()[source]

Reset all active joints to zero and return the resulting vector.

Return type:

ndarray

src.robots.urdf_robot module

class src.robots.urdf_robot.UrdfRobot(*, name, robot_root, base_link, tool_link, urdf_filename, world_link='world')[source]

Bases: Robot

Concrete robot base class that builds itself from a URDF file.

On construction the URDF at robot_root / urdf_filename is parsed via parse_urdf(). Active joints are determined by _default_active_joint_names() (all non-fixed, non-mimic joints). The kinematic model is finalised automatically by calling finalize().

Subclasses only need to supply constructor keyword arguments; all heavy lifting is done here.

build()[source]

Populate links, joints, visuals, and active_joint_names.

Return type:

None

Module contents

class src.robots.CameraPose(position, focal_point, viewup)[source]

Bases: object

focal_point: ndarray
position: ndarray
viewup: ndarray
class src.robots.ECM(robot_root='../urdfs/ecm', world_link='world', base_transform=None)[source]

Bases: UrdfRobot

Endoscope Camera Manipulator (ECM) robot with camera-pose helpers.

Extends UrdfRobot with:

  • An optional base_transform that maps the robot’s local FK frame into the world frame.

  • scope_camera_pose() / scope_stereo_camera_poses() for computing PyVista camera parameters directly from the ECM joint state.

  • from_camera_pose() class method to construct an ECM whose base transform is chosen so the scope tip matches a desired world pose.

Parameters:
  • robot_root (str | Path) – Directory containing ecm.urdf and meshes/.

  • world_link (str) – Name of the root link in the URDF tree.

  • base_transform (Optional[ndarray]) – Optional 4×4 transform from the robot base frame to the world frame. If None, identity is used.

base_transform: ndarray | None
classmethod from_camera_pose(camera_world_tf, robot_root='../urdfs/ecm', world_link='world', initial_q=None)[source]

Construct an ECM whose scope tip is placed at camera_world_tf.

Computes the required base_transform by inverting the FK at initial_q:

\[T_{\text{base}}^{\text{world}} = T_{\text{cam}}^{\text{world}} \cdot \bigl(T_{\text{FK}}(q_0)\bigr)^{-1}\]
Parameters:
  • camera_world_tf (ndarray) – 4×4 desired scope-tip pose in the world frame.

  • robot_root (str | Path) – Directory containing the ECM URDF and meshes.

  • world_link (str) – Name of the root link in the URDF tree.

  • initial_q (Optional[ndarray]) – (dof,) joint configuration at which the scope tip should coincide with camera_world_tf. Defaults to all-zeros.

Return type:

ECM

Returns:

ECM instance with base_transform set accordingly.

scope_camera_pose(theta=None, base_transform=None, optical_tilt_deg=0.0, focus_distance=0.2)[source]

Compute a monocular camera pose from the current ECM joint state.

The camera is placed at the scope tip with camera-frame convention tied to the scope frame: right \(+X\), up \(-Z\), forward \(+Y\). A tilt about local \(+X\) (optical tilt) rotates forward/up:

\[\begin{split}\hat{f} &= c\,\hat{y} + s\,\hat{z} \\ \hat{u} &= s\,\hat{y} - c\,\hat{z}\end{split}\]

where \(c = \cos(\alpha)\), \(s = \sin(\alpha)\), \(\alpha = \text{optical_tilt_deg}\).

Parameters:
  • theta (Union[ndarray, List[float], None]) – (dof,) joint configuration. Defaults to the stored state.

  • base_transform (Optional[ndarray]) – Optional base-to-world override.

  • optical_tilt_deg (float) – Optical tilt angle around the scope X axis (degrees). Typically 0° or 30° for 0°/30° scopes.

  • focus_distance (float) – Distance (metres) from the camera origin to the focal point along the viewing direction.

Return type:

CameraPose

Returns:

CameraPose with position, focal_point, and viewup vectors.

scope_stereo_camera_poses(theta=None, base_transform=None, optical_tilt_deg=0.0, baseline=0.008, focus_distance=0.2)[source]

Compute a parallel stereo camera pair from the current ECM joint state.

Left and right cameras are translated by \(\pm \text{baseline}/2\) along the local \(+X\) axis of the scope tip while sharing the same forward direction and viewup:

\[\begin{split}p_{\text{left}} &= p_{\text{center}} - \tfrac{d}{2}\,\hat{x} \\ p_{\text{right}} &= p_{\text{center}} + \tfrac{d}{2}\,\hat{x}\end{split}\]

where \(d\) is baseline.

Parameters:
  • theta (Union[ndarray, List[float], None]) – (dof,) joint configuration. Defaults to the stored state.

  • base_transform (Optional[ndarray]) – Optional base-to-world override.

  • optical_tilt_deg (float) – Optical tilt angle (degrees) applied before the stereo split.

  • baseline (float) – Stereo baseline (metres), i.e. inter-camera separation.

  • focus_distance (float) – Distance (metres) to the focal point along the shared viewing direction.

Return type:

Tuple[CameraPose, CameraPose]

Returns:

(left_pose, right_pose) — each a CameraPose.

tool_transform_world(theta=None, base_transform=None)[source]

Return the scope-tip (tool) pose in the world frame.

Applies the optional base_transform on top of the URDF tree FK:

\[T_{\text{tool}}^{\text{world}} = T_{\text{base}}^{\text{world}} \cdot T_{\text{FK}}(\theta)\]
Parameters:
  • theta (Union[ndarray, List[float], None]) – (dof,) joint configuration. Defaults to the current stored joint state.

  • base_transform (Optional[ndarray]) – Override for self.base_transform. If both are None, the FK result is returned unchanged.

Return type:

ndarray

Returns:

4×4 homogeneous scope-tip pose in the world frame.

class src.robots.JointInfo(name, joint_type, parent, child, origin_xyz, origin_rpy, axis, limit=None, mimic=None)[source]

Bases: object

Parsed representation of a single URDF joint.

name

Joint name from the URDF.

joint_type

One of 'revolute', 'prismatic', or 'fixed'.

parent

Name of the parent link.

child

Name of the child link.

origin_xyz

(3,) translation of the joint frame relative to the parent link frame (metres).

origin_rpy

(3,) roll-pitch-yaw orientation of the joint frame relative to the parent link frame (radians).

axis

(3,) joint motion axis expressed in the joint local frame.

limit

Optional joint position limits; None for fixed joints.

mimic

Optional mimic relationship; None for non-mimic joints.

axis: ndarray
child: str
joint_type: str
limit: JointLimit | None = None
mimic: Mimic | None = None
name: str
origin_rpy: ndarray
origin_xyz: ndarray
parent: str
class src.robots.JointLimit(lower, upper)[source]

Bases: object

URDF joint position limits.

lower

Lower joint position limit (radians or metres).

upper

Upper joint position limit (radians or metres).

lower: float
upper: float
class src.robots.JointStateLike(*args, **kwargs)[source]

Bases: Protocol

Minimal protocol for objects that expose a joint-angle sequence.

property joints: Sequence[float]
class src.robots.LinkVisual(link_name, mesh_path, origin_xyz, origin_rpy)[source]

Bases: object

Path and local origin of a single visual mesh element for a URDF link.

Name of the parent link.

mesh_path

Absolute path to the mesh file (STL preferred over DAE).

origin_xyz

(3,) local translation of the visual in the link frame.

origin_rpy

(3,) local roll-pitch-yaw orientation of the visual in the link frame (radians).

link_name: str
mesh_path: str
origin_rpy: ndarray
origin_xyz: ndarray
class src.robots.MTM(robot_root='../urdfs/mtm', world_link='world')[source]

Bases: UrdfRobot

Master Tool Manipulator (MTM) robot.

Loads mtm.urdf from robot_root and uses ee_link as the end-effector link.

Parameters:
  • robot_root (str | Path) – Directory containing mtm.urdf and meshes/.

  • world_link (str) – Name of the root/world link in the URDF tree.

class src.robots.Mimic(joint, multiplier=1.0, offset=0.0)[source]

Bases: object

URDF <mimic> specification linking one joint to another.

The mimicking joint value is computed as:

\[q_{\text{mimic}} = \text{multiplier} \cdot q_{\text{source}} + \text{offset}\]
joint

Name of the source (master) joint.

multiplier

Linear gain applied to the source joint value.

offset

Constant offset added after scaling.

joint: str
multiplier: float = 1.0
offset: float = 0.0
class src.robots.PSM(robot_root='../urdfs/psm', world_link='world')[source]

Bases: UrdfRobot

Patient Side Manipulator (PSM) robot.

Loads psm.urdf from robot_root, sets tool_yaw_link as the end-effector link, and uses the default active-joint selection (all non-fixed, non-mimic joints).

Parameters:
  • robot_root (str | Path) – Directory containing psm.urdf and meshes/.

  • world_link (str) – Name of the root/world link in the URDF tree.

class src.robots.Phantom(robot_root='../urdfs/phantom_touch', world_link='base')[source]

Bases: UrdfRobot

Phantom Touch haptic device modelled as a passive robot.

Loads phantom_touch.urdf from robot_root and uses stylus_point as the end-effector link. The world link is set to 'base' to match the Phantom URDF convention.

Parameters:
  • robot_root (str | Path) – Directory containing phantom_touch.urdf and meshes/.

  • world_link (str) – Name of the root link in the URDF tree (default 'base').

class src.robots.Robot(name, robot_root, base_link, tool_link, world_link='world')[source]

Bases: ABC

Base interface for dVRK robots (PSM, ECM, MTM).

Responsibilities: - store robot structure (links, joints, visuals) - manage joint state (theta) - provide metadata access

NOT responsible for: - forward kinematics - inverse kinematics - Jacobians - rendering

active_joint_names: List[str]
add_joint(joint, active=False)[source]
Return type:

None

Return type:

None

add_visual(visual)[source]
Return type:

None

abstractmethod build()[source]

Populate links, joints, visuals, and active_joint_names.

Return type:

None

build_kinematic_model()[source]
clamp_theta(theta)[source]

Return a copy of theta with each joint clamped to its URDF limits.

Joints without a <limit> tag are left unchanged.

Parameters:

theta (Union[ndarray, List[float]]) – (dof,) joint configuration to clamp.

Raises:

ValueError – If len(theta) != dof.

Return type:

ndarray

Returns:

(dof,) clamped joint configuration.

property dof: int
expand_theta(theta=None)[source]

Expand active-joint vector to a full joint dictionary including mimic joints.

Mimic joints are resolved iteratively using the formula:

\[q_{\text{mimic}} = \text{multiplier} \cdot q_{\text{source}} + \text{offset}\]

Revolute and prismatic joints not covered by active or mimic rules default to 0.

Parameters:

theta (Union[ndarray, List[float], None]) – (dof,) active-joint vector. Defaults to self.theta.

Raises:

ValueError – If len(theta) != dof.

Return type:

Dict[str, float]

Returns:

Dictionary mapping every non-fixed joint name to its float value.

finalize()[source]

Call after build(). Initializes joint state.

Return type:

None

forward_kinematics(theta=None, link_name=None)[source]
get_active_joints()[source]
Return type:

List[JointInfo]

get_child_joints(link)[source]
Return type:

List[str]

get_joint(name)[source]
Return type:

JointInfo

Return type:

List[LinkVisual]

get_theta()[source]

Return a copy of the current active joint vector.

Return type:

ndarray

joint_limits()[source]
Return type:

Dict[str, Tuple[float, float]]

property joint_names: List[str]
joints: Dict[str, JointInfo]
resolve_mesh_path(filename)[source]
Return type:

Path

set_theta(theta)[source]

Set the active joint vector, validating its size.

Parameters:

theta (Union[ndarray, List[float]]) – (dof,) joint configuration.

Raises:

ValueError – If len(theta) != dof.

Return type:

None

summary()[source]
Return type:

dict

visualize(theta=None, show_frames=False, alpha=1.0)[source]

Render this robot in a simple interactive viewer.

Parameters:
  • theta (ndarray | None) – Optional active-joint configuration, shape (dof,).

  • show_frames (bool) – Whether to draw joint frames.

  • alpha (float) – Robot mesh opacity in [0, 1].

Return type:

None

visuals: Dict[str, List[LinkVisual]]
zero_theta()[source]

Reset all active joints to zero and return the resulting vector.

Return type:

ndarray

class src.robots.RobotTreeLike(*args, **kwargs)[source]

Bases: Protocol

Structural protocol for robots that expose a kinematic tree.

Used by link_transforms() and related FK helpers so they can operate on any compliant robot object without inheriting from a concrete base class.

property dof: int
expand_theta(theta=None)[source]
Return type:

Mapping[str, float]

get_child_joints(link)[source]
Return type:

Sequence[str]

get_joint(name)[source]
Return type:

JointInfo

get_theta()[source]
Return type:

ndarray

class src.robots.ToolKinematicsRobotLike(*args, **kwargs)[source]

Bases: RobotTreeLike, Protocol

Protocol for robots that can compute their own forward kinematics.

Used by tool_transform_world().

forward_kinematics(theta=None, link_name=None)[source]
Return type:

ndarray

class src.robots.UrdfRobot(*, name, robot_root, base_link, tool_link, urdf_filename, world_link='world')[source]

Bases: Robot

Concrete robot base class that builds itself from a URDF file.

On construction the URDF at robot_root / urdf_filename is parsed via parse_urdf(). Active joints are determined by _default_active_joint_names() (all non-fixed, non-mimic joints). The kinematic model is finalised automatically by calling finalize().

Subclasses only need to supply constructor keyword arguments; all heavy lifting is done here.

build()[source]

Populate links, joints, visuals, and active_joint_names.

Return type:

None

class src.robots.VisualRobotLike(*args, **kwargs)[source]

Bases: RobotTreeLike, Protocol

Extended protocol for robots that also expose visual (mesh) information.

Used by visual_transforms() and the DvrkRealtimeViz viewer.

property active_joint_names: Sequence[str]
Return type:

Sequence[LinkVisual]