キネマティクス API¤
このページでは、Robopyのキネマティクス(運動学)モジュールに関連するAPIを説明します。
概要¤
robopy.kinematics モジュールは、5自由度ロボットアームのForward Kinematics (FK) と Inverse Kinematics (IK) を提供します。
- FK: 関節角度 → エンドエフェクタ姿勢(位置 + 姿勢)
- IK: エンドエフェクタ姿勢 → 関節角度(数値解法)
外部依存は numpy のみ です。scipy は不要です。
エンドエフェクタ姿勢¤
EEPose
dataclass
¤
5-DOF end-effector pose.
| ATTRIBUTE | DESCRIPTION |
|---|---|
x |
End-effector X position in meters.
TYPE:
|
y |
End-effector Y position in meters.
TYPE:
|
z |
End-effector Z position in meters.
TYPE:
|
pitch |
Rotation about the Y-axis in radians.
TYPE:
|
roll |
Rotation about the X-axis in radians.
TYPE:
|
| METHOD | DESCRIPTION |
|---|---|
to_array |
Return (5,) numpy array [x, y, z, pitch, roll]. |
from_array |
Construct from a (5,) array. |
キネマティックチェーン¤
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:
|
parent_to_joint |
4x4 static transform from parent frame to this joint's rotation center (before any rotation is applied).
TYPE:
|
axis |
Rotation axis as a string: "x", "y", or "z".
TYPE:
|
lower_limit_rad |
Minimum joint angle in radians.
TYPE:
|
upper_limit_rad |
Maximum joint angle in radians.
TYPE:
|
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:
|
joint_names |
TYPE:
|
lower_limits_rad |
TYPE:
|
upper_limits_rad |
TYPE:
|
Source code in src/robopy/kinematics/chain.py
forward_kinematics_matrix
¤
Compute the 4x4 homogeneous transform from base to end-effector.
| PARAMETER | DESCRIPTION |
|---|---|
joint_angles_rad
|
(n_joints,) array of joint angles in radians.
TYPE:
|
| RETURNS | DESCRIPTION |
|---|---|
NDArray[float64]
|
4x4 homogeneous transformation matrix. |
Source code in src/robopy/kinematics/chain.py
forward_kinematics
¤
Compute end-effector pose as (x, y, z, pitch, roll).
| PARAMETER | DESCRIPTION |
|---|---|
joint_angles_rad
|
(n_joints,) array of joint angles in radians.
TYPE:
|
| RETURNS | DESCRIPTION |
|---|---|
NDArray[float64]
|
(5,) array [x, y, z, pitch, roll]. |
Source code in src/robopy/kinematics/chain.py
jacobian
¤
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
clamp_to_limits
¤
Clamp joint angles to their limits.
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:
|
position_tolerance |
Convergence threshold for position error (meters).
TYPE:
|
orientation_tolerance |
Convergence threshold for orientation error (radians).
TYPE:
|
damping |
Damping factor lambda for DLS. Higher = more stable, less accurate.
TYPE:
|
step_scale |
Scale factor for each iteration step (0 < step_scale <= 1).
TYPE:
|
position_weight |
Weight for position (x, y, z) components in the error.
TYPE:
|
orientation_weight |
Weight for orientation (pitch, roll) components.
TYPE:
|
joint_limit_margin_rad |
Stay this far inside joint limits.
TYPE:
|
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:
|
success |
Whether the solver converged within tolerance.
TYPE:
|
iterations |
Number of iterations used.
TYPE:
|
position_error |
Final Euclidean position error in meters.
TYPE:
|
orientation_error |
Final orientation error in radians.
TYPE:
|
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:
|
Source code in src/robopy/kinematics/ik_solver.py
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:
|
initial_angles_rad
|
(n_joints,) initial guess in radians.
TYPE:
|
| RETURNS | DESCRIPTION |
|---|---|
IKResult
|
IKResult with solution and convergence information. |
Source code in src/robopy/kinematics/ik_solver.py
78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 | |
ロボット固有のチェーン定義¤
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
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
アルゴリズム¤
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]))