fullproof until limb swapping solved

This commit is contained in:
davidpagnon 2024-01-15 11:51:02 +01:00
parent fe0a3e66c2
commit c4de3d03a6
16 changed files with 60 additions and 23 deletions

View File

@ -134,7 +134,7 @@ interpolation = 'cubic' #linear, slinear, quadratic, cubic, or none
# 'none' if you don't want to interpolate missing points # 'none' if you don't want to interpolate missing points
interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -135,7 +135,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -135,7 +135,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -135,7 +135,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -134,7 +134,7 @@ interpolation = 'cubic' #linear, slinear, quadratic, cubic, or none
# 'none' if you don't want to interpolate missing points # 'none' if you don't want to interpolate missing points
interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -135,7 +135,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -134,7 +134,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -134,7 +134,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -134,7 +134,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -135,7 +135,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -135,7 +135,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -135,7 +135,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -135,7 +135,7 @@
## 'none' if you don't want to interpolate missing points ## 'none' if you don't want to interpolate missing points
# interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps # interp_if_gap_smaller_than = 10 # do not interpolate bigger gaps
# show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated # show_interp_indices = true # true or false (lowercase). For each keypoint, return the frames that need to be interpolated
# handle_LR_swap = true # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower # handle_LR_swap = false # Better if few cameras (eg less than 4) with risk of limb swapping (eg camera facing sagittal plane), otherwise slightly less accurate and slower
# undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low # undistort_points = false # Better if distorted image (parallel lines curvy on the edge or at least one param > 10^-2), but unnecessary (and slightly slower) if distortions are low
# make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon! # make_c3d = false # save triangulated data in c3d format in addition to trc # Coming soon!

View File

@ -15,6 +15,9 @@
Transforms from OpenSim's yup to Blender's zup unless you set direction = 'yup' Transforms from OpenSim's yup to Blender's zup unless you set direction = 'yup'
Beware, it can be quite slow depending on the ccomplexity
of the model and on the number of frames.
Usage: Usage:
from Pose2Sim.Utilities import bodykin_from_mot_osim; bodykin_from_mot_osim.bodykin_from_mot_osim_func(r'<input_mot_file>', r'<output_osim_file>', r'<output_csv_file>') from Pose2Sim.Utilities import bodykin_from_mot_osim; bodykin_from_mot_osim.bodykin_from_mot_osim_func(r'<input_mot_file>', r'<output_osim_file>', r'<output_csv_file>')
python -m bodykin_from_mot_osim -m input_mot_file -o input_osim_file python -m bodykin_from_mot_osim -m input_mot_file -o input_osim_file
@ -74,11 +77,24 @@ def bodykin_from_mot_osim_func(*args):
# Read model and motion files # Read model and motion files
model = osim.Model(osim_path) model = osim.Model(osim_path)
motion_data = osim.TimeSeriesTable(motion_path) motion_data = osim.TimeSeriesTable(motion_path)
# # Degrees or radians
# with open(motion_path) as m_p:
# while True:
# line = m_p.readline()
# if 'inDegrees' in line:
# break
# if 'yes' in line:
# in_degrees = True
# else:
# in_degrees = False
# Model: get model coordinates and bodies # Model: get model coordinates and bodies
model_coordSet = model.getCoordinateSet() model_coordSet = model.getCoordinateSet()
coordinates = [model_coordSet.get(i) for i in range(model_coordSet.getSize())] # coordinates = [model_coordSet.get(i) for i in range(model_coordSet.getSize())]
coordinateNames = [c.getName() for c in coordinates] # coordinates = [c for c in coordinates if '_beta' not in c.getName()]
# coordinateNames = [c.getName() for c in coordinates]
coordinateNames = motion_data.getColumnLabels()
model_bodySet = model.getBodySet() model_bodySet = model.getBodySet()
bodies = [model_bodySet.get(i) for i in range(model_bodySet.getSize())] bodies = [model_bodySet.get(i) for i in range(model_bodySet.getSize())]
bodyNames = [b.getName() for b in bodies] bodyNames = [b.getName() for b in bodies]
@ -86,16 +102,21 @@ def bodykin_from_mot_osim_func(*args):
# Motion: read coordinates and convert to radians # Motion: read coordinates and convert to radians
times = motion_data.getIndependentColumn() times = motion_data.getIndependentColumn()
motion_data_np = motion_data.getMatrix().to_numpy() motion_data_np = motion_data.getMatrix().to_numpy()
for i in range(len(coordinates)): for i, c in enumerate(coordinateNames):
if coordinates[i].getMotionType() == 1: # 1: rotation, 2: translation, 3: coupled if model_coordSet.get(c).getMotionType() == 1: # 1: rotation, 2: translation, 3: coupled
motion_data_np[:,i] = motion_data_np[:,i] * np.pi/180 # if rotation, convert to radians if motion_data.getTableMetaDataAsString('inDegrees') == 'yes':
# if in_degrees:
# for i in range(len(coordinates)):
# if coordinates[i].getMotionType() == 1: # 1: rotation, 2: translation, 3: coupled
motion_data_np[:,i] = motion_data_np[:,i] * np.pi/180 # if rotation, convert to radians
# Animate model # Animate model
state = model.initSystem() state = model.initSystem()
loc_rot_frame_all = [] loc_rot_frame_all = []
H_zup = np.array([[1,0,0,0], [0,0,-1,0], [0,1,0,0], [0,0,0,1]]) H_zup = np.array([[1,0,0,0], [0,0,-1,0], [0,1,0,0], [0,0,0,1]])
print('Time frame:')
for n in range(motion_data.getNumRows()): for n in range(motion_data.getNumRows()):
print(times[n], 's')
# Set model struct in each time state # Set model struct in each time state
for c, coord in enumerate(coordinateNames): for c, coord in enumerate(coordinateNames):
model.getCoordinateSet().get(coord).setValue(state, motion_data_np[n,c]) model.getCoordinateSet().get(coord).setValue(state, motion_data_np[n,c])

View File

@ -1 +0,0 @@

View File

@ -10,6 +10,9 @@
Build a trc file which stores all real and virtual markers Build a trc file which stores all real and virtual markers
calculated from a .mot motion file and a .osim model file. calculated from a .mot motion file and a .osim model file.
Beware, it can be quite slow depending on the ccomplexity
of the model and on the number of frames.
Usage: Usage:
from Pose2Sim.Utilities import trc_from_mot_osim; trc_from_mot_osim.trc_from_mot_osim_func(r'<input_mot_file>', r'<output_osim_file>', r'<output_trc_file>') from Pose2Sim.Utilities import trc_from_mot_osim; trc_from_mot_osim.trc_from_mot_osim_func(r'<input_mot_file>', r'<output_osim_file>', r'<output_trc_file>')
python -m trc_from_mot_osim -m input_mot_file -o input_osim_file python -m trc_from_mot_osim -m input_mot_file -o input_osim_file
@ -37,7 +40,7 @@ __status__ = "Development"
## FUNCTIONS ## FUNCTIONS
def get_marker_positions(motion_data, model): def get_marker_positions(motion_data, model, in_degrees=True):
''' '''
Get dataframe of marker positions Get dataframe of marker positions
@ -63,10 +66,12 @@ def get_marker_positions(motion_data, model):
# Get marker positions at each state # Get marker positions at each state
state = model.initSystem() state = model.initSystem()
marker_positions = [] marker_positions = []
print('Time frame:')
for n,t in enumerate(times): for n,t in enumerate(times):
print(t, 's')
# put the model in the right position # put the model in the right position
for coord in joint_angle_set_names: for coord in joint_angle_set_names:
if not coord.endswith('_tx') and not coord.endswith('_ty') and not coord.endswith('_tz'): if in_degrees and not coord.endswith('_tx') and not coord.endswith('_ty') and not coord.endswith('_tz'):
value = motion_data_pd.loc[n,coord]*np.pi/180 value = motion_data_pd.loc[n,coord]*np.pi/180
else: else:
value = motion_data_pd.loc[n,coord] value = motion_data_pd.loc[n,coord]
@ -109,7 +114,19 @@ def trc_from_mot_osim_func(*args):
# Create dataframe with marker positions # Create dataframe with marker positions
model = osim.Model(osim_path) model = osim.Model(osim_path)
motion_data = osim.TimeSeriesTable(motion_path) motion_data = osim.TimeSeriesTable(motion_path)
marker_positions_pd = get_marker_positions(motion_data, model)
# In degrees or radians
with open(motion_path) as m_p:
while True:
line = m_p.readline()
if 'inDegrees' in line:
break
if 'yes' in line:
in_degrees = True
else:
in_degrees = False
marker_positions_pd = get_marker_positions(motion_data, model, in_degrees=in_degrees)
# Trc header # Trc header
times = motion_data.getIndependentColumn() times = motion_data.getIndependentColumn()