Skip to content

Markerless kinematics with any cameras — From 2D Pose estimation to 3D OpenSim motion

License

Notifications You must be signed in to change notification settings

perfanalytics/pose2sim

Repository files navigation

Continuous integration PyPI version
Downloads Stars GitHub forks GitHub issues GitHub issues-closed
status DOI License

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.9:
Pose estimation with RTMPose is now included in Pose2Sim!
Other recently added features: Automatic camera synchronization, multi-person analysis, Blender visualization, Marker augmentation, Batch processing.

To upgrade, type pip install pose2sim --upgrade (note that you need Python 3.9 or higher).


Pose2Sim provides a workflow for 3D markerless kinematics, as an alternative to 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 originally used OpenPose inputs (2D keypoints coordinates) from multiple videos and lead to an OpenSim result (full-body 3D joint angles). Pose estimation is now performed with more recent models from RTMPose. OpenPose and other models are kept as legacy options.

If you can only use one single camera and don't mind losing some accuracy, please consider using Sports2D.

N.B.: As always, I am more than happy to welcome contributors (see How to contribute).


Pose2Sim releases:

  • v0.1 (08/2021): Published paper
  • v0.2 (01/2022): Published code
  • v0.3 (01/2023): Supported other pose estimation algorithms
  • v0.4 (07/2023): New calibration tool based on scene measurements
  • v0.5 (12/2023): Automatic batch processing
  • v0.6 (02/2024): Marker augmentation, Blender visualizer
  • v0.7 (03/2024): Multi-person analysis
  • v0.8 (04/2024): New synchronization tool
  • v0.9: (07/2024): Integration of pose estimation in the pipeline
  • v0.10: Integration of OpenSim in the pipeline
  • v0.11: Calibration based on keypoint detection, Handling left/right swaps, Correcting lens distortions
  • v0.12: Graphical User Interface
  • v1.0: First accomplished release

Contents

  1. Installation and Demonstration
    1. Installation
    2. Demonstration Part-1: Build 3D TRC file
    3. Demonstration Part-2: Obtain 3D joint angles with OpenSim
    4. Demonstration Part-3 (optional): Visualize your results with Blender
    5. Demonstration Part-4 (optional): Try multi-person analysis
    6. Demonstration Part-5 (optional): Try batch processing
  2. Use on your own data
    1. Setting up your project
    2. 2D pose estimation
      1. With RTMPose (default)
      2. With MMPose (coming soon)
      3. With DeepLabCut
      4. With OpenPose (legacy)
      5. With Mediapipe BlazePose (legacy)
      6. With AlphaPose (legacy)
    3. Camera calibration
      1. Convert from Qualisys, Optitrack, Vicon, OpenCap, EasyMocap, or bioCV
      2. Calculate from scratch
    4. Synchronizing, Tracking, Triangulating, Filtering
      1. Synchronization
      2. Associate persons across cameras
      3. Triangulating keypoints
      4. Filtering 3D coordinates
      5. Marker augmentation
    5. OpenSim kinematics
      1. OpenSim Scaling
      2. OpenSim Inverse kinematics
      3. Command Line
  3. Utilities
  4. How to cite and how to contribute
    1. How to cite
    2. How to contribute and to-do list

Installation and Demonstration

Installation

  1. Optional:
    Install Anaconda or Miniconda for simplicity and avoiding the risk of incompatibilities between libraries.

    Once installed, open an Anaconda prompt and create a virtual environment:

    conda create -n Pose2Sim python=3.9 -y 
    conda activate Pose2Sim
    
  2. Install OpenSim:
    Install the OpenSim Python API (if you do not want to install via conda, refer to this page):

    conda install -c opensim-org opensim -y
    
  3. INSTALL POSE2SIM:
    If you don't use Anaconda, type python -V in terminal to make sure python>=3.9 is installed.

    • OPTION 1: Quick install: Open a terminal.

      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.

      git clone --depth 1 https://github.com/perfanalytics/pose2sim.git
      cd pose2sim
      pip install .
  4. Optional:
    For faster inference, you can run on the GPU. Install pyTorch with CUDA and cuDNN support, and ONNX Runtime with GPU support (not available on MacOS).

    Go to the pyTorch website, select the latest CUDA version that is also available with ONNX runtime, and run the provided command.
    For example, for Windows 11 (June 6th, 2024), CUDA 12.4 is not available for pyTorch, and CUDA 12.1 is not available for ONNX Runtime, so you should revert to CUDA 11.8:

    pip3 install torch torchvision torchaudio --index-url https://download.pytorch.org/whl/cu118
    

    Then install ONNX Runtime with GPU support:

    pip install onnxruntime-gpu
    

Demonstration Part-1: Build 3D TRC file

This demonstration provides an example experiment of a person balancing on a beam, filmed with 4 cameras.

Open a terminal, enter pip show pose2sim, report package location.
Copy this path and go to the Single participant Demo folder: cd <path>\Pose2Sim\Demo_SinglePerson.
Type ipython, and try the following code:

from Pose2Sim import Pose2Sim
Pose2Sim.calibration()
Pose2Sim.poseEstimation()
Pose2Sim.synchronization()
Pose2Sim.personAssociation()
Pose2Sim.triangulation()
Pose2Sim.filtering()
Pose2Sim.markerAugmentation()

3D results are stored as .trc files in each trial folder in the pose-3d directory.


Note:

  • Default parameters have been provided in Config.toml but can be edited.
  • You can run all stages at once:
    from Pose2Sim import Pose2Sim
    Pose2Sim.runAll(do_calibration=True, do_poseEstimation=True, do_synchronization=True, do_personAssociation=True, do_triangulation=True, do_filtering=True, do_markerAugmentation=True, do_opensimProcessing=True)
  • Try the calibration tool by changing calibration_type to calculate instead of convert in Config.toml (more info there).


Demonstration Part-2: Obtain 3D joint angles with OpenSim

In the same vein as you would do with marker-based kinematics, start with scaling your model, and then perform inverse kinematics.

N.B.: For now, you still need to install OpenSim GUI (tested up to v4.5 on Windows, has to be compiled from source on Linux). Will be done natively within Pose2Sim soon.

Scaling

  1. Open OpenSim.
  2. Open the provided Model_Pose2Sim_LSTM.osim model from Pose2Sim/OpenSim_Setup. (File -> Open Model)
  3. Load the provided Scaling_Setup_Pose2Sim_LSTM.xml scaling file from Pose2Sim/OpenSim_Setup. (Tools -> Scale model -> Load)
  4. Run. You should see your skeletal model take the static pose.
  5. Save your scaled model in Demo_SinglePerson/OpenSim/Model_Pose2Sim_S00_P00_LSTM_scaled.osim. (File -> Save Model As)

Inverse kinematics

  1. Load the provided IK_Setup_Pose2Sim_LSTM.xml scaling file from Pose2Sim/OpenSim_Setup. (Tools -> Inverse kinematics -> Load)
  2. Run. You should see your skeletal model move in the Visualizer window.
  3. Your IK motion file will be saved in S00_P00_OpenSim.


Demonstration Part-3 (optional): Visualize your results with Blender

Visualize your results and look in detail for potential areas of improvement (and more).

Install the add-on

Follow instructions on the Pose2Sim_Blender add-on page.

Visualize your results

Just play with the buttons!
Visualize camera positions, videos, triangulated keypoints, OpenSim skeleton, and more.

N.B.: You need to proceed to the full install to import the inverse kinematic results from OpenSim. See instructions there.

Pose2Sim.Blender.mp4

Demonstration Part-4 (optional): Try multi-person analysis

Another person, hidden all along, will appear when multi-person analysis is activated!

Go to the Multi-participant Demo folder: cd <path>\Pose2Sim\Demo_MultiPerson.
Type ipython, and try the following code:

from Pose2Sim import Pose2Sim
Pose2Sim.runAll(do_synchronization=False) # Synchronization possible, but tricky with multiple persons

One .trc file per participant will be generated and stored in the pose-3d directory.
You can then run OpenSim scaling and inverse kinematics for each resulting .trc file as in Demonstration Part-2.
You can also visualize your results with Blender as in Demonstration Part-3.

N.B.: Set [project] multi_person = true for each trial that contains multiple persons.
Set [triangulation] reorder_trc = true if you need to run OpenSim and to match the generated .trc files with the static trials.
Make sure that the order of [markerAugmentation] participant_height and participant_mass matches the order of the static trials.


Demonstration Part-5 (optional): Try batch processing

Run numerous analysis with different parameters and minimal friction.

Go to the Batch Demo folder: cd <path>\Pose2Sim\Demo_Batch.
Type ipython, and try the following code:

from Pose2Sim import Pose2Sim
Pose2Sim.runAll()

The batch processing structure requires a Config.toml file in each of the trial directories. Global parameters are given in the Config.toml file of the BatchSession folder. They can be altered for specific Trials by uncommenting keys and their values in their respective Config.toml files.

Run Pose2Sim from the BatchSession folder if you want to batch process the whole session, or from a Trial folder if you want to process only a specific trial.

SingleTrial BatchSession
SingleTrial                    
├── calibration
├── videos
└── Config.toml
BatchSession                     
├── calibration
├── Trial_1
│ ├── videos
│ └── Config.toml
├── Trial_2
│ ├── videos
│ └── Config.toml
└── Config.toml

For example, try uncommenting [project] and set frame_range = [10,99], or uncomment [pose] and set mode = 'lightweight' in the Config.toml file of Trial_2.



Use on your own data

N.B.: If a step is not relevant for your use case (synchronization, person association, marker augmentation...), you can skip it.

Setting up your project

Get ready for automatic batch processing.

  1. Open a terminal, enter pip show pose2sim, report package location.
    Copy this path and do cd <path>\pose2sim.
  2. Copy-paste the Demo_SinglePerson, Demo_MultiPerson, or Demo_Batch folder wherever you like, and rename it as you wish.
  3. The rest of the tutorial will explain to you how to populate the Calibration and videos folders, edit the Config.toml files, and run each Pose2Sim step.

2D pose estimation

Estimate 2D pose from images with RTMPose or another pose estimation solution.

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 RTMPose (default):

RTMPose is a state-of-the-art pose estimation solution that is faster and more accurate than OpenPose. It is now included in Pose2Sim for straightforward end-to-end analysis.

Open an Anaconda prompt or a terminal in a Session, Participant, or Trial folder.
Type ipython.

from Pose2Sim import Pose2Sim
Pose2Sim.poseEstimation()


N.B.: The GPU will be used with ONNX backend if a valid CUDA installation is found (or MPS with MacOS), otherwise the CPU will be used with OpenVINO backend.
N.B.: Pose estimation can be run in lightweight, balanced, or performance mode.
N.B.: Pose estimation can be dramatically sped up by increasing the value of det_frequency. In that case, the detection is only done every det_frequency frames, and bounding boxes are tracked inbetween (keypoint detection is still performed on all frames).
N.B.: Activating tracking will attempt to give consistent IDs to the same persons across frames, which might facilitate synchronization if other people are in the background.


With MMPose (coming soon):

Coming soon


With DeepLabCut:

If you need to detect specific points on a human being, an animal, or an object, you can also train your own model with DeepLabCut. In this case, Pose2Sim is used as an alternative to AniPose.

  1. Train your DeepLabCut model and run it on your images or videos (more instruction on their repository)
  2. Translate the h5 2D coordinates to json files (with DLC_to_OpenPose.py script, see Utilities):
    python -m DLC_to_OpenPose -i input_h5_file
  3. Edit pose.CUSTOM in Config.toml, and edit the node IDs so that they correspond to the column numbers of the 2D pose file, starting from zero. Make sure you also changed the pose_model and the tracked_keypoint.
    You can visualize your skeleton's hierarchy by changing pose_model to CUSTOM and writing these lines:
     config_path = r'path_to_Config.toml'
     import toml, anytree
     config = toml.load(config_path)
     pose_model = config.get('pose').get('pose_model')
     model = anytree.importer.DictImporter().import_(config.get('pose').get(pose_model))
     for pre, _, node in anytree.RenderTree(model): 
         print(f'{pre}{node.name} id={node.id}')
  4. Create an OpenSim model if you need inverse kinematics.

With OpenPose (legacy):

N.B.: RTMlib is faster, more accurate, and easier to install than OpenPose. This is a legacy option.
N.B.: OpenPose model files are apparently not available on their website anymore. Send me an email at [email protected] if you want me to forward them to you!

The accuracy and robustness of Pose2Sim have been thoroughly assessed only with OpenPose, BODY_25B model. Consequently, we recommend using this 2D pose estimation solution. See OpenPose repository for installation and running. Windows portable demo is enough.

  • Open a command prompt in your OpenPose directory.
    Launch OpenPose for each videos folder:
    bin\OpenPoseDemo.exe --model_pose BODY_25B --video <PATH_TO_TRIAL_DIR>\videos\cam01.mp4 --write_json <PATH_TO_TRIAL_DIR>\pose\pose_cam01_json
  • The BODY_25B model has more accurate results than the standard BODY_25 one and has been extensively tested for Pose2Sim.
    You can also use the BODY_135 model, which allows for the evaluation of pronation/supination, wrist flexion, and wrist deviation.
    All other OpenPose models (BODY_25, COCO, MPII) are also supported.
    Make sure you modify the Config.toml file accordingly.
  • Use one of the json_display_with_img.py or json_display_with_img.py scripts (see Utilities) if you want to display 2D pose detections.

With MediaPipe BlazePose (legacy):

N.B.: RTMlib is faster, more accurate, and easier to install than BlazePose. This is also a legacy option.

Mediapipe BlazePose is very fast, fully runs under Python, handles upside-down postures and wrist movements (but no subtalar ankle angles).
However, it is less robust and accurate than OpenPose, and can only detect a single person.

  • Use the script Blazepose_runsave.py (see Utilities) to run BlazePose under Python, and store the detected coordinates in OpenPose (json) or DeepLabCut (h5 or csv) format:
    python -m Blazepose_runsave -i input_file -dJs
    Type in python -m Blazepose_runsave -h for explanation on parameters.
  • Make sure you changed the pose_model and the tracked_keypoint in the Config.toml file.

With AlphaPose (legacy):

N.B.: RTMlib is faster, more accurate, and easier to install than AlphaPose. This is also a legacy option.

AlphaPose is one of the main competitors of OpenPose, and its accuracy is comparable. As a top-down approach (unlike OpenPose which is bottom-up), it is faster on single-person detection, but slower on multi-person detection.
All AlphaPose models are supported (HALPE_26, HALPE_68, HALPE_136, COCO_133, COCO, MPII). For COCO and MPII, AlphaPose must be run with the flag "--format cmu".

  • Install and run AlphaPose on your videos (more instruction on their repository)
  • Translate the AlphaPose single json file to OpenPose frame-by-frame files (with AlphaPose_to_OpenPose.py script, see Utilities):
    python -m AlphaPose_to_OpenPose -i input_alphapose_json_file
  • Make sure you changed the pose_model and the tracked_keypoint in the Config.toml file.

Camera calibration

Calculate camera intrinsic properties and extrinsic locations and positions.
Convert a preexisting calibration file, or calculate intrinsic and extrinsic parameters from scratch.

Open an Anaconda prompt or a terminal in a Session, Participant, or Trial folder.
Type ipython.

from Pose2Sim import Pose2Sim
Pose2Sim.calibration()


Output file:

Convert from Qualisys, Optitrack, Vicon, OpenCap, EasyMocap, or bioCV

If you already have a calibration file, set calibration_type type to convert in your Config.toml file.

  • From Qualisys:
    • Export calibration to .qca.txt within QTM.
    • Copy it in the Calibration Pose2Sim folder.
    • set convert_from to 'qualisys' in your Config.toml file. Change binning_factor to 2 if you film in 540p.
  • From Optitrack: Exporting calibration will be available in Motive 3.2. In the meantime:
    • Calculate intrinsics with a board (see next section).
    • Use their C++ API to retrieve extrinsic properties. Translation can be copied as is in your Calib.toml file, but TT_CameraOrientationMatrix first needs to be converted to a Rodrigues vector with OpenCV. See instructions here.
    • Use the Calib.toml file as is and do not run Pose2Sim.calibration()
  • From Vicon:
    • Copy your .xcp Vicon calibration file to the Pose2Sim Calibration folder.
    • set convert_from to 'vicon' in your Config.toml file. No other setting is needed.
  • From OpenCap:
    • Copy your .pickle OpenCap calibration files to the Pose2Sim Calibration folder.
    • set convert_from to 'opencap' in your Config.toml file. No other setting is needed.
  • From EasyMocap:
    • Copy your intri.yml and extri.yml files to the Pose2Sim Calibration folder.
    • set convert_from to 'easymocap' in your Config.toml file. No other setting is needed.
  • From bioCV:
    • Copy your bioCV calibration files (no extension) to the Pose2Sim Calibration folder.
    • set convert_from to 'biocv' in your Config.toml file. No other setting is needed.
  • From AniPose or FreeMocap:
    • Copy your .toml calibration file to the Pose2Sim Calibration folder.
    • Calibration can be skipped since Pose2Sim uses the same Aniposelib format.

Calculate from scratch

Calculate calibration parameters with a checkerboard, with measurements on the scene, or automatically with detected keypoints.
Take heart, it is not that complicated once you get the hang of it!

N.B.: Try the calibration tool on the Demo by changing calibration_type to calculate in Config.toml.
For the sake of practicality, there are voluntarily few board images for intrinsic calibration, and few points to click for extrinsic calibration. In spite of this, your reprojection error should be under 1-2 cm, which does not hinder the quality of kinematic results in practice.).

  • Calculate intrinsic parameters with a checkerboard:

    N.B.: Intrinsic parameters: camera properties (focal length, optical center, distortion), usually need to be calculated only once in their lifetime. In theory, cameras with same model and same settings will have identical intrinsic parameters.
    N.B.: If you already calculated intrinsic parameters earlier, you can skip this step by setting overwrite_intrinsics to false.

    • Create a folder for each camera in your Calibration\intrinsics folder.
    • For each camera, film a checkerboard or a charucoboard. Either the board or the camera can be moved.
    • Adjust parameters in the Config.toml file.
    • Make sure that the board:
      • is filmed from different angles, covers a large part of the video frame, and is in focus.
      • is flat, without reflections, surrounded by a wide white border, and is not rotationally invariant (Nrows ≠ Ncols, and Nrows odd if Ncols even). Go to calib.io to generate a suitable checkerboard.
    • A common error is to specify the external, instead of the internal number of corners (one less than the count from calib.io). This may be one less than you would intuitively think.

    Intrinsic calibration error should be below 0.5 px.

  • Calculate extrinsic parameters:

    N.B.: Extrinsic parameters: camera placement in space (position and orientation), need to be calculated every time a camera is moved. Can be calculated from a board, or from points in the scene with known coordinates.
    N.B.: If there is no measurable item in the scene, you can temporarily bring something in (a table, for example), perform calibration, and then remove it before you start capturing motion.

    • Create a folder for each camera in your Calibration\extrinsics folder.
    • Once your cameras are in place, shortly film either a board laid on the floor, or the raw scene
      (only one frame is needed, but do not just take a photo unless you are sure it does not change the image format).
    • Adjust parameters in the Config.toml file.
    • Then,
      • With a checkerboard:
        Make sure that it is seen by all cameras.
        It should preferably be larger than the one used for intrinsics, as results will not be very accurate out of the covered zone.
      • With scene measurements (more flexible and potentially more accurate if points are spread out):
        Manually measure the 3D coordinates of 10 or more points in the scene (tiles, lines on wall, boxes, treadmill dimensions...). These points should be as spread out as possible. Replace object_coords_3d by these coordinates in Config.toml.
        Then you will click on the corresponding image points for each view.
      • With keypoints:
        For a more automatic calibration, OpenPose keypoints could also be used for calibration.
        COMING SOON!

    Extrinsic calibration error should be below 1 cm, but depending on your application, results will still be potentially acceptable up to 2.5 cm.


Synchronizing, Tracking, Triangulating, Filtering

Synchronization

Cameras need to be synchronized, so that 2D points correspond to the same position across cameras.
N.B.: Skip this step if your cameras are natively synchronized.

Open an Anaconda prompt or a terminal in a Session, Participant, or Trial folder.
Type ipython.

from Pose2Sim import Pose2Sim
Pose2Sim.synchronization()


For each camera, this computes mean vertical speed for the chosen keypoints, and finds the time offset for which their correlation is highest.
All keypoints can be taken into account, or a subset of them. The user can also specify a time for each camera when only one participant is in the scene, preferably performing a clear vertical motion.

N.B.: Works best when:

  • only one participant is in the scene (set approx_time_maxspeed and time_range_around_maxspeed accordingly)
  • the participant is at a roughly equal distance from all cameras
  • when the capture is at least 5 seconds long

N.B.: Alternatively, use a flashlight, a clap, or a clear event to synchronize cameras. GoPro cameras can also be synchronized with a timecode, by GPS (outdoors) or with their app (slightly less reliable).


Associate persons across cameras

If multi_person is set to false, the algorithm chooses the person for whom the reprojection error is smallest.
If multi_person is set to true, it associates across views the people for whom the distances between epipolar lines are the smallest. People are then associated across frames according to their displacement speed.

N.B.: Skip this step if only one person is in the field of view.

Open an Anaconda prompt or a terminal in a Session, Participant, or Trial folder.
Type ipython.

from Pose2Sim import Pose2Sim
Pose2Sim.personAssociation()


Check printed output. If results are not satisfying, try and release the constraints in the Config.toml file.


Triangulating keypoints

Triangulate your 2D coordinates in a robust way.
The triangulation is weighted by the likelihood of each detected 2D keypoint, provided that they this likelihood is above a threshold.
If the reprojection error is above another threshold, right and left sides are swapped; if it is still above, cameras are removed until the threshold is met. If more cameras are removed than a predefined number, triangulation is skipped for this point and this frame. In the end, missing values are interpolated.

Open an Anaconda prompt or a terminal in a Session, Participant, or Trial folder.
Type ipython.

from Pose2Sim import Pose2Sim
Pose2Sim.triangulation()


Check printed output, and visualize your trc in OpenSim: File -> Preview experimental data.
If your triangulation is not satisfying, try and release the constraints in the Config.toml file.


Filtering 3D coordinates

Filter your 3D coordinates.
Numerous filter types are provided, and can be tuned accordingly.

Open an Anaconda prompt or a terminal in a Session, Participant, or Trial folder.
Type ipython.

from Pose2Sim import Pose2Sim
Pose2Sim.filtering()


Check your filtration with the displayed figures, and visualize your .trc file in OpenSim. If your filtering is not satisfying, try and change the parameters in the Config.toml file.

Output:


Marker Augmentation

Use the Stanford LSTM model to estimate the position of 47 virtual markers.
Note that inverse kinematic results are not necessarily better after marker augmentation. Skip if results are not convincing.

N.B.: Marker augmentation tends to give a more stable, but less precise output. In practice, it is mostly beneficial when using less than 4 cameras.

Make sure that participant_height is correct in your Config.toml file. participant_mass is mostly optional for IK.
Only works with models estimating at least the following keypoints (e.g., not COCO):

 ["Neck", "RShoulder", "LShoulder", "RHip", "LHip", "RKnee", "LKnee",
 "RAnkle", "LAnkle", "RHeel", "LHeel", "RSmallToe", "LSmallToe",
 "RBigToe", "LBigToe", "RElbow", "LElbow", "RWrist", "LWrist"]

Will not work properly if missing values are not interpolated (i.e., if there are Nan value in the .trc file).

Open an Anaconda prompt or a terminal in a Session, Participant, or Trial folder.
Type ipython.

from Pose2Sim import Pose2Sim
Pose2Sim.markerAugmentation()


OpenSim kinematics

Obtain 3D joint angles.
Your OpenSim .osim scaled model and .mot inverse kinematic results will be found in the OpenSim folder of your Participant directory.

OpenSim Scaling

  1. Choose a time range where the 3D keypoints are particularly well reconstructed, or capture a static pose, typically an A-pose...
  2. Open OpenSim.
  3. Open the provided Model_Pose2Sim_LSTM.osim model from Pose2Sim/OpenSim_Setup. (File -> Open Model)
  4. Load the provided Scaling_Setup_Pose2Sim_LSTM.xml scaling file. (Tools -> Scale model -> Load)
  5. Replace the example .trc file with your own data.
  6. Run
  7. Save the new scaled OpenSim model.

OpenSim Inverse kinematics

  1. Load the provided IK_Setup_Pose2Sim_LSTM.xml scaling file from Pose2Sim/OpenSim_Setup. (Tools -> Inverse kinematics -> Load)
  2. Replace the example .trc file with your own data, and specify the path to your angle kinematics output file.
  3. Run.


Command line

Alternatively, you can use command-line tools:

import opensim
opensim.ScaleTool("<PATH TO YOUR SCALING OR IK SETUP FILE>.xml").run()
opensim.InverseKinematicsTool("<PATH TO YOUR SCALING OR IK SETUP FILE>.xml").run()

N.B.: You'll need to adjust the time_range, output_motion_file, and enter the absolute path (NOT the relative path) to the input and output .osim, .trc, and .mot files in your setup file.

You can also run other API commands. See there for more instructions on how to use it.


Utilities

A list of standalone tools (see Utilities), which can be either run as scripts, or imported as functions. Check usage in the docstring of each Python file. The figure below shows how some of these tools can be used to further extend Pose2Sim usage.

Converting pose files (CLICK TO SHOW)

Blazepose_runsave.py Runs BlazePose on a video, and saves coordinates in OpenPose (json) or DeepLabCut (h5 or csv) format.

DLC_to_OpenPose.py Converts a DeepLabCut (h5) 2D pose estimation file into OpenPose (json) files.

AlphaPose_to_OpenPose.py Converts AlphaPose single json file to OpenPose frame-by-frame files.

Converting calibration files (CLICK TO SHOW)

calib_toml_to_easymocap.py Converts an OpenCV .toml calibration file to EasyMocap intrinsic and extrinsic .yml calibration files.

calib_easymocap_to_toml.py Converts EasyMocap intrinsic and extrinsic .yml calibration files to an OpenCV .toml calibration file.

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 Converts a Qualisys .qca.txt calibration file to the Pose2Sim .toml calibration file (similar to what is used in AniPose).

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 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.

Plotting tools (CLICK TO SHOW)

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 Plots an animation of 2D detected json coordinates.

trc_plot.py Displays X, Y, Z coordinates of each 3D keypoint of a TRC file in a different matplotlib tab.

Other trc tools (CLICK TO SHOW)

trc_from_easymocap.py Convert EasyMocap results keypoints3d .json files to .trc.

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 Converts 3D point data from a .trc file to a .c3d file compatible with Visual3D.

trc_desample.py Undersamples a trc file.

trc_Zup_to_Yup.py Changes Z-up system coordinates to Y-up system coordinates.

trc_filter.py Filters trc files. Available filters: Butterworth, Kalman, Butterworth on speed, Gaussian, LOESS, Median.

trc_gaitevents.py Detects gait events from point coordinates according to Zeni et al. (2008).

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 Build a trc file from a .mot motion file and a .osim model file.

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 Reprojects 3D coordinates of a trc file to the image planes defined by a calibration file. Output in OpenPose or DeepLabCut format.


How to cite and how to contribute

How to cite

If you use this code or data, please cite Pagnon et al., 2022b, Pagnon et al., 2022a, or Pagnon et al., 2021.

@Article{Pagnon_2022_JOSS, 
  AUTHOR = {Pagnon, David and Domalain, Mathieu and Reveret, Lionel}, 
  TITLE = {Pose2Sim: An open-source Python package for multiview markerless kinematics}, 
  JOURNAL = {Journal of Open Source Software}, 
  YEAR = {2022},
  DOI = {10.21105/joss.04362}, 
  URL = {https://joss.theoj.org/papers/10.21105/joss.04362}
 }

@Article{Pagnon_2022_Accuracy,
  AUTHOR = {Pagnon, David and Domalain, Mathieu and Reveret, Lionel},
  TITLE = {Pose2Sim: An End-to-End Workflow for 3D Markerless Sports Kinematics—Part 2: Accuracy},
  JOURNAL = {Sensors},
  YEAR = {2022},
  DOI = {10.3390/s22072712},
  URL = {https://www.mdpi.com/1424-8220/22/7/2712}
}

@Article{Pagnon_2021_Robustness,
  AUTHOR = {Pagnon, David and Domalain, Mathieu and Reveret, Lionel},
  TITLE = {Pose2Sim: An End-to-End Workflow for 3D Markerless Sports Kinematics—Part 1: Robustness},
  JOURNAL = {Sensors},
  YEAR = {2021},
  DOI = {10.3390/s21196530},
  URL = {https://www.mdpi.com/1424-8220/21/19/6530}
}

How to contribute and to-do list

I would happily welcome any proposal for new features, code improvement, and more!
If you want to contribute to Pose2Sim, please see this issue.
You will be proposed a to-do list, but please feel absolutely free to propose your own ideas and improvements.


Main to-do list

  • Graphical User Interface
  • Synchronization
  • Self-calibration based on keypoint detection

Detailed GOT-DONE and TO-DO list (CLICK TO SHOW)

Pose: Support OpenPose body_25b for more accuracy, body_135 for pronation/supination. ✔ Pose: Support BlazePose for faster inference (on mobile device). ✔ Pose: Support DeepLabCut for training on custom datasets. ✔ Pose: Support AlphaPose as an alternative to OpenPose. ✔ Pose: Define custom model in config.toml rather than in skeletons.py. ✔ Pose: Integrate pose estimation within Pose2Sim (via RTMlib). ▢ Pose: Support MMPose, SLEAP, etc. ▢ 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 .qca.txt calibration file. ✔ Calibration: Convert Optitrack extrinsic calibration file. ✔ Calibration: Convert Vicon .xcp calibration file. ✔ Calibration: Convert OpenCap .pickle calibration files. ✔ Calibration: Convert EasyMocap .yml calibration files. ✔ Calibration: Convert bioCV 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: Support vertical checkerboard. ▢ 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. ▢ Calibration: Fine-tune calibration with bundle adjustment. ▢ Calibration: Support ChArUco board detection (see there). ▢ Calibration: Calculate calibration with points rather than board. (1) SBA calibration with wand (cf Argus, see converter here). Set world reference frame in the end. ▢ Calibration: Alternatively, self-calibrate with OpenPose keypoints. Set world reference frame in the end. ▢ Calibration: Convert fSpy calibration 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? or 2. Based on affinity matrices Dong 2021? or 3. Based on occupancy maps Yildiz 2012? or 4. With a neural network Huang 2023?

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 2D points before triangulating (and distort them before computing reprojection error). ✔ Triangulation: Offer the possibility to augment the triangulated data with the OpenCap LSTM. 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). ▢ Triangulation: Implement normalized DLT and RANSAC triangulation, Outlier rejection (sliding z-score?), as well as a triangulation refinement step. ▢ 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

OpenSim: Integrate better spine from lifting fullbody model to the gait full-body model, 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) and full-body muscles (DeGrooteFregly2016Muscle), for Moco for example. ✔ OpenSim: Add model with ISB shoulder. ▢ OpenSim: Integrate OpenSim in Pose2Sim. ▢ OpenSim: Do not require a separate scaling trial: scale on the 10% slowest frames of the moving trial instead, or take median scaling value. ▢ OpenSim: Implement optimal fixed-interval Kalman smoothing for inverse kinematics (this OpenSim fork), or Biorbd)

GUI: Blender add-on (cf MPP2SOS), Maya-Mocap and BlendOsim. ▢ GUI: App or webapp (e.g., with Napari). ▢ GUI: 3D plot of cameras and of triangulated keypoints. ▢ GUI: Demo on Google Colab (see Sports2D 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, MkDocs, or github.io (maybe better) for clearer documentation.

Pip packageBatch processing (also enable non-batch processing) ✔ Catch errorsConda packageDocker 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 typerUtilities: 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. ▢ Bug: common.py, class plotWindow(). Python crashes after a few runs of Pose2Sim.filtering() when display_figures=true. See there.


Acknowledgements: