All Projects → AdaptiveMotorControlLab → DLC2Kinematics

AdaptiveMotorControlLab / DLC2Kinematics

Licence: Unknown, Unknown licenses found Licenses found Unknown LICENSE Unknown license.md
a module for kinematic analysis of deeplabcut outputs

Programming Languages

Jupyter Notebook
11667 projects
python
139335 projects - #7 most used programming language

Projects that are alternatives of or similar to DLC2Kinematics

Pinocchio
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
Stars: ✭ 432 (+345.36%)
Mutual labels:  kinematics
Ikbt
A python package to solve robot arm inverse kinematics in symbolic form
Stars: ✭ 97 (+0%)
Mutual labels:  kinematics
Rigidbodydynamics.jl
Julia implementation of various rigid body dynamics and kinematics algorithms
Stars: ✭ 184 (+89.69%)
Mutual labels:  kinematics
Dart
Dynamic Animation and Robotics Toolkit
Stars: ✭ 596 (+514.43%)
Mutual labels:  kinematics
K
k: Kinematics Library for rust-lang
Stars: ✭ 66 (-31.96%)
Mutual labels:  kinematics
Venom
All Terrain Autonomous Quadruped
Stars: ✭ 145 (+49.48%)
Mutual labels:  kinematics
Hexapod
Blazing fast hexapod robot simulator for the web.
Stars: ✭ 370 (+281.44%)
Mutual labels:  kinematics
Helicopter-Simulation
A complete 6DOF helicopter simulation (physics engine + visualization)
Stars: ✭ 45 (-53.61%)
Mutual labels:  kinematics
Wave geometry
Manifold geometry with fast automatic derivatives and coordinate frame semantics checking
Stars: ✭ 92 (-5.15%)
Mutual labels:  kinematics
Kinematics
🤖 JavaScript 6DOF robot kinematics library
Stars: ✭ 187 (+92.78%)
Mutual labels:  kinematics
Robotics Toolbox Matlab
Robotics Toolbox for MATLAB
Stars: ✭ 601 (+519.59%)
Mutual labels:  kinematics
Bullet3
Bullet Physics SDK: real-time collision detection and multi-physics simulation for VR, games, visual effects, robotics, machine learning etc.
Stars: ✭ 8,714 (+8883.51%)
Mutual labels:  kinematics
Duik 15
Duduf IK & Animation Tools for Adobe After Effects
Stars: ✭ 152 (+56.7%)
Mutual labels:  kinematics
Hexapod Robot Simulator
A hexapod robot simulator built from first principles
Stars: ✭ 577 (+494.85%)
Mutual labels:  kinematics
Pybotics
The Python Toolbox for Robotics
Stars: ✭ 192 (+97.94%)
Mutual labels:  kinematics
Rl
The Robotics Library (RL) is a self-contained C++ library for rigid body kinematics and dynamics, motion planning, and control.
Stars: ✭ 391 (+303.09%)
Mutual labels:  kinematics
Makelangelo Firmware
CNC firmware for many different control boards and kinematic systems. Originally the brain of the Makelangelo art robot.
Stars: ✭ 116 (+19.59%)
Mutual labels:  kinematics
MARIO
Official Repository for ROS-based Manipulator, implemented with ESP32
Stars: ✭ 73 (-24.74%)
Mutual labels:  kinematics
RobotArmHelix
3D Simulation, forward and inverse kinematics of a robotic arm in C# using WPF and helix-toolkit
Stars: ✭ 84 (-13.4%)
Mutual labels:  kinematics
Robopy
Robopy is a python port for Robotics Toolbox in Matlab created by Peter Corke
Stars: ✭ 186 (+91.75%)
Mutual labels:  kinematics

PyPI version Downloads Downloads Code style: black Generic badge codecov Twitter Follow DOI

cam cntrl

A post-deeplabcut module for kinematic analysis

This repo will continue to grow, but here are some helper functions to get you started. Note, the API is subject to change. You can run the functions on data files obtained from running inference with DeepLabCut. Currently, this code requires python 3.8 onwards. We recommend using the DEEPLABCUT conda file, and then simply run pip install dlc2kinematics within your environment.

Quick start

pip install dlc2kinematics

Useage

import dlc2kinematics

Load data:

df, bodyparts, scorer = dlc2kinematics.load_data(<path of the h5 file>)

Basic Operations

Compute velocity:

  • For all bodyparts:
    df_vel = dlc2kinematics.compute_velocity(df,bodyparts=['all'])
  • For only few bodyparts:
    df_vel = dlc2kinematics.compute_velocity(df,bodyparts=['nose','joystick'])

Compute acceleration:

  • For all bodyparts:
    df_acc = dlc2kinematics.compute_acceleration(df,bodyparts=['all'])
  • For only few bodyparts:
    df_vel = dlc2kinematics.compute_acceleration(df,bodyparts=['nose','joystick'])

Compute speed:

df_speed = dlc2kinematics.compute_speed(df,bodyparts=['nose','joystick'])

Computations in joint coordinates

To compute joint angles, we first create a dictionary where keys are the joint angles and the corresponding values are the set of bodyparts:

joints_dict= {}
joints_dict['R-Elbow']  = ['R_shoulder', 'Right_elbow', 'Right_wrist']

and compute the joint angles with

joint_angles = dlc2kinematics.compute_joint_angles(df,joints_dict)

Compute joint angular velocity with

joint_vel = dlc2kinematics.compute_joint_velocity(joint_angles)

Compute joint angular acceleration with

joint_acc = dlc2kinematics.compute_joint_acceleration(joint_angles)

Compute correlation of angular velocity

corr = dlc2kinematics.compute_correlation(joint_vel, plot=True)

Compute PCA of angular velocity with

pca = dlc2kinematics.compute_pca(joint_vel, plot=True)

PCA-based reconstruction of postures

Compute and plot PCA based on posture reconstruction with:

dlc2kinematics.plot_3d_pca_reconstruction(df_vel, n_components=10, framenumber=500,
                                     bodyparts2plot=bodyparts2plot, bp_to_connect=bp_to_connect)

UMAP Embeddings

embedding, transformed_data = dlc2kinematics.compute_umap(df, key=['LeftForelimb', 'RightForelimb'], chunk_length=30, fit_transform=True, n_neighbors=30, n_components=3,metric="euclidean")

dlc2kinematics.plot_umap(transformed_data, size=5, alpha=1, color="indigo", figsize=(10, 6))

Contributing

  • If you spot an issue or have a question, please open an issue with a suitable tag.
  • For code contributions:
    • please see the contributing guide.
    • Please reference all issues this PR addresses in the description text.
    • Before submitting your PR, ensure all code is formatted properly by running
      black .
      in the root directory.
    • Assign a reviewer, typically MMathisLab.
    • sign CLA.

Acknowledgements

This code is a collect of contributions from members of the Mathis Laboratory over the years. In particular (alphabetical): Michael Beauzile, Sebastien Hausmann, Jessy Lauer, Alexander Mathis, Mackenzie Mathis, Tanmay Nath, Steffen Schneider.

If you use this code, please cite:

@software{mathis_mackenzie_2020_6669074,
  author       = {Mathis, Mackenzie and
                  Lauer, Jessy and
                  Nath, Tanmay and
                  Beauzile, Michael and
                  Hausmann, Sébastien and
                  Schneider, Steffen and
                  Mathis, Alexander},
  title        = {{DLC2Kinematics: a post-deeplabcut module for 
                   kinematic analysis}},
  month        = feb,
  year         = 2020,
  publisher    = {Zenodo},
  version      = {v0.0.4},
  doi          = {10.5281/zenodo.6669074},
  url          = {https://doi.org/10.5281/zenodo.6669074}
}
Note that the project description data, including the texts, logos, images, and/or trademarks, for each open source project belongs to its rightful owner. If you wish to add or remove any projects, please contact us at [email protected].