Skip to content

キネマティクス API¤

このページでは、Robopyのキネマティクス(運動学)モジュールに関連するAPIを説明します。

概要¤

robopy.kinematics モジュールは、5自由度ロボットアームのForward Kinematics (FK) と Inverse Kinematics (IK) を提供します。

  • FK: 関節角度 → エンドエフェクタ姿勢(位置 + 姿勢)
  • IK: エンドエフェクタ姿勢 → 関節角度(数値解法)

外部依存は numpy のみ です。scipy は不要です。

エンドエフェクタ姿勢¤

EEPose dataclass ¤

EEPose(x: float, y: float, z: float, pitch: float, roll: float)

5-DOF end-effector pose.

ATTRIBUTE DESCRIPTION
x

End-effector X position in meters.

TYPE: float

y

End-effector Y position in meters.

TYPE: float

z

End-effector Z position in meters.

TYPE: float

pitch

Rotation about the Y-axis in radians.

TYPE: float

roll

Rotation about the X-axis in radians.

TYPE: float

METHOD DESCRIPTION
to_array

Return (5,) numpy array [x, y, z, pitch, roll].

from_array

Construct from a (5,) array.

to_array ¤

to_array() -> NDArray[float64]

Return (5,) numpy array [x, y, z, pitch, roll].

Source code in src/robopy/kinematics/ee_pose.py
def to_array(self) -> NDArray[np.float64]:
    """Return (5,) numpy array [x, y, z, pitch, roll]."""
    return np.array([self.x, self.y, self.z, self.pitch, self.roll])

from_array classmethod ¤

from_array(arr: NDArray[float64]) -> EEPose

Construct from a (5,) array.

Source code in src/robopy/kinematics/ee_pose.py
@classmethod
def from_array(cls, arr: NDArray[np.float64]) -> "EEPose":
    """Construct from a (5,) array."""
    if len(arr) != 5:
        raise ValueError(f"Expected 5 elements, got {len(arr)}")
    return cls(
        x=float(arr[0]),
        y=float(arr[1]),
        z=float(arr[2]),
        pitch=float(arr[3]),
        roll=float(arr[4]),
    )

キネマティックチェーン¤

RevoluteJoint dataclass ¤

RevoluteJoint(name: str, parent_to_joint: NDArray[float64], axis: str, lower_limit_rad: float, upper_limit_rad: float)

A single revolute joint in the kinematic chain.

ATTRIBUTE DESCRIPTION
name

Joint name (e.g., "shoulder_pan").

TYPE: str

parent_to_joint

4x4 static transform from parent frame to this joint's rotation center (before any rotation is applied).

TYPE: NDArray[float64]

axis

Rotation axis as a string: "x", "y", or "z".

TYPE: str

lower_limit_rad

Minimum joint angle in radians.

TYPE: float

upper_limit_rad

Maximum joint angle in radians.

TYPE: float

KinematicChain ¤

KinematicChain(joints: List[RevoluteJoint], ee_fixed_transform: NDArray[float64])

Forward kinematics and numerical Jacobian for a serial revolute chain.

The chain is a sequence of :class:RevoluteJoint objects followed by a fixed transform from the last joint frame to the end-effector frame.

METHOD DESCRIPTION
forward_kinematics_matrix

Compute the 4x4 homogeneous transform from base to end-effector.

forward_kinematics

Compute end-effector pose as (x, y, z, pitch, roll).

jacobian

Numerical Jacobian of the 5-DOF pose w.r.t. joint angles.

clamp_to_limits

Clamp joint angles to their limits.

ATTRIBUTE DESCRIPTION
n_joints

TYPE: int

joint_names

TYPE: List[str]

lower_limits_rad

TYPE: NDArray[float64]

upper_limits_rad

TYPE: NDArray[float64]

Source code in src/robopy/kinematics/chain.py
def __init__(
    self,
    joints: List[RevoluteJoint],
    ee_fixed_transform: NDArray[np.float64],
) -> None:
    self._joints = list(joints)
    self._ee_fixed = np.array(ee_fixed_transform, dtype=np.float64)
    self._n_joints = len(self._joints)

n_joints property ¤

n_joints: int

joint_names property ¤

joint_names: List[str]

lower_limits_rad property ¤

lower_limits_rad: NDArray[float64]

upper_limits_rad property ¤

upper_limits_rad: NDArray[float64]

forward_kinematics_matrix ¤

forward_kinematics_matrix(joint_angles_rad: NDArray[float64]) -> NDArray[float64]

Compute the 4x4 homogeneous transform from base to end-effector.

PARAMETER DESCRIPTION
joint_angles_rad

(n_joints,) array of joint angles in radians.

TYPE: NDArray[float64]

RETURNS DESCRIPTION
NDArray[float64]

4x4 homogeneous transformation matrix.

Source code in src/robopy/kinematics/chain.py
def forward_kinematics_matrix(
    self, joint_angles_rad: NDArray[np.float64]
) -> NDArray[np.float64]:
    """Compute the 4x4 homogeneous transform from base to end-effector.

    Args:
        joint_angles_rad: (n_joints,) array of joint angles in radians.

    Returns:
        4x4 homogeneous transformation matrix.
    """
    if len(joint_angles_rad) != self._n_joints:
        raise ValueError(f"Expected {self._n_joints} joint angles, got {len(joint_angles_rad)}")

    T = np.eye(4)
    for i, joint in enumerate(self._joints):
        rot_fn = _ROT_FUNCS[joint.axis]
        T = T @ joint.parent_to_joint @ rot_fn(float(joint_angles_rad[i]))
    T = T @ self._ee_fixed
    return T

forward_kinematics ¤

forward_kinematics(joint_angles_rad: NDArray[float64]) -> NDArray[float64]

Compute end-effector pose as (x, y, z, pitch, roll).

PARAMETER DESCRIPTION
joint_angles_rad

(n_joints,) array of joint angles in radians.

TYPE: NDArray[float64]

RETURNS DESCRIPTION
NDArray[float64]

(5,) array [x, y, z, pitch, roll].

Source code in src/robopy/kinematics/chain.py
def forward_kinematics(self, joint_angles_rad: NDArray[np.float64]) -> NDArray[np.float64]:
    """Compute end-effector pose as (x, y, z, pitch, roll).

    Args:
        joint_angles_rad: (n_joints,) array of joint angles in radians.

    Returns:
        (5,) array [x, y, z, pitch, roll].
    """
    T = self.forward_kinematics_matrix(joint_angles_rad)
    return pose_from_matrix(T)

jacobian ¤

jacobian(joint_angles_rad: NDArray[float64], delta: float = 1e-06) -> NDArray[float64]

Numerical Jacobian of the 5-DOF pose w.r.t. joint angles.

Uses central finite differences for O(delta^2) accuracy.

RETURNS DESCRIPTION
NDArray[float64]

(5, n_joints) Jacobian matrix.

Source code in src/robopy/kinematics/chain.py
def jacobian(
    self, joint_angles_rad: NDArray[np.float64], delta: float = 1e-6
) -> NDArray[np.float64]:
    """Numerical Jacobian of the 5-DOF pose w.r.t. joint angles.

    Uses central finite differences for O(delta^2) accuracy.

    Returns:
        (5, n_joints) Jacobian matrix.
    """
    J = np.zeros((5, self._n_joints))

    for i in range(self._n_joints):
        q_plus = joint_angles_rad.copy()
        q_minus = joint_angles_rad.copy()
        q_plus[i] += delta
        q_minus[i] -= delta

        pose_plus = self.forward_kinematics(q_plus)
        pose_minus = self.forward_kinematics(q_minus)

        diff = pose_plus - pose_minus
        # Wrap angular components to [-pi, pi]
        for k in (3, 4):
            diff[k] = (diff[k] + np.pi) % (2 * np.pi) - np.pi

        J[:, i] = diff / (2 * delta)

    return J

clamp_to_limits ¤

clamp_to_limits(joint_angles_rad: NDArray[float64]) -> NDArray[float64]

Clamp joint angles to their limits.

Source code in src/robopy/kinematics/chain.py
def clamp_to_limits(self, joint_angles_rad: NDArray[np.float64]) -> NDArray[np.float64]:
    """Clamp joint angles to their limits."""
    return np.clip(joint_angles_rad, self.lower_limits_rad, self.upper_limits_rad)

IKソルバー¤

IKConfig dataclass ¤

IKConfig(max_iterations: int = 100, position_tolerance: float = 0.0001, orientation_tolerance: float = 0.001, damping: float = 0.05, step_scale: float = 0.5, position_weight: float = 1.0, orientation_weight: float = 0.1, joint_limit_margin_rad: float = 0.01)

Configuration for the IK solver.

ATTRIBUTE DESCRIPTION
max_iterations

Maximum solver iterations.

TYPE: int

position_tolerance

Convergence threshold for position error (meters).

TYPE: float

orientation_tolerance

Convergence threshold for orientation error (radians).

TYPE: float

damping

Damping factor lambda for DLS. Higher = more stable, less accurate.

TYPE: float

step_scale

Scale factor for each iteration step (0 < step_scale <= 1).

TYPE: float

position_weight

Weight for position (x, y, z) components in the error.

TYPE: float

orientation_weight

Weight for orientation (pitch, roll) components.

TYPE: float

joint_limit_margin_rad

Stay this far inside joint limits.

TYPE: float

IKResult dataclass ¤

IKResult(joint_angles_rad: NDArray[float64], success: bool, iterations: int, position_error: float, orientation_error: float)

Result from the IK solver.

ATTRIBUTE DESCRIPTION
joint_angles_rad

(n_joints,) solution joint angles in radians.

TYPE: NDArray[float64]

success

Whether the solver converged within tolerance.

TYPE: bool

iterations

Number of iterations used.

TYPE: int

position_error

Final Euclidean position error in meters.

TYPE: float

orientation_error

Final orientation error in radians.

TYPE: float

IKSolver ¤

IKSolver(chain: KinematicChain, config: IKConfig | None = None)

Damped Least-Squares (Levenberg-Marquardt style) IK solver.

Uses the formulation::

dq = J_w^T (J_w J_w^T + lambda^2 I)^{-1} e_w

where J_w is the weighted Jacobian and e_w is the weighted task-space error. The 5x5 linear system is solved with np.linalg.solve — no scipy required.

METHOD DESCRIPTION
solve

Solve IK for a target 5-DOF pose.

ATTRIBUTE DESCRIPTION
config

TYPE: IKConfig

Source code in src/robopy/kinematics/ik_solver.py
def __init__(self, chain: KinematicChain, config: IKConfig | None = None) -> None:
    self._chain = chain
    self._config = config or IKConfig()

config property ¤

config: IKConfig

solve ¤

solve(target_pose: NDArray[float64], initial_angles_rad: NDArray[float64]) -> IKResult

Solve IK for a target 5-DOF pose.

PARAMETER DESCRIPTION
target_pose

(5,) array [x, y, z, pitch, roll].

TYPE: NDArray[float64]

initial_angles_rad

(n_joints,) initial guess in radians.

TYPE: NDArray[float64]

RETURNS DESCRIPTION
IKResult

IKResult with solution and convergence information.

Source code in src/robopy/kinematics/ik_solver.py
def solve(
    self,
    target_pose: NDArray[np.float64],
    initial_angles_rad: NDArray[np.float64],
) -> IKResult:
    """Solve IK for a target 5-DOF pose.

    Args:
        target_pose: (5,) array [x, y, z, pitch, roll].
        initial_angles_rad: (n_joints,) initial guess in radians.

    Returns:
        IKResult with solution and convergence information.
    """
    cfg = self._config
    q = initial_angles_rad.copy().astype(np.float64)

    W = np.diag(
        [
            cfg.position_weight,
            cfg.position_weight,
            cfg.position_weight,
            cfg.orientation_weight,
            cfg.orientation_weight,
        ]
    )

    lower = self._chain.lower_limits_rad + cfg.joint_limit_margin_rad
    upper = self._chain.upper_limits_rad - cfg.joint_limit_margin_rad

    for iteration in range(cfg.max_iterations):
        current_pose = self._chain.forward_kinematics(q)
        error = target_pose - current_pose

        # Wrap angular errors to [-pi, pi]
        for k in (3, 4):
            error[k] = (error[k] + np.pi) % (2 * np.pi) - np.pi

        pos_err = float(np.linalg.norm(error[:3]))
        ori_err = float(np.linalg.norm(error[3:]))

        if pos_err < cfg.position_tolerance and ori_err < cfg.orientation_tolerance:
            return IKResult(
                joint_angles_rad=q,
                success=True,
                iterations=iteration + 1,
                position_error=pos_err,
                orientation_error=ori_err,
            )

        # Weighted error and Jacobian
        e_w = W @ error
        J = self._chain.jacobian(q)
        J_w = W @ J  # (5, n_joints)

        # DLS: dq = J_w^T (J_w J_w^T + lambda^2 I)^{-1} e_w
        JJT = J_w @ J_w.T  # (5, 5)
        damped = JJT + (cfg.damping**2) * np.eye(5)
        y = np.linalg.solve(damped, e_w)
        dq = J_w.T @ y

        q = q + cfg.step_scale * dq
        q = np.clip(q, lower, upper)

    # Did not converge — compute final error
    current_pose = self._chain.forward_kinematics(q)
    error = target_pose - current_pose
    pos_err = float(np.linalg.norm(error[:3]))
    ori_err = float(np.linalg.norm(error[3:]))

    logger.debug(
        "IK did not converge after %d iterations. "
        "Position error: %.6f m, Orientation error: %.6f rad",
        cfg.max_iterations,
        pos_err,
        ori_err,
    )

    return IKResult(
        joint_angles_rad=q,
        success=False,
        iterations=cfg.max_iterations,
        position_error=pos_err,
        orientation_error=ori_err,
    )

ロボット固有のチェーン定義¤

so101_chain ¤

so101_chain() -> KinematicChain

Create the kinematic chain for the SO-101 robot (5-DOF, excluding gripper).

All parameters are taken directly from the SO-101 URDF (SO-ARM100/Simulation/SO101/so101_new_calib.urdf).

In the URDF every revolute joint has axis xyz="0 0 1" (local Z). The joint-origin RPY rotations orient each link frame so that the local Z-axis points in the correct physical direction.

Source code in src/robopy/kinematics/robot_chains.py
def so101_chain() -> KinematicChain:
    """Create the kinematic chain for the SO-101 robot (5-DOF, excluding gripper).

    All parameters are taken **directly** from the SO-101 URDF
    (``SO-ARM100/Simulation/SO101/so101_new_calib.urdf``).

    In the URDF every revolute joint has ``axis xyz="0 0 1"`` (local Z).
    The joint-origin RPY rotations orient each link frame so that the
    local Z-axis points in the correct physical direction.
    """
    joints = [
        RevoluteJoint(
            name="shoulder_pan",
            # origin xyz="0.0388 0 0.0624" rpy="π 0 -π"
            parent_to_joint=urdf_transform(
                xyz=(0.0388, 0.0, 0.0624),
                rpy=(_PI, 0.0, -_PI),
            ),
            axis="z",
            lower_limit_rad=-1.91986,  # -110 deg
            upper_limit_rad=1.91986,  # +110 deg
        ),
        RevoluteJoint(
            name="shoulder_lift",
            # origin xyz="-0.0304 -0.0183 -0.0542" rpy="-π/2 -π/2 0"
            parent_to_joint=urdf_transform(
                xyz=(-0.0304, -0.0183, -0.0542),
                rpy=(-_HALF_PI, -_HALF_PI, 0.0),
            ),
            axis="z",
            lower_limit_rad=-1.74533,  # -100 deg
            upper_limit_rad=1.74533,  # +100 deg
        ),
        RevoluteJoint(
            name="elbow_flex",
            # origin xyz="-0.11257 -0.028 0" rpy="0 0 π/2"
            parent_to_joint=urdf_transform(
                xyz=(-0.11257, -0.028, 0.0),
                rpy=(0.0, 0.0, _HALF_PI),
            ),
            axis="z",
            lower_limit_rad=-1.69,  # -96.8 deg
            upper_limit_rad=1.69,  # +96.8 deg
        ),
        RevoluteJoint(
            name="wrist_flex",
            # origin xyz="-0.1349 0.0052 0" rpy="0 0 -π/2"
            parent_to_joint=urdf_transform(
                xyz=(-0.1349, 0.0052, 0.0),
                rpy=(0.0, 0.0, -_HALF_PI),
            ),
            axis="z",
            lower_limit_rad=-1.65806,  # -95 deg
            upper_limit_rad=1.65806,  # +95 deg
        ),
        RevoluteJoint(
            name="wrist_roll",
            # origin xyz="0 -0.0611 0.0181" rpy="π/2 0.0487 π"
            parent_to_joint=urdf_transform(
                xyz=(0.0, -0.0611, 0.0181),
                rpy=(_HALF_PI, 0.0487, _PI),
            ),
            axis="z",
            lower_limit_rad=-2.74385,  # -157.2 deg
            upper_limit_rad=2.84121,  # +162.8 deg
        ),
    ]

    # Fixed transform: gripper_frame_joint
    # origin xyz="-0.0079 -0.000218 -0.0981" rpy="0 π 0"
    ee_fixed = urdf_transform(
        xyz=(-0.0079, -0.000218, -0.0981),
        rpy=(0.0, _PI, 0.0),
    )

    return KinematicChain(joints=joints, ee_fixed_transform=ee_fixed)

koch_chain ¤

koch_chain() -> KinematicChain

Create the kinematic chain for the Koch v1.1 robot (5-DOF, excluding gripper).

.. warning::

Koch has **no official URDF**.  The parameters below are rough
approximations from MuJoCo menagerie and CAD drawings.  Every numeric
constant is marked with ``TODO(physical-params)`` and **must** be
validated against the physical robot before production use.

TODO(physical-params): Validate shoulder_pan offset against real robot. TODO(physical-params): Measure exact upper_arm length (currently ~110 mm est.). TODO(physical-params): Measure exact forearm length (currently ~100 mm est.). TODO(physical-params): Validate wrist offset and EE frame position. TODO(physical-params): Measure and confirm joint axis directions. TODO(physical-params): Calibrate joint limit values against real hardware.

Source code in src/robopy/kinematics/robot_chains.py
def koch_chain() -> KinematicChain:
    """Create the kinematic chain for the Koch v1.1 robot (5-DOF, excluding gripper).

    .. warning::

        Koch has **no official URDF**.  The parameters below are rough
        approximations from MuJoCo menagerie and CAD drawings.  Every numeric
        constant is marked with ``TODO(physical-params)`` and **must** be
        validated against the physical robot before production use.

    TODO(physical-params): Validate shoulder_pan offset against real robot.
    TODO(physical-params): Measure exact upper_arm length (currently ~110 mm est.).
    TODO(physical-params): Measure exact forearm length (currently ~100 mm est.).
    TODO(physical-params): Validate wrist offset and EE frame position.
    TODO(physical-params): Measure and confirm joint axis directions.
    TODO(physical-params): Calibrate joint limit values against real hardware.
    """
    joints = [
        RevoluteJoint(
            name="shoulder_pan",
            # TODO(physical-params): Approximate. Measure base-to-shoulder offset.
            parent_to_joint=translation(0.0, 0.0, 0.05),
            axis="y",  # TODO(physical-params): Confirm axis direction
            lower_limit_rad=-2.61799,  # -150 deg (estimate)
            upper_limit_rad=2.61799,  # +150 deg (estimate)
        ),
        RevoluteJoint(
            name="shoulder_lift",
            # TODO(physical-params): Approximate shoulder-to-upper-arm offset.
            parent_to_joint=translation(0.0, 0.0, -0.04),
            axis="x",  # TODO(physical-params): Confirm axis direction
            lower_limit_rad=-1.74533,  # -100 deg (estimate)
            upper_limit_rad=1.74533,  # +100 deg (estimate)
        ),
        RevoluteJoint(
            name="elbow",
            # Upper arm length ~110 mm
            # TODO(physical-params): Measure precisely.
            parent_to_joint=translation(-0.110, 0.0, 0.0),
            axis="x",  # TODO(physical-params): Confirm axis direction
            lower_limit_rad=-1.74533,  # -100 deg (estimate)
            upper_limit_rad=1.74533,  # +100 deg (estimate)
        ),
        RevoluteJoint(
            name="wrist_flex",
            # Forearm length ~100 mm
            # TODO(physical-params): Measure precisely.
            parent_to_joint=translation(-0.100, 0.0, 0.0),
            axis="x",  # TODO(physical-params): Confirm axis direction
            lower_limit_rad=-1.74533,  # -100 deg (estimate)
            upper_limit_rad=1.74533,  # +100 deg (estimate)
        ),
        RevoluteJoint(
            name="wrist_roll",
            # TODO(physical-params): Approximate wrist-to-gripper offset.
            parent_to_joint=translation(0.0, -0.04, 0.0),
            axis="y",  # TODO(physical-params): Confirm axis direction
            lower_limit_rad=-3.14159,  # -180 deg (estimate)
            upper_limit_rad=3.14159,  # +180 deg (estimate)
        ),
    ]

    # TODO(physical-params): Measure precise EE offset from wrist_roll.
    ee_fixed = translation(0.0, 0.0, -0.06)

    return KinematicChain(joints=joints, ee_fixed_transform=ee_fixed)

アルゴリズム¤

Damped Least-Squares (DLS) IK¤

IKソルバーは Damped Least-Squares アルゴリズムを使用しています:

$$ \Delta q = J_w^T (J_w J_w^T + \lambda^2 I)^{-1} e_w $$

ここで:

  • $J_w$: 重み付きヤコビアン行列 (5 x n_joints)
  • $e_w$: 重み付きタスク空間誤差 (5,)
  • $\lambda$: ダンピング係数(IKConfig.damping
  • $I$: 単位行列

この手法の特徴:

  • 特異姿勢(腕が完全に伸びた状態など)でも安定
  • 位置と姿勢に独立した重みを設定可能
  • 5x5の線形方程式を np.linalg.solve で解くため高速
  • scipy 不要(numpy のみ)

数値ヤコビアン¤

ヤコビアンは中心差分法で計算されます:

$$ J_{ij} = \frac{f(q + \delta e_j) - f(q - \delta e_j)}{2\delta} $$

5関節の場合、1回のヤコビアン計算に10回のFK評価が必要ですが、各FKは5回の4x4行列乗算のみなので100Hzの制御ループでも十分高速です。

使用例¤

オフラインでのFK/IK計算¤

ハードウェア接続なしでFK/IK計算を行う例:

import numpy as np
from robopy.kinematics import so101_chain, koch_chain, IKSolver, IKConfig

# SO-101のチェーンを作成
chain = so101_chain()

# 全関節0度でのEE位置を確認
home_pose = chain.forward_kinematics(np.zeros(5))
print(f"Home位置: x={home_pose[0]:.4f}, y={home_pose[1]:.4f}, z={home_pose[2]:.4f}")

# IKで目標姿勢に到達する関節角度を求める
solver = IKSolver(chain, IKConfig(max_iterations=200))
result = solver.solve(
    target_pose=home_pose,
    initial_angles_rad=np.zeros(5),
)
print(f"収束: {result.success}, 反復回数: {result.iterations}")

ロボットクラスからの利用¤

from robopy.robots.so101.so101_robot import So101Robot
from robopy.kinematics import EEPose
import numpy as np

# FK(classmethodなのでインスタンス不要)
joint_angles = np.array([0.0, 30.0, -45.0, 20.0, 0.0, 50.0], dtype=np.float32)
ee_pose = So101Robot.forward_kinematics(joint_angles)

# IK(接続済みロボットで)
# target = EEPose(x=0.1, y=0.0, z=0.15, pitch=0.0, roll=0.0)
# result = robot.inverse_kinematics(target, current_joints)

# EEアクション送信(接続済みロボットで)
# robot.send_ee_frame_action(np.array([0.1, 0.0, 0.15, 0.0, 0.0, 50.0]))