[![Continuous integration](https://github.com/perfanalytics/pose2sim/actions/workflows/continuous-integration.yml/badge.svg?branch=main)](https://github.com/perfanalytics/pose2sim/actions/workflows/continuous-integration.yml)
[![PyPI version](https://badge.fury.io/py/Pose2Sim.svg)](https://badge.fury.io/py/Pose2Sim) \
[![Downloads](https://static.pepy.tech/badge/pose2sim)](https://pepy.tech/project/pose2sim)
[![Stars](https://img.shields.io/github/stars/perfanalytics/pose2sim)](https://github.com/perfanalytics/pose2sim/stargazers)
[![GitHub forks](https://img.shields.io/github/forks/perfanalytics/pose2sim)](https://GitHub.com/perfanalytics/pose2sim/forks)
[![GitHub issues](https://img.shields.io/github/issues/perfanalytics/pose2sim)](https://github.com/perfanalytics/pose2sim/issues)
[![GitHub issues-closed](https://img.shields.io/github/issues-closed/perfanalytics/pose2sim)](https://GitHub.com/perfanalytics/pose2sim/issues?q=is%3Aissue+is%3Aclosed)
\
[![status](https://joss.theoj.org/papers/a31cb207a180f7ac9838d049e3a0de26/status.svg)](https://joss.theoj.org/papers/a31cb207a180f7ac9838d049e3a0de26)
[![DOI](https://zenodo.org/badge/501642916.svg)](https://zenodo.org/doi/10.5281/zenodo.10658947)
[![License](https://img.shields.io/badge/License-BSD_3--Clause-blue.svg)](https://opensource.org/licenses/BSD-3-Clause)
# Pose2Sim
##### N.B:. Please set undistort_points and handle_LR_swap to false for now since it currently leads to inaccuracies. I'll try to fix it soon.
> **_News_: Version 0.8:**\
> **Automatic camera synchronization is now supported!**\
> **Other recently added features**: Multi-person analysis, Blender visualization, Marker augmentation, Automatic batch processing.
> To upgrade, type `pip install pose2sim --upgrade`.
`Pose2Sim` provides a workflow for 3D markerless kinematics, as an alternative to the more usual marker-based motion capture methods. It aims to provide a free tool to obtain research-grade results from consumer-grade equipment. Any combination of phone, webcam, GoPro, etc. can be used.
Pose2Sim stands for "OpenPose to OpenSim", as it uses OpenPose inputs (2D keypoints coordinates obtained from multiple videos) and leads to an OpenSim result (full-body 3D joint angles). Other 2D pose estimators such as BlazePose (MediaPipe), DeepLabCut, AlphaPose, can now be used as inputs.
If you can only use one single camera and don't mind losing some accuracy, please consider using [Sports2D](https://github.com/davidpagnon/Sports2D).
> *N.B.:* As always, I am more than happy to welcome contributors (see [How to contribute](#how-to-contribute)).
**Pose2Sim releases:**
- [x] **v0.1** *(08/2021)*: Published paper
- [x] **v0.2** *(01/2022)*: Published code
- [x] **v0.3** *(01/2023)*: Supported other pose estimation algorithms
- [x] **v0.4** *(07/2023)*: New calibration tool based on scene measurements
- [x] **v0.5** *(12/2023)*: Automatic batch processing
- [x] **v0.6** *(02/2024)*: Marker augmentation, Blender visualizer
- [x] **v0.7** *(03/2024)*: Multi-person analysis
- [x] **v0.8 *(04/2024)*: New synchronization tool**
- [ ] v0.9: Calibration based on keypoint detection, Handling left/right swaps, Correcting lens distortions
- [ ] v0.10: Graphical User Interface
- [ ] v1.0: First accomplished release
# Contents
1. [Installation and Demonstration](#installation-and-demonstration)
1. [Installation](#installation)
2. [Demonstration Part-1: Triangulate OpenPose outputs](#demonstration-part-1-build-3d-trc-file-on-python)
3. [Demonstration Part-2: Obtain 3D joint angles with OpenSim](#demonstration-part-2-obtain-3d-joint-angles-with-opensim)
4. [Demonstration Part-3 (optional): Visualize your results with Blender](#demonstration-part-3-optional-visualize-your-results-with-blender)
5. [Demonstration Part-4 (optional): Try multi-person analysis](#demonstration-part-4-optional-try-multi-person-analysis)
2. [Use on your own data](#use-on-your-own-data)
1. [Setting your project up](#setting-your-project-up)
1. [Retrieve the folder structure](#retrieve-the-folder-structure)
2. [Single Trial vs. Batch processing](#single-trial-vs-batch-processing)
2. [2D pose estimation](#2d-pose-estimation)
1. [With OpenPose](#with-openpose)
2. [With BlazePose (Mediapipe)](#with-blazepose-mediapipe)
3. [With DeepLabCut](#with-deeplabcut)
4. [With AlphaPose](#with-alphapose)
4. [Camera calibration](#camera-calibration)
1. [Convert from Qualisys, Optitrack, Vicon, OpenCap, EasyMocap, or bioCV](#convert-from-qualisys-optitrack-vicon-opencap-easymocap-or-biocv)
2. [Calculate from scratch](#calculate-from-scratch)
5. [Synchronizing, Tracking, Triangulating, Filtering](#synchronizing-tracking-triangulating-filtering)
1. [Synchronization](#synchronization)
2. [Associate persons across cameras](#associate-persons-across-cameras)
3. [Triangulating keypoints](#triangulating-keypoints)
4. [Filtering 3D coordinates](#filtering-3d-coordinates)
5. [Marker augmentation](#marker-augmentation)
6. [OpenSim kinematics](#opensim-kinematics)
1. [OpenSim Scaling](#opensim-scaling)
2. [OpenSim Inverse kinematics](#opensim-inverse-kinematics)
3. [Command Line](#command-line)
3. [Utilities](#utilities)
4. [How to cite and how to contribute](#how-to-cite-and-how-to-contribute)
1. [How to cite](#how-to-cite)
2. [How to contribute and to-do list](#how-to-contribute-and-to-do-list)
# Installation and Demonstration
## Installation
1. **Install OpenPose** (instructions [there](https://github.com/CMU-Perceptual-Computing-Lab/openpose/blob/master/doc/installation/0_index.md)). \
*Windows portable demo is enough.*
2. **Install OpenSim 4.x** ([there](https://simtk.org/frs/index.php?group_id=91)). \
*Tested up to v4.5 on Windows. Has to be compiled from source on Linux (see [there](https://simtk-confluence.stanford.edu:8443/display/OpenSim/Linux+Support)).*
3. ***Optional.*** *Install Anaconda or [Miniconda](https://docs.conda.io/en/latest/miniconda.html). \
Open an Anaconda terminal and create a virtual environment with typing:*
conda create -n Pose2Sim python=3.8 -y conda activate Pose2Sim3. **Install Pose2Sim**:\ If you don't use Anaconda, type `python -V` in terminal to make sure python>=3.8 is installed. - OPTION 1: **Quick install:** Open a terminal. ``` cmd pip install pose2sim ``` - OPTION 2: **Build from source and test the last changes:** Open a terminal in the directory of your choice and Clone the Pose2Sim repository. ``` cmd git clone --depth 1 https://github.com/perfanalytics/pose2sim.git cd pose2sim pip install . ``` ## Demonstration Part-1: Build 3D TRC file on Python > _**This demonstration provides an example experiment of a person balancing on a beam, filmed with 4 calibrated cameras processed with OpenPose.**_ Open a terminal, enter `pip show pose2sim`, report package location. \ Copy this path and go to the Single participant Demo folder: `cd
SingleTrial \ ├── calibration \ ├── pose \ └── Config.toml#### Batch processing For batch processing, each session directory should follow a `Session -> Participant -> Trial` structure, with a `Config.toml` file in each of the directory levels.
Session_s1 \ Config.toml ├── Calibration\ └── Participant_p1 \ Config.toml └── Trial_t1 \ Config.toml └── pose \Run Pose2Sim from the `Session` folder if you want to batch process the whole session, from the `Participant` folder if you want to batch process all the trials of a participant, or from the `Trial` folder if you want to process a single trial. There should be one `Calibration` folder per session. Global parameters are given in the `Config.toml` file of the `Session` folder, and can be altered for specific `Participants` or `Trials` by uncommenting keys and their values in their respective Config.toml files.\ Try uncommenting `[project]` and set `frame_range = [10,300]` for a Participant for example, or uncomment `[filtering.butterworth]` and set `cut_off_frequency = 10` for a Trial. ## 2D pose estimation > _**Estimate 2D pose from images with Openpose or another pose estimation solution.**_ \ N.B.: First film a short static pose that will be used for scaling the OpenSim model (A-pose for example), and then film your motions of interest.\ N.B.: Note that the names of your camera folders must follow the same order as in the calibration file, and end with '_json'. ### With OpenPose: The accuracy and robustness of Pose2Sim have been thoroughly assessed only with OpenPose, and especially with the BODY_25B model. Consequently, we recommend using this 2D pose estimation solution. See [OpenPose repository](https://github.com/CMU-Perceptual-Computing-Lab/openpose) for installation and running. * Open a command prompt in your **OpenPose** directory. \ Launch OpenPose for each `videos` folder: ``` cmd bin\OpenPoseDemo.exe --model_pose BODY_25B --video
[Blazepose_runsave.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/Blazepose_runsave.py) Runs BlazePose on a video, and saves coordinates in OpenPose (json) or DeepLabCut (h5 or csv) format. [DLC_to_OpenPose.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/DLC_to_OpenPose.py) Converts a DeepLabCut (h5) 2D pose estimation file into OpenPose (json) files. [AlphaPose_to_OpenPose.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/AlphaPose_to_OpenPose.py) Converts AlphaPose single json file to OpenPose frame-by-frame files.
[calib_toml_to_easymocap.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/calib_toml_to_easymocap.py) Converts an OpenCV .toml calibration file to EasyMocap intrinsic and extrinsic .yml calibration files. [calib_easymocap_to_toml.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/calib_easymocap_to_toml.py) Converts EasyMocap intrinsic and extrinsic .yml calibration files to an OpenCV .toml calibration file. [calib_from_checkerboard.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/calib_from_checkerboard.py) Calibrates cameras with images or a video of a checkerboard, saves calibration in a Pose2Sim .toml calibration file. You should probably use Pose2Sim.calibration() instead, which is much easier and better. [calib_qca_to_toml.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/calib_qca_to_toml.py) Converts a Qualisys .qca.txt calibration file to the Pose2Sim .toml calibration file (similar to what is used in [AniPose](https://anipose.readthedocs.io/en/latest/)). [calib_toml_to_qca.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/calib_toml_to_qca.py) Converts a Pose2Sim .toml calibration file (e.g., from a checkerboard) to a Qualisys .qca.txt calibration file. [calib_toml_to_opencap.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/calib_toml_to_opencap.py) Converts an OpenCV .toml calibration file to OpenCap .pickle calibration files. [calib_toml_to_opencap.py]( ) To convert OpenCap calibration tiles to a .toml file, please use Pose2Sim.calibration() and set convert_from = 'opencap' in Config.toml.
[json_display_with_img.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/json_display_with_img.py) Overlays 2D detected json coordinates on original raw images. High confidence keypoints are green, low confidence ones are red. [json_display_without_img.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/json_display_without_img.py) Plots an animation of 2D detected json coordinates. [trc_plot.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_plot.py) Displays X, Y, Z coordinates of each 3D keypoint of a TRC file in a different matplotlib tab.
[trc_from_easymocap.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_from_easymocap.py) Convert EasyMocap results keypoints3d .json files to .trc. [c3d_to_trc.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/c3d_to_trc.py) Converts 3D point data from a .c3d file to a .trc file compatible with OpenSim. No analog data (force plates, emg) nor computed data (angles, powers, etc.) are retrieved. [trc_to_c3d.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_to_c3d.py) Converts 3D point data from a .trc file to a .c3d file compatible with Visual3D. [trc_desample.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_desample.py) Undersamples a trc file. [trc_Zup_to_Yup.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_Zup_to_Yup.py) Changes Z-up system coordinates to Y-up system coordinates. [trc_filter.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_filter.py) Filters trc files. Available filters: Butterworth, Kalman, Butterworth on speed, Gaussian, LOESS, Median. [trc_gaitevents.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_gaitevents.py) Detects gait events from point coordinates according to [Zeni et al. (2008)](https://www.sciencedirect.com/science/article/abs/pii/S0966636207001804?via%3Dihub). [trc_combine.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_combine.py) Combine two trc files, for example a triangulated DeepLabCut trc file and a triangulated OpenPose trc file. [trc_from_mot_osim.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/trc_from_mot_osim.py) Build a trc file from a .mot motion file and a .osim model file. [bodykin_from_mot_osim.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/bodykin_from_mot_osim.py) Converts a mot file to a .csv file with rotation and orientation of all segments. [reproj_from_trc_calib.py](https://github.com/perfanalytics/pose2sim/blob/main/Pose2Sim/Utilities/reproj_from_trc_calib.py) Reprojects 3D coordinates of a trc file to the image planes defined by a calibration file. Output in OpenPose or DeepLabCut format.
✔ **Pose:** Support OpenPose [body_25b](https://github.com/CMU-Perceptual-Computing-Lab/openpose_train/tree/master/experimental_models#body_25b-model---option-2-recommended) for more accuracy, [body_135](https://github.com/CMU-Perceptual-Computing-Lab/openpose_train/tree/master/experimental_models#single-network-whole-body-pose-estimation-model) for pronation/supination. ✔ **Pose:** Support [BlazePose](https://developers.google.com/mediapipe/solutions/vision/pose_landmarker) for faster inference (on mobile device). ✔ **Pose:** Support [DeepLabCut](http://www.mackenziemathislab.org/deeplabcut) for training on custom datasets. ✔ **Pose:** Support [AlphaPose](https://github.com/MVIG-SJTU/AlphaPose) as an alternative to OpenPose. ✔ **Pose:** Define custom model in config.toml rather than in skeletons.py. ▢ **Pose:** Support [MMPose](https://github.com/open-mmlab/mmpose), [SLEAP](https://sleap.ai/), etc. ▢ **Pose:** Integrate pose estimation within Pose2Sim (via MMPose). ▢ **Pose:** Directly reading from DeepLabCut .csv or .h5 files instead of converting to .json (triangulation, person association, calibration, synchronization...) ▢ **Pose:** GUI help for DeepLabCut model creation. ✔ **Calibration:** Convert [Qualisys](https://www.qualisys.com) .qca.txt calibration file. ✔ **Calibration:** Convert [Optitrack](https://optitrack.com/) extrinsic calibration file. ✔ **Calibration:** Convert [Vicon](http://www.vicon.com/Software/Nexus) .xcp calibration file. ✔ **Calibration:** Convert [OpenCap](https://www.opencap.ai/) .pickle calibration files. ✔ **Calibration:** Convert [EasyMocap](https://github.com/zju3dv/EasyMocap/) .yml calibration files. ✔ **Calibration:** Convert [bioCV](https://github.com/camera-mc-dev/.github/blob/main/profile/mocapPipe.md) calibration files. ✔ **Calibration:** Easier and clearer calibration procedure: separate intrinsic and extrinsic parameter calculation, edit corner detection if some are wrongly detected (or not visible). ✔ **Calibration:** Possibility to evaluate extrinsic parameters from cues on scene. ▢ **Calibration:** Once object points have been detected or clicked once, track them for live calibration of moving cameras. Propose to click again when they are lost. ▢ **Calibration:** Calibrate cameras by pairs and compute average extrinsic calibration with [aniposelib](https://github.com/lambdaloop/aniposelib/blob/d03b485c4e178d7cff076e9fe1ac36837db49158/aniposelib/utils.py#L167). ▢ **Calibration:** Fine-tune calibration with bundle adjustment. ▢ **Calibration:** Support ChArUco board detection (see [there](https://mecaruco2.readthedocs.io/en/latest/notebooks_rst/Aruco/sandbox/ludovic/aruco_calibration_rotation.html)). ▢ **Calibration:** Calculate calibration with points rather than board. (1) SBA calibration with wand (cf [Argus](https://argus.web.unc.edu), see converter [here](https://github.com/backyardbiomech/DLCconverterDLT/blob/master/DLTcameraPosition.py)). Set world reference frame in the end. ▢ **Calibration:** Alternatively, self-calibrate with [OpenPose keypoints](https://ietresearch.onlinelibrary.wiley.com/doi/full/10.1049/cvi2.12130). Set world reference frame in the end. ▢ **Calibration:** Convert [fSpy calibration](https://fspy.io/) based on vanishing point. ✔ **Synchronization:** Synchronize cameras on keypoint speeds. ✔ **Person Association:** Automatically choose the main person to triangulate. ✔ **Person Association:** Multiple persons association. 1. Triangulate all the persons whose reprojection error is below a certain threshold (instead of only the one with minimum error), and then track in time with speed cf [Slembrouck 2020](https://link.springer.com/chapter/10.1007/978-3-030-40605-9_15)? or 2. Based on affinity matrices [Dong 2021](https://arxiv.org/pdf/1901.04111.pdf)? or 3. Based on occupancy maps [Yildiz 2012](https://link.springer.com/chapter/10.1007/978-3-642-35749-7_10)? or 4. With a neural network [Huang 2023](https://arxiv.org/pdf/2304.09471.pdf)? ✔ **Triangulation:** Triangulation weighted with confidence. ✔ **Triangulation:** Set a likelihood threshold below which a camera should not be used, a reprojection error threshold, and a minimum number of remaining cameras below which triangulation is skipped for this frame. ✔ **Triangulation:** Interpolate missing frames (cubic, bezier, linear, slinear, quadratic) ✔ **Triangulation:** Show mean reprojection error in px and in mm for each keypoint. ✔ **Triangulation:** Show how many cameras on average had to be excluded for each keypoint. ✔ **Triangulation:** Evaluate which cameras were the least reliable. ✔ **Triangulation:** Show which frames had to be interpolated for each keypoint. ✔ **Triangulation:** Solve limb swapping (although not really an issue with Body_25b). Try triangulating with opposite side if reprojection error too large. Alternatively, ignore right and left sides, use RANSAC or SDS triangulation, and then choose right or left by majority voting. More confidence can be given to cameras whose plane is the most coplanar to the right/left line. ✔ **Triangulation:** [Undistort](https://docs.opencv.org/3.4/da/d54/group__imgproc__transform.html#ga887960ea1bde84784e7f1710a922b93c) 2D points before triangulating (and [distort](https://github.com/lambdaloop/aniposelib/blob/d03b485c4e178d7cff076e9fe1ac36837db49158/aniposelib/cameras.py#L301) them before computing reprojection error). ✔ **Triangulation:** Offer the possibility to augment the triangulated data with [the OpenCap LSTM](https://github.com/stanfordnmbl/opencap-core/blob/main/utilsAugmenter.py). Create "BODY_25_AUGMENTED" model, Scaling_setup, IK_Setup. ✔ **Triangulation:** Multiple person kinematics (output multiple .trc coordinates files). Triangulate all persons with reprojection error above threshold, and identify them by minimizing their displacement across frames. ▢ **Triangulation:** Pre-compile weighted_triangulation and reprojection with @jit(nopython=True, parallel=True) for faster execution. ▢ **Triangulation:** Offer the possibility of triangulating with Sparse Bundle Adjustment (SBA), Extended Kalman Filter (EKF), Full Trajectory Estimation (FTE) (see [AcinoSet](https://github.com/African-Robotics-Unit/AcinoSet)). ▢ **Triangulation:** Implement normalized DLT and RANSAC triangulation, Outlier rejection (sliding z-score?), as well as a [triangulation refinement step](https://doi.org/10.1109/TMM.2022.3171102). ▢ **Triangulation:** Track hands and face (won't be taken into account in OpenSim at this stage). ✔ **Filtering:** Available filtering methods: Butterworth, Butterworth on speed, Gaussian, Median, LOESS (polynomial smoothing). ✔ **Filtering:** Implement Kalman filter and Kalman smoother. ▢ **Filtering:** Implement [smoothNet](https://github.com/perfanalytics/pose2sim/issues/29) ✔ **OpenSim:** Integrate better spine from [lifting fullbody model](https://pubmed.ncbi.nlm.nih.gov/30714401) to the [gait full-body model](https://nmbl.stanford.edu/wp-content/uploads/07505900.pdf), more accurate for the knee. ✔ **OpenSim:** Optimize model marker positions as compared to ground-truth marker-based positions. ✔ **OpenSim:** Add scaling and inverse kinematics setup files. ✔ **OpenSim:** Add full model with contact spheres ([SmoothSphereHalfSpaceForce](https://simtk.org/api_docs/opensim/api_docs/classOpenSim_1_1SmoothSphereHalfSpaceForce.html#details)) and full-body muscles ([DeGrooteFregly2016Muscle](https://simtk.org/api_docs/opensim/api_docs/classOpenSim_1_1DeGrooteFregly2016Muscle.html#details)), for [Moco](https://opensim-org.github.io/opensim-moco-site/) for example. ✔ **OpenSim:** Add model with [ISB shoulder](https://github.com/stanfordnmbl/opencap-core/blob/main/opensimPipeline/Models/LaiUhlrich2022_shoulder.osim). ▢ **OpenSim:** Integrate OpenSim in Pose2Sim. ▢ **OpenSim:** Do not require a separate scaling trial: scale on the 10 slowest frames of the moving trial instead. ▢ **OpenSim:** Implement optimal fixed-interval Kalman smoothing for inverse kinematics ([this OpenSim fork](https://github.com/antoinefalisse/opensim-core/blob/kalman_smoother/OpenSim/Tools/InverseKinematicsKSTool.cpp)), or [Biorbd](https://github.com/pyomeca/biorbd/blob/f776fe02e1472aebe94a5c89f0309360b52e2cbc/src/RigidBody/KalmanReconsMarkers.cpp)) ✔ **GUI:** Blender add-on (cf [MPP2SOS](https://blendermarket.com/products/mocap-mpp2soss)), [Maya-Mocap](https://github.com/davidpagnon/Maya-Mocap) and [BlendOsim](https://github.com/JonathanCamargo/BlendOsim). ▢ **GUI:** App or webapp (e.g., with [Napari](https://napari.org/stable). ▢ **GUI:** 3D plot of cameras and of triangulated keypoints. ▢ **GUI:** Demo on Google Colab (see [Sports2D](https://bit.ly/Sports2D_Colab) for OpenPose and Python package installation on Google Drive). ✔ **Demo:** Provide Demo data for users to test the code. ✔ **Demo:** Add videos for users to experiment with other pose detection frameworks ✔ **Demo:** Time shift videos and json to demonstrate synchronization ✔ **Demo:** Add another virtual person to demonstrate personAssociation ▢ **Tutorials:** Make video tutorials. ▢ **Doc:** Use [Sphinx](https://www.sphinx-doc.org/en/master), [MkDocs](https://www.mkdocs.org), or (maybe better), [github.io](https://docs.github.com/fr/pages/quickstart) for clearer documentation. ✔ **Pip package** ✔ **Batch processing** (also enable non-batch processing) ✔ **Catch errors** ▢ **Conda package** ▢ **Docker image** ▢ Run pose estimation and OpenSim from within Pose2Sim ▢ Real-time: Run Pose estimation, Person association, Triangulation, Kalman filter, IK frame by frame (instead of running each step for all frames) ▢ Config parameter for non batch peocessing ▢ **Run from command line via click or typer** ▢ **Utilities**: Export other data from c3d files into .mot or .sto files (angles, powers, forces, moments, GRF, EMG...) ▢ **Utilities**: Create trc_to_c3d.py script ✔ **Bug:** calibration.py. FFMPEG error message when calibration files are images. See [there](https://github.com/perfanalytics/pose2sim/issues/33#:~:text=In%20order%20to%20check,filter%20this%20message%20yet.). ▢ **Bug:** common.py, class plotWindow(). Python crashes after a few runs of `Pose2Sim.filtering()` when `display_figures=true`. See [there](https://github.com/superjax/plotWindow/issues/7).