Getting started#
To use SeqIKPy on your own data, first, you need to install the package. You can install the package using pip:
pip install seqikpy
Once you have installed the package, you can import the package and use it to analyze your data. This tutorial will show you how to use SeqIKPy on your own data.
The following steps are required to use SeqIKPy on your own data:
Alignment of the 3D pose data (if the data is already aligned, skip this step).
Inverse kinematics calculation.
Visualization of the results.
Letās start by importing the necessary libraries and loading the data.
from pathlib import Path
import numpy as np
import matplotlib.pyplot as plt
from seqikpy.data import PTS2ALIGN, NMF_TEMPLATE, INITIAL_ANGLES, BOUNDS
from seqikpy.utils import load_file, save_file, calculate_body_size, dict_to_nparray_pose
from seqikpy.alignment import AlignPose, convert_from_anipose_to_dict
from seqikpy.kinematic_chain import KinematicChainSeq
from seqikpy.head_inverse_kinematics import HeadInverseKinematics
from seqikpy.leg_inverse_kinematics import LegInvKinSeq
from seqikpy.visualization import plot_3d_points, animate_3d_points
# Load the data, below contains the kinematics during locomotion
path_to_data = Path('...')
pose_data = load_file(
path_to_data
)
Alignment of the 3D pose data#
The alignment process serves two purposes:
Transforming the 3D pose data to the biomechanical modelās frame of reference.
(OPTIONAL) Scaling the animal 3D data to match the size of the biomechanical model if the biomechanical modelās size is given to the
AlignPose
class. This option is useful if you want to scale all of your data to one body size, or if you want to perform kinematic replay in simulation using the body model.Alternatively, the user can provide the experimental animalās body size into the class. In that case, the scaling will ensure that the animalās limb size is the same throughout the trial duration. This will work as a denoising step for the kinematic data.
Note
Note that, the alignment process requires the data to be in a dictionary format with specific key values.
For each leg to calculate the inverse kinematics, the dictionary should contain
<R or L><F or M or H>_leg
as a key value, which consists of an array of (N_frames, key_points=5, axes=3). The key point order should be in from proximal to distal leg segments (i.e., Coxa, Femur, Tibia, Tarsus, Claw).For the head joint angles, the dictionary should contain
L_head
,R_head
,Thorax
.L_head
andR_head
contain (N_frames, key_points=3, axes=3) where key points are neck, the base and tip of the antenna.Thorax
contains (N_frames, key_points=3, axes=3) where key points are the left wing hinge joint, mid thorax, and the right wing hinge joint.
Option 1: align the kinematics to the body model.
This will be useful for the kinematic replay, in which case you can use the following template.
NMF_TEMPLATE = {
"RF_Coxa": np.array([0.33, -0.17, 1.07]),
"RF_Femur": np.array([0.33, -0.17, 0.67]),
"RF_Tibia": np.array([0.33, -0.17, -0.02]),
"RF_Tarsus": np.array([0.33, -0.17, -0.56]),
"RF_Claw": np.array([0.33, -0.17, -1.19]),
"LF_Coxa": np.array([0.33, 0.17, 1.07]),
"LF_Femur": np.array([0.33, 0.17, 0.67]),
"LF_Tibia": np.array([0.33, 0.17, -0.02]),
"LF_Tarsus": np.array([0.33, 0.17, -0.56]),
"LF_Claw": np.array([0.33, 0.17, -1.19]),
}
align = AlignPose(
pose_data_dict=pose_data,
legs_list=['RF', 'LF'],
include_claw=False,
body_template=NMF_TEMPLATE,
body_size=None,
log_level="INFO"
)
Option 2: align the kinematics to the body size of the experimental animal
This will be useful for the kinematic analysis.
# Create yor own template from the recorded 3D kinematics
# See `seqikpy.utils` for the functions to calculate the body size
EXP_TEMPLATE = {
....
}
align = AlignPose(
pose_data_dict=pose_data,
legs_list=['RF', 'LF'],
include_claw=False,
body_size=seqikpy.utils.calculate_body_size(EXP_TEMPLATE, ['RF', 'LF']),
log_level="INFO"
)
Calculate the aligned pose#
aligned_pos = align.align_pose(export_path=None)
Option 3: the pose quality is already good enough, no need for the alignment.
Then proceed to the next step, inverse kinematics calculation.
Sequential Inverse Kinematics#
Below, we will start the inverse kinematics process using seqikpy
The initial step is to determine the initial seeds for the first time step. While it is not crucial to have good initial seeds, having initial values out of the joint DOF limits will raise an error.
Secondly, we need to define some lower and upper limits for the joints. Again, having informative bounds is helpful to prevent singularities in the optimization. For example, Tibia-tarsus pitch joint should not exceed 0 degrees (always negative since the rotation is clockwise). So, it makes sense to assign an upper limit of 0 degrees for this joint.
For now, we use the default values imported from seqikpy.data
module.
# Initialize the necessary classes
kin_chain = KinematicChainSeq(
bounds_dof=BOUNDS,
# Put the body size you prefer (biomechenical model or real animal size)
body_size=body_size,
legs_list=['RF', 'LF'],
)
class_seq_ik = LegInvKinSeq(
# Aligned or loaded pose
aligned_pos=aligned_pos,
kinematic_chain_class=kin_chain,
initial_angles=INITIAL_ANGLES,
log_level="INFO",
)
The below code will commence the IK process, which consists of four stages per kinematic chain. For more details, please visit the methodology page.
After the process is over, run_ik_and_fk
will save the results in two separete .pkl files:
leg_joint_angles.pkl
-> pickle file that contains the leg joint anglesforward_kinematics.pkl
-> 3D position of the legs construction from the calculated leg joint angles, useful for visualization and debugging purposes
leg_joint_angles, forward_kinematics = class_seq_ik.run_ik_and_fk(
export_path=data_path,
hide_progress_bar=False
)
2D visualization of the joint angles#
# Let's plot the joint angles for all six legs
leg_joint_angle_names = [
"ThC_yaw",
"ThC_pitch",
"ThC_roll",
"CTr_pitch",
"CTr_roll",
"FTi_pitch",
"TiTa_pitch",
]
fig, axs = plt.subplots(1, 2, figsize=(9, 2), dpi=200)
axs = axs.flatten()
for angle_name in leg_joint_angle_names:
for i, leg_name in enumerate(["RF", "LF"]):
axs[i].plot(
np.rad2deg(leg_joint_angles[f"Angle_{leg_name}_{angle_name}"]),
label=angle_name,
lw=2,
)
axs[i].set_ylabel(leg_name)
time_step = 1e-2
for ax in axs:
ax.set_xticklabels(np.array(ax.get_xticks() * time_step, dtype='f'))
axs[-1].set_xlabel("Time (sec)")
axs[-2].set_xlabel("Time (sec)")
axs[1].legend(bbox_to_anchor=(1.1, 1), frameon=False)
plt.suptitle("Leg joint angles (deg)")
plt.tight_layout()
# fig.savefig("../results/alljoints_follow_ikpy_left.png", bbox_inches="tight")
plt.show()
Animation of the target 3D pose and the forward kinematics#
n_frames = 300
# change the neck points to an array
aligned_pos['Neck'] = np.tile(aligned_pos['Neck'], (n_frames, 1, 1))
axim, elev = 90, 0
animate_3d_points(
points3d=aligned_pos,
points3d_second=forward_kinematics,
export_path=data_path / f'fk_ik_elev_{elev}_azim_{azim}.mp4',
frame_no=n_frames,
elev=elev,
azim=azim,
fps=100,
)