2. Matrix based transforms#
In the last notebook 1_getting_started_with_robot_ik.ipynb we have familiarized ourselves with the concept of Forward and Inverse Kinematics (IK) and implemented a simple IK solver for a 3DOF leg using trigonometry. In this notebook we will use SciPy to implement a more advanced IK solver using matrix transformations.
SciPy, a Python library built upon NumPy, provides a wide array of mathematical algorithms and functions that are valuable for robotics, including linear algebra, which is of interest here.
Affine transforms#
The first step is to convert our forward kinematics code from custom Points and hand crafted function to use matrix transforms for rotation and translation.
Alongside the conversion, we are going to bring all the algorithms to work in full 3D space, not just 2D projections.
As a first step in conversion, let’s replace hand crafted rotations with rotation matrices.
from drqp_kinematics.geometry import Leg3D, Line3D, Point3D
import numpy as np
from scipy.spatial.transform import Rotation as R
def forward_kinematics(
coxa_length,
femur_length,
tibia_length,
alpha,
beta,
gamma,
start_height=2,
body_length=5,
):
# Define initial points in local coordinates
start_point = Point3D([0, start_height, 0])
body_local = Point3D([body_length, 0, 0])
coxa_local = Point3D([coxa_length, 0, 0])
femur_local = Point3D([femur_length, 0, 0])
tibia_local = Point3D([tibia_length, 0, 0])
# Create rotation matrices
rotation_axis = np.array([0, 0, 1])
r_alpha = R.from_rotvec(rotation_axis * alpha, degrees=True)
r_beta = R.from_rotvec(rotation_axis * beta, degrees=True)
r_gamma = R.from_rotvec(rotation_axis * gamma, degrees=True)
# Calculate global positions using transformations
body_point = start_point + body_local
# Apply alpha rotation to coxa
coxa_rotated = r_alpha.apply(coxa_local.numpy())
coxa_point = body_point + coxa_rotated
# Apply alpha+beta rotation to femur
r_alpha_beta = r_alpha * r_beta
femur_rotated = r_alpha_beta.apply(femur_local.numpy())
femur_point = coxa_point + femur_rotated
# Apply alpha+beta+gamma rotation to tibia
r_alpha_beta_gamma = r_alpha_beta * r_gamma
tibia_rotated = r_alpha_beta_gamma.apply(tibia_local.numpy())
tibia_point = femur_point + tibia_rotated
# Set Point labels for visualization
body_point.label = rf'$\alpha$={alpha}°'
coxa_point.label = rf'$\beta$={beta}°'
femur_point.label = rf'$\gamma$={gamma}°'
tibia_point.label = 'Foot'
# Return lines connecting the points
return Leg3D(
[
Line3D(start_point, body_point, 'Body'),
Line3D(body_point, coxa_point, 'Coxa'),
Line3D(coxa_point, femur_point, 'Femur'),
Line3D(femur_point, tibia_point, 'Tibia'),
]
)
from plotting import plot_leg_with_points
coxa = 5
femur = 8
tibia = 10
model = forward_kinematics(coxa, femur, tibia, 45, -55, -14)
_ = plot_leg_with_points(
model.xy, 'Foot on the ground (XY)', link_labels='none', x_label="X'", y_label='Y'
)
display_and_close(plt.gcf())
_ = plot_leg_with_points(
model.xz, 'Foot on the ground (XZ)', link_labels='none', x_label="X'", y_label='Z'
)
display_and_close(plt.gcf())
This was a good start, but code is hard to read and understand due to excessive repetitions. Let’s introduce a transform system, similar to the one used in ROS TF2 library.
Code from drqp_kinematics/geometry/transforms.py:
import numpy as np
from scipy.spatial.transform import Rotation as R
from .line import Line3D
from .point import Point3D
class AffineTransform:
"""
An affine transform class.
Uses 4x4 matrix to represent a transform.
"""
def __init__(self, matrix):
self._matrix = matrix
self._inverse = None
@classmethod
def make(cls, rotation, translation):
return cls(
np.block(
[
[rotation.as_matrix(), np.array(translation).reshape(3, 1)],
[np.zeros(3), 1],
]
)
)
@classmethod
def identity(cls):
return cls(np.identity(4))
@classmethod
def from_rotvec(cls, rotvec, degrees=False):
return cls.make(R.from_rotvec(rotvec, degrees=degrees), [0, 0, 0])
@classmethod
def from_rotmatrix(cls, rotation_matrix):
return cls(
np.block(
[
[np.array(rotation_matrix), np.zeros((3, 1))],
[np.zeros(3), 1],
]
)
)
@classmethod
def from_translation(cls, translation):
return cls.make(R.identity(), translation)
@property
def rotation(self):
return self._matrix[:3, :3]
@property
def translation(self):
return self._matrix[:3, 3]
@property
def matrix(self):
return self._matrix
@property
def inverse(self):
if self._inverse is None:
self._inverse = AffineTransform(np.linalg.inv(self._matrix))
return self._inverse
def apply_point(self, point):
return Point3D(self.apply_nd(point.numpy()))
def apply_line(self, line: Line3D):
return Line3D(self.apply_point(line.start), self.apply_point(line.end), line.label)
def apply_nd(self, nd_point):
point4d = np.append(nd_point, 1)
transformed_point = self._matrix @ point4d
return transformed_point[:3]
def __matmul__(self, other):
return AffineTransform(self._matrix @ other._matrix)
def __repr__(self):
rotation = R.from_matrix(self.rotation).as_rotvec(degrees=True)
translation = self.translation
return f'AffineTransform({translation=}, {rotation=}, as matrix:\n{self._matrix})'
With this AffineTransform class we can now create a chain of transformations instead of hand crafting them. Let’s rewrite the forward kinematics code using transforms.
The code below is an excerpt from LegModel in drqp_kinematics/models.py:
def forward_kinematics(self, alpha, beta, gamma):
self.update_base_transforms()
self.coxa_angle = alpha
self.femur_angle = beta
self.tibia_angle = gamma
self.coxa_joint = self.body_joint @ AffineTransform.from_rotvec(
[0, 0, alpha], degrees=True
)
self.coxa_link = self.coxa_joint @ AffineTransform.from_translation(
[self.coxa_length, 0, 0]
)
self.femur_joint = self.coxa_link @ AffineTransform.from_rotvec([0, beta, 0], degrees=True)
self.femur_link = self.femur_joint @ AffineTransform.from_translation(
[self.femur_length, 0, 0]
)
self.tibia_joint = self.femur_link @ AffineTransform.from_rotvec(
[0, gamma, 0], degrees=True
)
self.tibia_link = self.tibia_joint @ AffineTransform.from_translation(
[self.tibia_length, 0, 0]
)
identity_point = Point3D([0, 0, 0])
self.body_start = self.body_transform.apply_point(identity_point)
self.body_end = self.body_link.apply_point(identity_point)
self.body_end.label = rf'$\alpha$={alpha}°'
self.coxa_end = self.coxa_link.apply_point(identity_point)
self.coxa_end.label = rf'$\beta$={beta}°'
self.femur_end = self.femur_link.apply_point(identity_point)
self.femur_end.label = rf'$\gamma$={gamma}°'
self.tibia_end = self.tibia_link.apply_point(identity_point)
self.tibia_end.label = 'Foot'
from drqp_kinematics.models import HexapodLeg, LegModel
from plotting import plot_leg3d
coxa = 5
femur = 8
tibia = 10
# model = forward_kinematics_transforms(coxa, femur, tibia, 0, -25, 110)
model = LegModel(coxa, femur, tibia, HexapodLeg.left_front)
model.forward_kinematics(0, -25, 110)
fig, _, _ = plot_leg_with_points(
model.xy,
'Foot in 3D (XY)',
link_labels='none',
joint_labels='points',
x_label='X',
y_label='Y',
subplot=221,
)
_ = plot_leg_with_points(
model.xz,
'Foot in 3D (XZ)',
link_labels='none',
joint_labels='points',
x_label='X',
y_label='Z',
subplot=222,
fig=fig,
)
_ = plot_leg_with_points(
model.yz,
'Foot in 3D (YZ)',
link_labels='none',
joint_labels='points',
x_label='Y',
y_label='Z',
subplot=223,
fig=fig,
)
fig, ax, plot_data = plot_leg3d(
model,
'Foot in 3D',
link_labels='none',
joint_labels='points',
subplot=224,
fig=fig,
hide_grid=False,
)
ax.plot(*zip([0, -5, 0], [0, 5, 0]), 'w:') # add depth
ax.set_aspect('equal') # Upset the aspect ratio
display_and_close(fig)
With full 3D kinematics model and plotting support lets put it all together and create a 6 legged robot model.
Code from drqp_kinematics/models.py:
import enum
import numpy as np
from drqp_kinematics.geometry import AffineTransform, Line3D, Point3D
class HexapodLeg(enum.Enum):
left_front = enum.auto()
left_middle = enum.auto()
left_back = enum.auto()
right_front = enum.auto()
right_middle = enum.auto()
right_back = enum.auto()
def safe_arccos(num):
if num < -1:
return False, np.pi
if num > 1:
return False, 0.0
return True, np.arccos(num)
class HexapodModel:
def __init__(
self,
front_offset=100.0,
side_offset=100.0,
middle_offset=100.0,
coxa_len=100.0,
femur_len=100.0,
tibia_len=100.0,
body_transform=AffineTransform.identity(),
leg_rotation=[0, 0, 45],
):
leg_rotation = np.array(leg_rotation)
self.left_front = LegModel(
coxa_len,
femur_len,
tibia_len,
label=HexapodLeg.left_front,
rotation=leg_rotation,
location_on_body=[front_offset, side_offset, 0.0],
)
self.left_middle = LegModel(
coxa_len,
femur_len,
tibia_len,
label=HexapodLeg.left_middle,
rotation=leg_rotation * 2,
location_on_body=[0.0, middle_offset, 0.0],
)
self.left_back = LegModel(
coxa_len,
femur_len,
tibia_len,
label=HexapodLeg.left_back,
rotation=leg_rotation * 3,
location_on_body=[-front_offset, side_offset, 0.0],
)
self.right_front = LegModel(
coxa_len,
femur_len,
tibia_len,
label=HexapodLeg.right_front,
rotation=leg_rotation * -1,
location_on_body=[front_offset, -side_offset, 0.0],
)
self.right_middle = LegModel(
coxa_len,
femur_len,
tibia_len,
label=HexapodLeg.right_middle,
rotation=leg_rotation * -2,
location_on_body=[0.0, -middle_offset, 0.0],
)
self.right_back = LegModel(
coxa_len,
femur_len,
tibia_len,
label=HexapodLeg.right_back,
rotation=leg_rotation * -3,
location_on_body=[-front_offset, -side_offset, 0.0],
)
self.__named_legs = {
leg.label: leg
for leg in [
self.left_front,
self.left_middle,
self.left_back,
self.right_front,
self.right_middle,
self.right_back,
]
}
self.__head_base_line = Line3D(Point3D([0, 0, 0]), Point3D([front_offset, 0, 0]), 'Head')
self.body_transform = body_transform
def forward_kinematics(self, alpha, beta, gamma):
for leg in self.legs:
leg.forward_kinematics(alpha, beta, gamma)
def move_legs_to(self, foot_targets, verbose=False):
return [leg.move_to(target, verbose) for leg, target in zip(self.legs, foot_targets)]
@property
def legs(self):
return self.__named_legs.values()
@property
def named_legs(self):
return self.__named_legs
@property
def body_transform(self):
return self.left_front.body_transform
@body_transform.setter
def body_transform(self, body_transform):
for leg in self.legs:
leg.body_transform = body_transform
self.head = body_transform.apply_line(self.__head_base_line)
class LegModel:
"""A leg model class."""
def __init__(
self,
coxa_length: float,
femur_length: float,
tibia_length: float,
label: HexapodLeg,
location_on_body=[0, 0, 0],
rotation=[0, 0, 0],
body_transform=AffineTransform.identity(),
):
self.coxa_length = coxa_length
self.femur_length = femur_length
self.tibia_length = tibia_length
self.label = label
self.location_on_body = location_on_body
self.rotation = rotation
self._body_transform = body_transform
self.update_base_transforms()
self.forward_kinematics(0, 0, 0)
@property
def body_transform(self):
return self._body_transform
@body_transform.setter
def body_transform(self, value):
self._body_transform = value
self.update_base_transforms()
def update_base_transforms(self):
self.body_link = self.body_transform @ AffineTransform.from_translation(
self.location_on_body
)
self.body_joint = self.body_link @ AffineTransform.from_rotvec(self.rotation, degrees=True)
@property
def lines(self):
return [
Line3D(self.body_start, self.body_end, 'Body'),
Line3D(self.body_end, self.coxa_end, 'Coxa'),
Line3D(self.coxa_end, self.femur_end, 'Femur'),
Line3D(self.femur_end, self.tibia_end, 'Tibia'),
]
@property
def xy(self):
return [line.xy for line in self.lines]
@property
def xz(self):
return [line.xz for line in self.lines]
@property
def yz(self):
return [line.yz for line in self.lines]
def __iter__(self):
return iter(self.lines)
def __repr__(self):
return (
'LegModel('
f'body_start={self.body_start}, '
f'body_end={self.body_end}, '
f'coxa_end={self.coxa_end}, '
f'femur_end={self.femur_end}, '
f'tibia_end={self.tibia_end})'
)
# Leg Forward kinematics - START
def forward_kinematics(self, alpha, beta, gamma):
self.update_base_transforms()
self.coxa_angle = alpha
self.femur_angle = beta
self.tibia_angle = gamma
self.coxa_joint = self.body_joint @ AffineTransform.from_rotvec(
[0, 0, alpha], degrees=True
)
self.coxa_link = self.coxa_joint @ AffineTransform.from_translation(
[self.coxa_length, 0, 0]
)
self.femur_joint = self.coxa_link @ AffineTransform.from_rotvec([0, beta, 0], degrees=True)
self.femur_link = self.femur_joint @ AffineTransform.from_translation(
[self.femur_length, 0, 0]
)
self.tibia_joint = self.femur_link @ AffineTransform.from_rotvec(
[0, gamma, 0], degrees=True
)
self.tibia_link = self.tibia_joint @ AffineTransform.from_translation(
[self.tibia_length, 0, 0]
)
identity_point = Point3D([0, 0, 0])
self.body_start = self.body_transform.apply_point(identity_point)
self.body_end = self.body_link.apply_point(identity_point)
self.body_end.label = rf'$\alpha$={alpha}°'
self.coxa_end = self.coxa_link.apply_point(identity_point)
self.coxa_end.label = rf'$\beta$={beta}°'
self.femur_end = self.femur_link.apply_point(identity_point)
self.femur_end.label = rf'$\gamma$={gamma}°'
self.tibia_end = self.tibia_link.apply_point(identity_point)
self.tibia_end.label = 'Foot'
# Leg Forward kinematics - END
def move_to(self, foot_target: Point3D, verbose=False):
reached_target, alpha, beta, gamma = self.inverse_kinematics(foot_target, verbose)
if verbose:
print(
f'{self.label} moving to {foot_target}. '
f'new angles: {alpha=:.4f}\t{beta=:.4f}\t{gamma=:.4f}'
)
self.forward_kinematics(alpha, beta, gamma)
return reached_target
def inverse_kinematics(self, foot_target: Point3D, verbose=False):
localized_foot_target = self.to_local(foot_target)
alpha, x_tick = self._inverse_kinematics_xy(localized_foot_target)
solvable, beta, gamma = self._inverse_kinematics_xz(
localized_foot_target.z,
x_tick,
verbose=verbose,
)
return solvable, alpha, beta, gamma
def to_local(self, point):
return self.body_joint.inverse.apply_point(point)
@staticmethod
def _inverse_kinematics_xy(localized_foot_target: Point3D):
alpha = np.degrees(np.arctan2(localized_foot_target.y, localized_foot_target.x))
x_tick = np.hypot(localized_foot_target.x, localized_foot_target.y)
return alpha, x_tick
def _inverse_kinematics_xz(self, z_offset: float, x_tick: float, verbose=False):
d_offset = -z_offset
t_offset = x_tick - self.coxa_length
span = np.hypot(d_offset, t_offset)
solvable_theta1, theta1_rad = safe_arccos(
(span**2 + self.femur_length**2 - self.tibia_length**2)
/ (2 * span * self.femur_length)
)
theta1 = np.degrees(theta1_rad)
theta2 = np.degrees(np.arctan2(t_offset, d_offset))
solvable_phi, phi_rad = safe_arccos(
(self.tibia_length**2 + self.femur_length**2 - span**2)
/ (2 * self.tibia_length * self.femur_length)
)
phi = np.degrees(phi_rad)
beta = 90 - (theta1 + theta2)
gamma = 180 - phi
if verbose:
print(
f'{theta1=} - solvable={solvable_theta1}\n'
f'{theta2=}\n'
f'{phi=} - solvable={solvable_phi}\n\n'
f'{beta=}\n'
f'{gamma=}'
)
return solvable_theta1 and solvable_phi, beta, gamma
from drqp_kinematics.models import HexapodModel
from plotting import plot_hexapod
# Dr.QP Dimensions
drqp_front_offset = 0.116924 # x offset for the front and back legs
drqp_side_offset = 0.063871 # y offset fo the front and back legs
drqp_middle_offset = 0.103 # x offset for the middle legs
drqp_coxa = 0.053
drqp_femur = 0.066225
drqp_tibia = 0.123
class DrQP(HexapodModel):
def __init__(self):
super().__init__(
front_offset=drqp_front_offset,
side_offset=drqp_side_offset,
middle_offset=drqp_middle_offset,
coxa_len=drqp_coxa,
femur_len=drqp_femur,
tibia_len=drqp_tibia,
leg_rotation=[0, 0, 45],
)
drqp = DrQP()
drqp.forward_kinematics(0, -25, 110)
fig, ax, plot_data = plot_hexapod(drqp)
display_and_close(fig)
With the ability to do forward kinematics for a full robot, we can now start to work on the inverse kinematics. 1_getting_started_with_robot_ik.ipynb notebook covers the full 3D case of a single leg IK, however it works in the leg’s local coordinate frame. In order to use it for the full robot, each leg global target position needs to be converted to the leg’s local coordinate frame. Since we used matrix transformations for the forward kinematics, we can use the inverse of the body transform to convert the global target to the local coordinate frame.
def to_local(self, point):
return self.body_joint.inverse().apply_point(point)
orig_alpha, orig_beta, orig_gamma = 0, -25, 110
drqp = DrQP()
drqp.forward_kinematics(orig_alpha, orig_beta, orig_gamma)
targets = []
for leg in drqp.legs:
target = leg.tibia_end.copy()
target.label = 'Target'
target.x -= 0.08
target.y *= 1.4
reached = leg.move_to(target)
if not reached:
target.label = 'Unreachable target'
targets.append(target)
print(f'Leg {leg.label} failed to reach {target}, ended at {leg.tibia_end}')
fig, ax, plot_data = plot_hexapod(drqp, targets)
display_and_close(fig)
Leg HexapodLeg.left_middle failed to reach Point3D(-0.0800, 0.3174, -0.0945, Unreachable target), ended at Point3D(-0.0768, 0.3088, -0.0896, Foot)
Leg HexapodLeg.left_back failed to reach Point3D(-0.2844, 0.2119, -0.0945, Unreachable target), ended at Point3D(-0.2806, 0.2086, -0.0917, Foot)
Leg HexapodLeg.right_middle failed to reach Point3D(-0.0800, -0.3174, -0.0945, Unreachable target), ended at Point3D(-0.0768, -0.3088, -0.0896, Foot)
Leg HexapodLeg.right_back failed to reach Point3D(-0.2844, -0.2119, -0.0945, Unreachable target), ended at Point3D(-0.2806, -0.2086, -0.0917, Foot)
With the ability to position all legs, its time to work on the inverse kinematics for the body.
The algorithm is as follows:
Capture the reference stance
Run forward kinematics for all legs with the same angles in a desired position (neutral, wide, narrow, specific gait).
Capture global positions of all leg foot tips
Apply transform to the robot’s body (translation, rotation, twist).
Run inverse kinematics for all legs with the foot positions captured in step 1.
from drqp_kinematics.geometry import AffineTransform
orig_alpha, orig_beta, orig_gamma = 0, -25, 110
drqp = DrQP()
drqp.forward_kinematics(orig_alpha, orig_beta, orig_gamma)
targets = [leg.tibia_end.copy() for leg in drqp.legs]
drqp.body_transform = AffineTransform.from_translation(
[0.05, 0, -0.01]
) @ AffineTransform.from_rotvec([10, 10, 10], degrees=True)
unreachable_targets = []
for leg, target in zip(drqp.legs, targets):
reached = leg.move_to(target)
if not reached:
target.label = 'Unreachable target'
unreachable_targets.append(target)
print(f'Leg {leg.label} failed to reach {target}, ended at {leg.tibia_end}')
fig, ax, plot_data = plot_hexapod(drqp, unreachable_targets)
display_and_close(fig)
import math
steps = 64
x = 0.0
y = 0.0
z = 0.0
scalar = 0.05
sequence_xy_little_circle = [
AffineTransform.from_translation([x + math.cos(i) * scalar, y + math.sin(i) * scalar, z])
for i in np.linspace(np.pi, np.pi * 3, steps)
]
sequence_xz_little_circle = [
AffineTransform.from_translation([x + math.sin(i) * scalar, y, z + math.cos(i) * scalar])
for i in np.linspace(0, np.pi * 2, steps)
]
sequence_yz_little_circle = [
AffineTransform.from_translation([x, y + math.sin(i) * scalar, z + math.cos(i) * scalar])
for i in np.linspace(0, np.pi * 2, steps)
]
sequence_xyz_little_circle = [
AffineTransform.from_translation(
[x + math.cos(i) * scalar, y + math.sin(i) * scalar, z + math.cos(i) * scalar]
)
for i in np.linspace(0, np.pi * 2, steps)
]
# Plot IK solutions and targets into an animation
from plotting import animate_plot, is_sphinx_build, update_hexapod_plot
from scipy.interpolate import interp1d
orig_alpha, orig_beta, orig_gamma = 0, -25, 110
drqp = DrQP()
drqp.forward_kinematics(orig_alpha, orig_beta, orig_gamma)
targets = [leg.tibia_end.copy() for leg in drqp.legs]
transforms = [AffineTransform.identity()]
def interpolate(tf1: AffineTransform, tf2: AffineTransform, steps=10):
interp_func = interp1d([0, steps], np.stack([tf1.matrix, tf2.matrix]), axis=0)
for i in range(steps):
transforms.append(AffineTransform(interp_func(i)))
def extend_transforms(ohter_transforms, steps=10):
interpolate(transforms[-1], ohter_transforms[0], steps=steps)
transforms.extend(ohter_transforms)
def turn_transforms(axis, turn_degrees=10):
axis = np.array(axis)
for i in range(0, turn_degrees):
transforms.append(AffineTransform.from_rotvec(axis * i, degrees=True))
for i in range(turn_degrees, -turn_degrees, -1):
transforms.append(AffineTransform.from_rotvec(axis * i, degrees=True))
for i in range(-turn_degrees, 0):
transforms.append(AffineTransform.from_rotvec(axis * i, degrees=True))
turn_transforms([0, 0, 1])
turn_transforms([0, 1, 0])
turn_transforms([1, 0, 0])
turn_transforms([1, 1, 0])
turn_transforms([1, 0, 1])
turn_transforms([1, 1, 1])
extend_transforms(sequence_xy_little_circle, steps=5)
extend_transforms(sequence_xz_little_circle, steps=5)
extend_transforms(sequence_yz_little_circle, steps=5)
extend_transforms(sequence_xyz_little_circle, steps=5)
# Close the loop
interpolate(transforms[-1], transforms[0], steps=15)
fig, ax, plot_data = plot_hexapod(drqp)
def animate(frame):
drqp.body_transform = transforms[frame]
for leg, target in zip(drqp.legs, targets):
leg.move_to(target)
update_hexapod_plot(drqp, plot_data)
save_animation = False
skip_in_local_runs_because_its_slow = not is_sphinx_build()
if not skip_in_local_runs_because_its_slow:
animate_plot(
fig,
animate,
_frames=len(transforms),
_interval=20,
_interactive=False, # Interactive animation doesn't work well due to number of frames, rendering video works much better
_save_animation_name='animation' if save_animation else None,
)
---------------------------------------------------------------------------
RuntimeError Traceback (most recent call last)
File ~/checkouts/readthedocs.org/user_builds/drqp/checkouts/latest/.venv/lib/python3.12/site-packages/IPython/core/formatters.py:406, in BaseFormatter.__call__(self, obj)
404 method = get_real_method(obj, self.print_method)
405 if method is not None:
--> 406 return method()
407 return None
408 else:
File ~/checkouts/readthedocs.org/user_builds/drqp/checkouts/latest/.venv/lib/python3.12/site-packages/matplotlib/animation.py:1385, in Animation._repr_html_(self)
1383 fmt = mpl.rcParams['animation.html']
1384 if fmt == 'html5':
-> 1385 return self.to_html5_video()
1386 elif fmt == 'jshtml':
1387 return self.to_jshtml()
File ~/checkouts/readthedocs.org/user_builds/drqp/checkouts/latest/.venv/lib/python3.12/site-packages/matplotlib/animation.py:1302, in Animation.to_html5_video(self, embed_limit)
1299 path = Path(tmpdir, "temp.m4v")
1300 # We create a writer manually so that we can get the
1301 # appropriate size for the tag
-> 1302 Writer = writers[mpl.rcParams['animation.writer']]
1303 writer = Writer(codec='h264',
1304 bitrate=mpl.rcParams['animation.bitrate'],
1305 fps=1000. / self._interval)
1306 self.save(str(path), writer=writer)
File ~/checkouts/readthedocs.org/user_builds/drqp/checkouts/latest/.venv/lib/python3.12/site-packages/matplotlib/animation.py:121, in MovieWriterRegistry.__getitem__(self, name)
119 if self.is_available(name):
120 return self._registered[name]
--> 121 raise RuntimeError(f"Requested MovieWriter ({name}) not available")
RuntimeError: Requested MovieWriter (ffmpeg) not available
<matplotlib.animation.FuncAnimation at 0x7fdc2406c620>
To make all the learnings and findings reusable in other notebooks, lets move all the code into modules and double check it works.
from drqp_kinematics.models import HexapodModel
from plotting import plot_hexapod, update_hexapod_plot
hexapod = HexapodModel()
hexapod.forward_kinematics(0, -25, 110)
fig, ax, plot_data = plot_hexapod(hexapod)
leg_tips = [leg.tibia_end.copy() for leg in hexapod.legs]
hexapod.body_transform = AffineTransform.from_translation(
[0.05, 0, -0.01]
) @ AffineTransform.from_rotvec([10, 10, 10], degrees=True)
hexapod.move_legs_to(leg_tips)
update_hexapod_plot(hexapod, plot_data)
display_and_close(fig)