Kinematics User Guide#
This chapter walks you through everyday kinematics workflows in ManipulaPy: from building a SerialManipulator object, to computing forward & inverse kinematics, Jacobians, workspace envelopes, and velocity mappings. It assumes you already ran the installation guide and have a working Python interpreter.
Prerequisites#
Python â„ 3.8 with numpy & matplotlib
ManipulaPy â„ 1.3.2.post1
A basic grasp of screw theory / the ProductâofâExponentials (PoE) model.
If you need a refresher, see Modern Robotics, Ch 3 (free online PDF) or the conceptual overview in Kinematics User Guide.
What is robot kinematics?#
Robot kinematics studies the geometry of a manipulator without worrying about forces or torques. The central problems are:
Forward kinematics (FK): joint angles â pose of the tool frame \(T \in \mathrm{SE}(3)\).
Inverse kinematics (IK): desired pose â one or more joint angle solutions.
Velocity kinematics: jointâspace rates â spatial twist of the endâeffector.
ManipulaPy models every rigid motion as an element of \(\mathrm{SE}(3) \cong \mathbb{R}^3 \times \mathrm{SO}(3)\) using homogeneous transforms and encodes joint axes as screws \(S_i \in \mathfrak{se}(3)\).
Forward kinematics via PoE#
With screws arranged columnâwise in \(S_{list} \in \mathbb{R}^{6\times n}\) and a home configuration matrix \(M\), the FK map is
ManipulaPy evaluates this with numerically stable Rodrigues formulas.
Quickâstart example#
import numpy as np
from ManipulaPy.kinematics import SerialManipulator
# Home pose of tool frame (millimetres â metres)
M = np.array([[1, 0, 0, 0.817],
[0, 1, 0, 0.000],
[0, 0, 1, 0.191],
[0, 0, 0, 1 ]])
# Screw axes in the *space* frame (ÏÂ |Â v)
S_list = np.array([
[0, 0, 1, 0.000, 0.000, 0.000],
[0, -1, 0, -0.089, 0.000, 0.000],
[0, -1, 0, -0.089, 0.000, 0.425],
[0, -1, 0, -0.089, 0.000, 0.817],
[1, 0, 0, 0.000, 0.109, 0.000],
[0, -1, 0, -0.089, 0.000, 0.817],
]).T
robot = SerialManipulator(M_list=M, S_list=S_list) # B_list autocomputed
thetalist = np.deg2rad([30, -45, 10, 120, 0, 90])
T = robot.forward_kinematics(thetalist)
print(np.round(T, 3))
Creating a robot from URDF#
Most users will load a real robot description:
from ManipulaPy.urdf_processor import URDFToSerialManipulator
urdf_path = "resources/urdfs/panda_arm.urdf"
robot = URDFToSerialManipulator(urdf_path).serial_manipulator
print(robot.n_joints) # 7
print(robot.joint_limits[:3]) # perâjoint lower/upper bounds
ManipulaPy parses <limit> tags, inertias, and collision geometry so the
same object can be reused for dynamics and planning.
Forward kinematics recipes#
Single pose#
T_BÂ = robot.forward_kinematics(thetalist, frame="body")
xyz = T_B[:3, 3]
R Â = T_B[:3, :3] # orientation matrix
Batch evaluation#
If you need thousands of FK calls per frame, wrap them in NumPy arrays:
thetas = np.random.uniform(-np.pi, np.pi, (1024, robot.n_joints))
poses = robot.batch_forward_kinematics(thetas) # returns (1024, 4, 4)
(The batch routine is CuPyâaccelerated when installed with
pip install ManipulaPy[gpu-cuda11].)
Inverse kinematics#
ManipulaPy supplies four flavours:
NewtonâRaphson (iterative_inverse_kinematics) â default, robust.
LevenbergâMarquardt (lm_inverse_kinematics) â higher success near singularities.
Positionâonly IK (position_inverse_kinematics) â ignores orientation.
Nullâspace IK (redundancy resolution) â exposed via
NullSpaceIKSolver.
Example (basic Newton):
success, sol, _ = robot.iterative_inverse_kinematics(
T_desired=T, thetalist0=np.zeros(robot.n_joints))
assert success
Jacobian & singularities#
J = robot.jacobian(thetalist, frame="space") # (6Â ĂÂ n)
manipulability = np.sqrt(np.linalg.det(J @ J.T))
cond_number = np.linalg.cond(J)
A warning is raised if cond_number > 1e6 (config near singularity).
Velocity kinematics helper#
Ξdot = np.deg2rad([10, 5, 0, 0, 0, 0]) # joint rates [radâŻsâ»Âč]
V_s = robot.end_effector_velocity(thetalist, Ξdot) # spatial twist
# Solve inverse velocity problem
V_des = np.array([0.1, 0, 0, 0, 0, 0.2]) # move +X & rotate +Z
Ξdot_r = robot.joint_velocity(thetalist, V_des)
Workspace visualisation snippet#
import matplotlib.pyplot as plt
pts = robot.sample_workspace(n_samples=500)
fig = plt.figure(); ax = fig.add_subplot(111, projection="3d")
ax.scatter(*pts.T, s=3, alpha=.4)
ax.set_xlabel("X [m]"); ax.set_ylabel("Y [m]"); ax.set_zlabel("Z [m]")
Troubleshooting#
Symptom |
Fix |
|---|---|
IK fails to |
|
converge |
 limits or workspace. * Provide a better initial guess; use the smart_initial_guess helper below. |
Numerical |
|
instability |
|
Joint limit |
|
violation |
passing them to the IK solver. |
def smart_initial_guess(robot, T_desired):
try:
return robot.current_configuration # live robot state
except AttributeError:
# fallback: midârange of each joint
return np.mean(robot.joint_limits, axis=1)