beta: opensim integration

This commit is contained in:
davidpagnon 2024-09-19 00:39:58 +02:00
parent 6bb2c3fd9c
commit e321228a75
7 changed files with 106 additions and 68 deletions

Binary file not shown.

Before

Width:  |  Height:  |  Size: 83 KiB

After

Width:  |  Height:  |  Size: 94 KiB

View File

@ -39,7 +39,7 @@ Pose2Sim.personAssociation()
Pose2Sim.triangulation()
Pose2Sim.filtering()
Pose2Sim.markerAugmentation()
Pose2Sim.opensimProcessing()
Pose2Sim.kinematics()
# Then run OpenSim (see Readme.md)
'''
@ -158,7 +158,6 @@ def read_config_files(config):
return level, config_dicts
def calibration(config=None):
'''
Cameras calibration from checkerboards or from qualisys files.
@ -192,7 +191,11 @@ def calibration(config=None):
logging.info("---------------------------------------------------------------------\n")
start = time.time()
calibrate_cams_all(config_dict)
try:
calibrate_cams_all(config_dict)
except Exception as e:
logging.error(f"Error during calibration: {e}")
return
end = time.time()
logging.info(f'\nCalibration took {end-start:.2f} s.\n')
@ -236,7 +239,11 @@ def poseEstimation(config=None):
logging.info(f"Project directory: {project_dir}")
logging.info("---------------------------------------------------------------------\n")
rtm_estimator(config_dict)
try:
rtm_estimator(config_dict)
except Exception as e:
logging.error(f"Error during pose estimation: {e}")
continue
end = time.time()
elapsed = end - start
@ -280,7 +287,11 @@ def synchronization(config=None):
logging.info(f"Project directory: {project_dir}")
logging.info("---------------------------------------------------------------------\n")
synchronize_cams_all(config_dict)
try:
synchronize_cams_all(config_dict)
except Exception as e:
logging.error(f"Error during synchronization: {e}")
continue
end = time.time()
elapsed = end-start
@ -327,7 +338,11 @@ def personAssociation(config=None):
logging.info(f"Project directory: {project_dir}")
logging.info("---------------------------------------------------------------------\n")
track_2d_all(config_dict)
try:
track_2d_all(config_dict)
except Exception as e:
logging.error(f"Error during person association: {e}")
continue
end = time.time()
elapsed = end-start
@ -373,7 +388,11 @@ def triangulation(config=None):
logging.info(f"Project directory: {project_dir}")
logging.info("---------------------------------------------------------------------\n")
triangulate_all(config_dict)
try:
triangulate_all(config_dict)
except Exception as e:
logging.error(f"Error during triangulation: {e}")
continue
end = time.time()
elapsed = end-start
@ -418,7 +437,11 @@ def filtering(config=None):
logging.info(f"Project directory: {project_dir}\n")
logging.info("---------------------------------------------------------------------\n")
filter_all(config_dict)
try:
filter_all(config_dict)
except Exception as e:
logging.error(f"Error during filtering: {e}")
continue
logging.info('\n')
@ -459,31 +482,32 @@ def markerAugmentation(config=None):
logging.info(f"Project directory: {project_dir}")
logging.info("---------------------------------------------------------------------\n")
augmentTRC(config_dict)
try:
augmentTRC(config_dict)
except Exception as e:
logging.error(f"Error during marker augmentation: {e}")
continue
end = time.time()
elapsed = end-start
logging.info(f'\nMarker augmentation took {time.strftime("%Hh%Mm%Ss", time.gmtime(elapsed))}.\n')
def opensimProcessing(config=None):
def kinematics(config=None):
'''
Performing OpenSim scaling and inverse kinematics.
Selected the 10% slowest frames from trc for scaling
Saved as .osim and .mot
Select the 10% slowest frames from trc for scaling
Save scaled model as .osim and output motion as .mot
config can be a dictionary,
or a the directory path of a trial, participant, or session,
or the function can be called without an argument, in which case it the config directory is the current one.
'''
from Pose2Sim.kinematics import opensimProcessing
# Read the configuration files
from Pose2Sim.kinematics import kinematics
level, config_dicts = read_config_files(config)
# Ensure the configuration is properly structured
if isinstance(config, dict):
if type(config) == dict:
config_dict = config_dicts[0]
if config_dict.get('project').get('project_dir') is None:
raise ValueError('Please specify the project directory in config_dict:\n \
@ -502,24 +526,23 @@ def opensimProcessing(config=None):
frames = ["all frames" if frame_range == [] else f"frames {frame_range[0]} to {frame_range[1]}"][0]
logging.info("\n---------------------------------------------------------------------")
logging.info(f"OpenSim processing for {seq_name}, for {frames}.")
logging.info(f"OpenSim scaling and inverse kinematics for {seq_name}, for {frames}.")
logging.info(f"On {currentDateAndTime.strftime('%A %d. %B %Y, %H:%M:%S')}")
logging.info(f"Project directory: {project_dir}")
logging.info("---------------------------------------------------------------------\n")
try:
opensimProcessing(config_dict)
kinematics(config_dict)
except Exception as e:
logging.error(f"Error during OpenSim processing: {e}")
continue
end = time.time()
elapsed = end - start
logging.info(f'\nOpenSim processing took {time.strftime("%Hh%Mm%Ss", time.gmtime(elapsed))}.\n')
logging.info(f'\nOpenSim scaling and inverse kinematics took {time.strftime("%Hh%Mm%Ss", time.gmtime(elapsed))}.\n')
def runAll(config=None, do_calibration=True, do_poseEstimation=True, do_synchronization=True, do_personAssociation=True, do_triangulation=True, do_filtering=True, do_markerAugmentation=True, do_opensimProcessing=True):
def runAll(config=None, do_calibration=True, do_poseEstimation=True, do_synchronization=True, do_personAssociation=True, do_triangulation=True, do_filtering=True, do_markerAugmentation=True, do_kinematics=True):
'''
Run all functions at once. Beware that Synchronization, personAssociation, and markerAugmentation are not always necessary,
and may even lead to worse results. Think carefully before running all.
@ -610,11 +633,11 @@ def runAll(config=None, do_calibration=True, do_poseEstimation=True, do_synchron
logging.info('Skipping marker augmentation.')
logging.info("\n\n=====================================================================")
if do_opensimProcessing:
if do_kinematics:
logging.info("\n\n=====================================================================")
logging.info("Running OpenSim processing.")
logging.info("=====================================================================")
opensimProcessing(config)
kinematics(config)
else:
logging.info("\n\n=====================================================================")
logging.info('Skipping OpenSim processing.')

View File

@ -39,9 +39,9 @@ __status__ = "Development"
## FUNCTIONS
def natural_sort_key(s):
"""
'''
Key for natural sorting of strings containing numbers.
"""
'''
return [int(c) if c.isdigit() else c.lower() for c in re.split(r'(\d+)', s)]

View File

@ -7,31 +7,49 @@
## Pose2Sim tests ##
########################################
- BATCH SESSION:
- Calibration conversion from .qca.txt
- Single person:
- synchronization
- person association
- triangulation
- filtering
- marker augmentation
- opensim processing
- Multi-person:
- synchronization
- person association
- triangulation
- filtering
- marker augmentation
- opensim processing
- SINGLE TRIAL:
- calibration
- SINGLE PERSON:
- calibration conversion from .qca.txt
- pose estimation
- synchronization
- person association
- triangulation
- filtering
- marker augmentation
- opensim processing
- opensim scaling and inverse kinematics
- run all
- MULTI PERSON:
- calibration conversion from .qca.txt
- pose estimation
- NO synchronization
- person association
- triangulation
- filtering
- marker augmentation
- opensim scaling and inverse kinematics
- run all
- BATCH SESSION, RUN ALL:
- Calibration conversion from .qca.txt
- Single person:
- pose estimation
- NO synchronization
- person association
- triangulation
- filtering
- marker augmentation
- opensim scaling and inverse kinematics
- Multi-person:
- pose estimation
- NO synchronization
- person association
- triangulation
- filtering
- marker augmentation
- opensim scaling and inverse kinematics
N.B.:
1. Calibration from scene dimensions is not tested, as it requires the
@ -77,13 +95,12 @@ class TestWorkflow(unittest.TestCase):
- triangulation
- filtering
- marker augmentation
- OpenSim processing
- opensim scaling and inverse kinematics
- run all
N.B.: Calibration from scene dimensions is not tested, as it requires the
user to click points on the image.
Not all possible configuration parameters are extensively tested.
Scaling and inverse kinematics are not tested yet.
Usage:
from Pose2Sim import tests; tests.test_workflow()
@ -103,7 +120,6 @@ class TestWorkflow(unittest.TestCase):
config_dict.get("pose").update({"mode":'lightweight'})
config_dict.get("pose").update({"display_detection":False})
config_dict.get("synchronization").update({"display_sync_plots":False})
# config_dict['triangulation']['reorder_trc'] = False
config_dict['filtering']['display_figures'] = False
Pose2Sim.calibration(config_dict)
@ -113,7 +129,7 @@ class TestWorkflow(unittest.TestCase):
Pose2Sim.triangulation(config_dict)
Pose2Sim.filtering(config_dict)
Pose2Sim.markerAugmentation(config_dict)
Pose2Sim.opensimProcessing(config_dict)
Pose2Sim.kinematics(config_dict)
config_dict.get("pose").update({"overwrite_pose":False})
Pose2Sim.runAll(config_dict)
@ -141,7 +157,7 @@ class TestWorkflow(unittest.TestCase):
Pose2Sim.triangulation(config_dict)
Pose2Sim.filtering(config_dict)
Pose2Sim.markerAugmentation(config_dict)
Pose2Sim.opensimProcessing(config_dict)
Pose2Sim.kinematics(config_dict)
# Run all
config_dict.get("pose").update({"overwrite_pose":False})

View File

@ -36,7 +36,7 @@ from Pose2Sim.common import convert_to_c3d, natural_sort_key
## AUTHORSHIP INFORMATION
__author__ = "Antoine Falisse, adapted by HunMin Kim and David Pagnon"
__copyright__ = "Copyright 2022, OpenCap"
__credits__ = ["Antoine Falisse", "HunMin Kim"]
__credits__ = ["Antoine Falisse", "HunMin Kim", "David Pagnon"]
__license__ = "Apache-2.0 License"
__version__ = "0.9.4"
__maintainer__ = "David Pagnon"

View File

@ -735,7 +735,6 @@ def triangulate_all(config_dict):
multi_person = config_dict.get('project').get('multi_person')
pose_model = config_dict.get('pose').get('pose_model')
frame_range = config_dict.get('project').get('frame_range')
reorder_trc = config_dict.get('triangulation').get('reorder_trc')
likelihood_threshold = config_dict.get('triangulation').get('likelihood_threshold_triangulation')
interpolation_kind = config_dict.get('triangulation').get('interpolation')
interp_gap_smaller_than = config_dict.get('triangulation').get('interp_if_gap_smaller_than')
@ -977,21 +976,21 @@ def triangulate_all(config_dict):
if make_c3d:
c3d_paths = [convert_to_c3d(t) for t in trc_paths]
# Reorder TRC files
if multi_person and reorder_trc and len(trc_paths)>1:
trc_id = retrieve_right_trc_order(trc_paths)
[os.rename(t, t+'.old') for t in trc_paths]
[os.rename(t+'.old', trc_paths[i]) for i, t in zip(trc_id,trc_paths)]
if make_c3d:
[os.rename(c, c+'.old') for c in c3d_paths]
[os.rename(c+'.old', c3d_paths[i]) for i, c in zip(trc_id,c3d_paths)]
error_tot = [error_tot[i] for i in trc_id]
nb_cams_excluded_tot = [nb_cams_excluded_tot[i] for i in trc_id]
cam_excluded_count = [cam_excluded_count[i] for i in trc_id]
interp_frames = [interp_frames[i] for i in trc_id]
non_interp_frames = [non_interp_frames[i] for i in trc_id]
# # Reorder TRC files
# if multi_person and reorder_trc and len(trc_paths)>1:
# trc_id = retrieve_right_trc_order(trc_paths)
# [os.rename(t, t+'.old') for t in trc_paths]
# [os.rename(t+'.old', trc_paths[i]) for i, t in zip(trc_id,trc_paths)]
# if make_c3d:
# [os.rename(c, c+'.old') for c in c3d_paths]
# [os.rename(c+'.old', c3d_paths[i]) for i, c in zip(trc_id,c3d_paths)]
# error_tot = [error_tot[i] for i in trc_id]
# nb_cams_excluded_tot = [nb_cams_excluded_tot[i] for i in trc_id]
# cam_excluded_count = [cam_excluded_count[i] for i in trc_id]
# interp_frames = [interp_frames[i] for i in trc_id]
# non_interp_frames = [non_interp_frames[i] for i in trc_id]
logging.info('\nThe trc and c3d files have been renamed to match the order of the static sequences.')
# logging.info('\nThe trc and c3d files have been renamed to match the order of the static sequences.')
# Recap message

View File

@ -1,6 +1,6 @@
[metadata]
name = pose2sim
version = 0.9.12
version = 0.9.13
author = David Pagnon
author_email = contact@david-pagnon.com
description = Perform a markerless kinematic analysis from multiple calibrated views as a unified workflow from an OpenPose input to an OpenSim result.