forked from stanfordnmbl/opencap-core
-
Notifications
You must be signed in to change notification settings - Fork 0
/
utilsChecker.py
3026 lines (2490 loc) · 129 KB
/
utilsChecker.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
import sys
sys.path.append("./mmpose") # utilities in child directory
import cv2
import numpy as np
import pandas as pd
import os
import glob
import pickle
import json
import subprocess
import urllib.request
import shutil
import utilsDataman
import requests
import ffmpeg
import matplotlib.pyplot as plt
from scipy.ndimage import gaussian_filter1d
from scipy.signal import gaussian, sosfiltfilt, butter, find_peaks
from scipy.interpolate import pchip_interpolate
from scipy.spatial.transform import Rotation
import scipy.linalg
from itertools import combinations
import copy
from utilsCameraPy3 import Camera, nview_linear_triangulations
from utils import getOpenPoseMarkerNames, getOpenPoseFaceMarkers
from utils import numpy2TRC, rewriteVideos, delete_multiple_element,loadCameraParameters
from utilsAPI import getAPIURL
from utilsAuth import getToken
API_TOKEN = getToken()
API_URL = getAPIURL()
# %%
def download_file(url, file_name):
with urllib.request.urlopen(url) as response, open(file_name, 'wb') as out_file:
shutil.copyfileobj(response, out_file)
# %%
def getVideoLength(filename):
result = subprocess.run(
["ffprobe", "-v", "error", "-show_entries", "format=duration",
"-of", "default=noprint_wrappers=1:nokey=1", filename],
stdout=subprocess.PIPE, stderr=subprocess.STDOUT)
return float(result.stdout)
# %%
def video2Images(videoPath, nImages=12, tSingleImage=None, filePrefix='output', skipIfRun=True, outputFolder='default'):
# Pops images out of a video.
# If tSingleImage is defined (time, not frame number), only one image will be popped
if outputFolder == 'default':
outputFolder = os.path.dirname(videoPath)
# already written out?
if not os.path.exists(os.path.join(outputFolder, filePrefix + '_0.jpg')) or not skipIfRun:
if tSingleImage is not None: # pop single image at time value
CMD = ('ffmpeg -loglevel error -skip_frame nokey -y -ss ' + str(tSingleImage) + ' -i ' + videoPath +
" -qmin 1 -q:v 1 -frames:v 1 -vf select='-eq(pict_type\,I)' " +
os.path.join(outputFolder,filePrefix + '0.png'))
os.system(CMD)
outImagePath = os.path.join(outputFolder,filePrefix + '0.png')
else: # pop multiple images from video
lengthVideo = getVideoLength(videoPath)
timeImageSamples = np.linspace(1,lengthVideo-1,nImages) # disregard first and last second
for iFrame,t_image in enumerate(timeImageSamples):
CMD = ('ffmpeg -loglevel error -skip_frame nokey -ss ' + str(t_image) + ' -i ' + videoPath +
" -qmin 1 -q:v 1 -frames:v 1 -vf select='-eq(pict_type\,I)' " +
os.path.join(outputFolder,filePrefix) + '_' + str(iFrame) + '.jpg')
os.system(CMD)
outImagePath = os.path.join(outputFolder,filePrefix) + '0.jpg'
return outImagePath
# %%
def calcIntrinsics(folderName, CheckerBoardParams=None, filenames=['*.jpg'],
imageScaleFactor=1, visualize=False, saveFileName=None):
if CheckerBoardParams is None:
# number of black to black corners and side length (cm)
CheckerBoardParams = {'dimensions': (6,9), 'squareSize': 2.71}
if '*' in filenames[0]:
imageFiles = glob.glob(folderName + '/' + filenames[0])
else:
imageFiles = [] ;
for fName in filenames:
imageFiles.append(folderName + '/' + fName)
# stop the iteration when specified
# accuracy, epsilon, is reached or
# specified number of iterations are completed.
criteria = (cv2.TERM_CRITERIA_EPS +
cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001)
# Vector for 3D points
threedpoints = []
# Vector for 2D points
twodpoints = []
# 3D points real world coordinates
# objectp3d = generate3Dgrid(CheckerBoardParams)
# Load images in for calibration
for iImage, pathName in enumerate(imageFiles):
image = cv2.imread(pathName)
if imageScaleFactor != 1:
dim = (int(imageScaleFactor*image.shape[1]),int(imageScaleFactor*image.shape[0]))
image = cv2.resize(image,dim,interpolation=cv2.INTER_AREA)
imageSize = np.reshape(np.asarray(np.shape(image)[0:2]).astype(np.float64),(2,1)) # This all to be able to copy camera param dictionary
grayColor = cv2.cvtColor(image, cv2.COLOR_BGR2GRAY)
print(pathName + ' used for intrinsics calibration.')
# Find the chess board corners
# If desired number of corners are
# found in the image then ret = true
# ret, corners = cv2.findChessboardCorners(
# grayColor, CheckerBoardParams['dimensions'],
# cv2.CALIB_CB_ADAPTIVE_THRESH
# + cv2.CALIB_CB_FAST_CHECK +
# cv2.CALIB_CB_NORMALIZE_IMAGE)
ret,corners,meta = cv2.findChessboardCornersSBWithMeta( grayColor, CheckerBoardParams['dimensions'],
cv2.CALIB_CB_EXHAUSTIVE +
cv2.CALIB_CB_ACCURACY +
cv2.CALIB_CB_LARGER)
# If desired number of corners can be detected then,
# refine the pixel coordinates and display
# them on the images of checker board
if ret == True:
# 3D points real world coordinates
checkerCopy = copy.copy(CheckerBoardParams)
checkerCopy['dimensions'] = meta.shape[::-1] # reverses order so width is first
objectp3d = generate3Dgrid(checkerCopy)
threedpoints.append(objectp3d)
# Refining pixel coordinates
# for given 2d points.
# corners2 = cv2.cornerSubPix(
# grayColor, corners, (11, 11), (-1, -1), criteria)
corners2 = corners/imageScaleFactor # Don't need subpixel refinement with findChessboardCornersSBWithMeta
twodpoints.append(corners2)
# Draw and display the corners
image = cv2.drawChessboardCorners(image,
meta.shape[::-1],
corners2, ret)
#findAspectRatio
ar = imageSize[1]/imageSize[0]
# cv2.namedWindow("img", cv2.WINDOW_NORMAL)
cv2.resize(image,(int(600*ar),600))
# Save intrinsic images
imageSaveDir = os.path.join(folderName,'IntrinsicCheckerboards')
if not os.path.exists(imageSaveDir):
os.mkdir(imageSaveDir)
cv2.imwrite(os.path.join(imageSaveDir,'intrinsicCheckerboard' + str(iImage) + '.jpg'), image)
if visualize:
print('Press enter or close image to continue')
cv2.imshow('img', image)
cv2.waitKey(0)
cv2.destroyAllWindows()
if ret == False:
print("Couldn't find checkerboard in " + pathName)
if len(twodpoints) < .5*len(imageFiles):
print('Checkerboard not detected in at least half of intrinsic images. Re-record video.')
return None
# Perform camera calibration by
# passing the value of above found out 3D points (threedpoints)
# and its corresponding pixel coordinates of the
# detected corners (twodpoints)
ret, matrix, distortion, r_vecs, t_vecs = cv2.calibrateCamera(
threedpoints, twodpoints, grayColor.shape[::-1], None, None)
CamParams = {'distortion':distortion,'intrinsicMat':matrix,'imageSize':imageSize}
if saveFileName is not None:
saveCameraParameters(saveFileName,CamParams)
return CamParams
# %%
def computeAverageIntrinsics(session_path,trialIDs,CheckerBoardParams,nImages=25,cameraModel= None,videoType=".mov"):
CamParamList = []
camModels = []
trial_name = ''
for trial_id in trialIDs:
if cameraModel is None:
resp = requests.get(API_URL + "trials/{}/".format(trial_id),
headers = {"Authorization": "Token {}".format(API_TOKEN)})
trial = resp.json()
camModels.append(trial['videos'][0]['parameters']['model'])
trial_name = trial['name']
else:
camModels.append(cameraModel)
if trial_name == '':
trial_name = trial_id
# Make directory (folder for trialname, intrinsics also saved there)
video_dir = os.path.join(session_path,trial_name)
os.makedirs(video_dir, exist_ok=True)
video_path = os.path.join(video_dir,trial_name + videoType)
# Download video if not done
if not os.path.exists(video_path):
download_file(trial["videos"][0]["video"], video_path)
if not os.path.exists(os.path.join(video_dir,'cameraIntrinsics.pickle')):
# Compute intrinsics from images popped out of intrinsic video.
video2Images(video_path,filePrefix=trial_name,nImages=nImages)
CamParams = calcIntrinsics(os.path.join(session_path,trial_name), CheckerBoardParams=CheckerBoardParams,
filenames=['*.jpg'],
saveFileName=os.path.join(video_dir,'cameraIntrinsics.pickle'),
visualize = False)
if CamParams is None:
saveCameraParameters(os.path.join(video_dir,'cameraIntrinsics.pickle'),CamParams)
else:
CamParams = loadCameraParameters(os.path.join(video_dir,'cameraIntrinsics.pickle'))
if CamParams is not None:
CamParamList.append(CamParams)
# Compute results
intComp = {}
intComp['fx'] = [c['intrinsicMat'][0,0] for c in CamParamList]
intComp['fy'] = [c['intrinsicMat'][1,1] for c in CamParamList]
intComp['cx'] = [c['intrinsicMat'][0,2] for c in CamParamList]
intComp['cy'] = [c['intrinsicMat'][1,2] for c in CamParamList]
intComp['d'] = np.asarray([c['distortion'] for c in CamParamList])
intCompNames = list(intComp.keys())
for v in intCompNames:
intComp[v + '_u'] = np.mean(intComp[v],axis=0)
intComp[v + '_std'] = np.std(intComp[v],axis=0)
intComp[v + '_stdPerc'] = np.divide(intComp[v + '_std'],intComp[v + '_u']) * 100
phoneModel = camModels[0]
if any([camModel != phoneModel for camModel in camModels]):
raise Exception('You are averaging intrinsics across different phone models.')
# output averaged parameters
CamParamsAverage = {}
params = list(CamParamList[0].keys())
for param in params:
CamParamsAverage[param] = np.mean(np.asarray([c[param] for c in CamParamList]),axis=0)
return CamParamsAverage, CamParamList, intComp, phoneModel
# %%
def generate3Dgrid(CheckerBoardParams):
# 3D points real world coordinates. Assuming z=0
objectp3d = np.zeros((1, CheckerBoardParams['dimensions'][0]
* CheckerBoardParams['dimensions'][1],
3), np.float32)
objectp3d[0, :, :2] = np.mgrid[0:CheckerBoardParams['dimensions'][0],
0:CheckerBoardParams['dimensions'][1]].T.reshape(-1, 2)
objectp3d = objectp3d * CheckerBoardParams['squareSize']
return objectp3d
# %%
def saveCameraParameters(filename,CameraParams):
if not os.path.exists(os.path.dirname(filename)):
os.makedirs(os.path.dirname(filename),exist_ok=True)
open_file = open(filename, "wb")
pickle.dump(CameraParams, open_file)
open_file.close()
return True
#%%
def getVideoRotation(videoPath):
meta = ffmpeg.probe(videoPath)
try:
rotation = meta['format']['tags']['com.apple.quicktime.video-orientation']
except:
# For AVI (after we rewrite video), no rotation paramter, so just using h and w.
# For now this is ok, we don't need leaning right/left for this, just need to know
# how to orient the pose estimation resolution parameters.
try:
if meta['format']['format_name'] == 'avi':
if meta['streams'][0]['height']>meta['streams'][0]['width']:
rotation = 90
else:
rotation = 0
else:
raise Exception('no rotation info')
except:
rotation = 90 # upright is 90, and intrinsics were captured in that orientation
return int(rotation)
#%%
def rotateIntrinsics(CamParams,videoPath):
rotation = getVideoRotation(videoPath)
# upright is 90, which is how intrinsics recorded so no rotation needed
if rotation !=90:
originalCamParams = copy.deepcopy(CamParams)
fx = originalCamParams['intrinsicMat'][0,0]
fy = originalCamParams['intrinsicMat'][1,1]
px = originalCamParams['intrinsicMat'][0,2]
py = originalCamParams['intrinsicMat'][1,2]
lx = originalCamParams['imageSize'][1]
ly = originalCamParams['imageSize'][0]
if rotation == 0: # leaning left
# Flip image size
CamParams['imageSize'] = np.flipud(CamParams['imageSize'])
# Flip focal lengths
CamParams['intrinsicMat'][0,0] = fy
CamParams['intrinsicMat'][1,1] = fx
# Change principle point - from upper left
CamParams['intrinsicMat'][0,2] = py
CamParams['intrinsicMat'][1,2] = lx-px
elif rotation == 180: # leaning right
# Flip image size
CamParams['imageSize'] = np.flipud(CamParams['imageSize'])
# Flip focal lengths
CamParams['intrinsicMat'][0,0] = fy
CamParams['intrinsicMat'][1,1] = fx
# Change principle point - from upper left
CamParams['intrinsicMat'][0,2] = ly-py
CamParams['intrinsicMat'][1,2] = px
elif rotation == 270: # upside down
# Change principle point - from upper left
CamParams['intrinsicMat'][0,2] = lx-px
CamParams['intrinsicMat'][1,2] = ly-py
return CamParams
# %%
def calcExtrinsics(imageFileName, CameraParams, CheckerBoardParams,
imageScaleFactor=1,visualize=False,
imageUpsampleFactor=1,useSecondExtrinsicsSolution=False):
# Camera parameters is a dictionary with intrinsics
# stop the iteration when specified
# accuracy, epsilon, is reached or
# specified number of iterations are completed.
criteria = (cv2.TERM_CRITERIA_EPS +
cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001)
# Vector for 3D points
threedpoints = []
# Vector for 2D points
twodpoints = []
# 3D points real world coordinates. Assuming z=0
objectp3d = generate3Dgrid(CheckerBoardParams)
# Load and resize image - remember calibration image res needs to be same as all processing
image = cv2.imread(imageFileName)
if imageScaleFactor != 1:
dim = (int(imageScaleFactor*image.shape[1]),int(imageScaleFactor*image.shape[0]))
image = cv2.resize(image,dim,interpolation=cv2.INTER_AREA)
if imageUpsampleFactor != 1:
dim = (int(imageUpsampleFactor*image.shape[1]),int(imageUpsampleFactor*image.shape[0]))
imageUpsampled = cv2.resize(image,dim,interpolation=cv2.INTER_AREA)
else:
imageUpsampled = image
# Find the chess board corners
# If desired number of corners are
# found in the image then ret = true
#TODO need to add a timeout to the findChessboardCorners function
grayColor = cv2.cvtColor(imageUpsampled, cv2.COLOR_BGR2GRAY)
## Contrast TESTING - openCV does thresholding already, but this may be a bit helpful for bumping contrast
# grayColor = grayColor.astype('float64')
# cv2.imshow('Grayscale', grayColor.astype('uint8'))
# savePath = os.path.join(os.path.dirname(imageFileName),'extrinsicGray.jpg')
# cv2.imwrite(savePath,grayColor)
# grayContrast = np.power(grayColor,2)
# grayContrast = grayContrast/(np.max(grayContrast)/255)
# # plt.figure()
# # plt.imshow(grayContrast, cmap='gray')
# # cv2.imshow('ContrastEnhanced', grayContrast.astype('uint8'))
# savePath = os.path.join(os.path.dirname(imageFileName),'extrinsicGrayContrastEnhanced.jpg')
# cv2.imwrite(savePath,grayContrast)
# grayContrast = grayContrast.astype('uint8')
# grayColor = grayColor.astype('uint8')
## End contrast Testing
## Testing settings - slow and don't help
# ret, corners = cv2.findChessboardCorners(
# grayContrast, CheckerBoardParams['dimensions'],
# cv2.CALIB_CB_ADAPTIVE_THRESH
# + cv2.CALIB_CB_FAST_CHECK +
# cv2.CALIB_CB_NORMALIZE_IMAGE)
# Note I tried findChessboardCornersSB here, but it didn't find chessboard as reliably
ret, corners = cv2.findChessboardCorners(
grayColor, CheckerBoardParams['dimensions'],
cv2.CALIB_CB_ADAPTIVE_THRESH)
# If desired number of corners can be detected then,
# refine the pixel coordinates and display
# them on the images of checker board
if ret == True:
# 3D points real world coordinates
threedpoints.append(objectp3d)
# Refining pixel coordinates
# for given 2d points.
corners2 = cv2.cornerSubPix(
grayColor, corners, (11, 11), (-1, -1), criteria) / imageUpsampleFactor
twodpoints.append(corners2)
# For testing: Draw and display the corners
# image = cv2.drawChessboardCorners(image,
# CheckerBoardParams['dimensions'],
# corners2, ret)
# Draw small dots instead
# Choose dot size based on size of squares in pixels
circleSize = 1
squareSize = np.linalg.norm((corners2[1,0,:] - corners2[0,0,:]).squeeze())
if squareSize >12:
circleSize = 2
for iPoint in range(corners2.shape[0]):
thisPt = corners2[iPoint,:,:].squeeze()
cv2.circle(image, tuple(thisPt.astype(int)), circleSize, (255,255,0), 2)
#cv2.imshow('img', image)
#cv2.waitKey(0)
#cv2.destroyAllWindows()
if ret == False:
print('No checkerboard detected. Will skip cam in triangulation.')
return None
# Find position and rotation of camera in board frame.
# ret, rvec, tvec = cv2.solvePnP(objectp3d, corners2,
# CameraParams['intrinsicMat'],
# CameraParams['distortion'])
# This function gives two possible solutions.
# It helps with the ambiguous cases with small checkerboards (appears like
# left handed coord system). Unfortunately, there isn't a clear way to
# choose the correct solution. It is the nature of the solvePnP problem
# with a bit of 2D point noise.
rets, rvecs, tvecs, reprojError = cv2.solvePnPGeneric(
objectp3d, corners2, CameraParams['intrinsicMat'],
CameraParams['distortion'], flags=cv2.SOLVEPNP_IPPE)
rvec = rvecs[1]
tvec = tvecs[1]
if rets < 1 or np.max(rvec) == 0 or np.max(tvec) == 0:
print('solvePnPGeneric failed. Use SolvePnPRansac')
# Note: can input extrinsics guess if we generally know where they are.
# Add to lists to look like solvePnPRansac results
rvecs = []
tvecs = []
ret, rvec, tvec, inliers = cv2.solvePnPRansac(
objectp3d, corners2, CameraParams['intrinsicMat'],
CameraParams['distortion'])
if ret is True:
rets = 1
rvecs.append(rvec)
tvecs.append(tvec)
else:
print('Extrinsic calculation failed. Will skip cam in triangulation.')
return None
# Select which extrinsics solution to use
extrinsicsSolutionToUse = 0
if useSecondExtrinsicsSolution:
extrinsicsSolutionToUse = 1
topLevelExtrinsicImageFolder = os.path.abspath(
os.path.join(os.path.dirname(imageFileName),
'../../../../CalibrationImages'))
if not os.path.exists(topLevelExtrinsicImageFolder):
os.makedirs(topLevelExtrinsicImageFolder,exist_ok=True)
for iRet,rvec,tvec in zip(range(rets),rvecs,tvecs):
theseCameraParams = copy.deepcopy(CameraParams)
# Show reprojections
img_points, _ = cv2.projectPoints(objectp3d, rvec, tvec,
CameraParams['intrinsicMat'],
CameraParams['distortion'])
# Plot reprojected points
# for c in img_points.squeeze():
# cv2.circle(image, tuple(c.astype(int)), 2, (0, 255, 0), 2)
# Show object coordinate system
imageCopy = copy.deepcopy(image)
imageWithFrame = cv2.drawFrameAxes(
imageCopy, CameraParams['intrinsicMat'],
CameraParams['distortion'], rvec, tvec, 200, 4)
# Create zoomed version.
ht = image.shape[0]
wd = image.shape[1]
bufferVal = 0.05 * np.mean([ht,wd])
topEdge = int(np.max([np.squeeze(np.min(img_points,axis=0))[1]-bufferVal,0]))
leftEdge = int(np.max([np.squeeze(np.min(img_points,axis=0))[0]-bufferVal,0]))
bottomEdge = int(np.min([np.squeeze(np.max(img_points,axis=0))[1]+bufferVal,ht]))
rightEdge = int(np.min([np.squeeze(np.max(img_points,axis=0))[0]+bufferVal,wd]))
# imageCopy2 = copy.deepcopy(imageWithFrame)
imageCropped = imageCopy[topEdge:bottomEdge,leftEdge:rightEdge,:]
# Save extrinsics picture with axis
imageSize = np.shape(image)[0:2]
#findAspectRatio
ar = imageSize[1]/imageSize[0]
# cv2.namedWindow("axis", cv2.WINDOW_NORMAL)
cv2.resize(imageWithFrame,(600,int(np.round(600*ar))))
# save crop image to local camera file
savePath2 = os.path.join(os.path.dirname(imageFileName),
'extrinsicCalib_soln{}.jpg'.format(iRet))
cv2.imwrite(savePath2,imageCropped)
if visualize:
print('Close image window to continue')
cv2.imshow('axis', image)
cv2.waitKey()
cv2.destroyAllWindows()
R_worldFromCamera = cv2.Rodrigues(rvec)[0]
theseCameraParams['rotation'] = R_worldFromCamera
theseCameraParams['translation'] = tvec
theseCameraParams['rotation_EulerAngles'] = rvec
# save extrinsics parameters to video folder
# will save the selected parameters in Camera folder in main
saveExtPath = os.path.join(
os.path.dirname(imageFileName),
'cameraIntrinsicsExtrinsics_soln{}.pickle'.format(iRet))
saveCameraParameters(saveExtPath,theseCameraParams)
# save images to top level folder and return correct extrinsics
camName = os.path.split(os.path.abspath(
os.path.join(os.path.dirname(imageFileName), '../../')))[1]
if iRet == extrinsicsSolutionToUse:
fullCamName = camName
CameraParamsToUse = copy.deepcopy(theseCameraParams)
else:
fullCamName = 'altSoln_{}'.format(camName)
savePath = os.path.join(topLevelExtrinsicImageFolder, 'extrinsicCalib_'
+ fullCamName + '.jpg')
cv2.imwrite(savePath,imageCropped)
return CameraParamsToUse
# %%
def calcExtrinsicsFromVideo(videoPath, CamParams, CheckerBoardParams,
visualize=False, imageUpsampleFactor=2,
useSecondExtrinsicsSolution=False):
# Get video parameters.
vidLength = getVideoLength(videoPath)
videoDir, videoName = os.path.split(videoPath)
# Pick end of video as only sample point. For some reason, won't output
# video with t close to vidLength, so we count down til it does.
tSampPts = [np.round(vidLength-0.3, decimals=1)]
upsampleIters = 0
for iTime,t in enumerate(tSampPts):
# Pop an image.
imagePath = os.path.join(videoDir, 'extrinsicImage0.png')
if os.path.exists(imagePath):
os.remove(imagePath)
while not os.path.exists(imagePath) and t>=0:
video2Images(videoPath, nImages=1, tSingleImage=t, filePrefix='extrinsicImage', skipIfRun=False)
t -= 0.2
# Default to beginning if can't find a keyframe.
if not os.path.exists(imagePath):
video2Images(videoPath, nImages=1, tSingleImage=0.01, filePrefix='extrinsicImage', skipIfRun=False)
# Throw error if it can't find a keyframe.
if not os.path.exists(imagePath):
exception = 'No calibration image could be extracted for at least one camera. Verify your setup and try again. Visit https://www.opencap.ai/best-pratices to learn more about camera calibration and https://www.opencap.ai/troubleshooting for potential causes for a failed calibration.'
raise Exception(exception, exception)
# Try to find the checkerboard; return None if you can't find it.
CamParamsTemp = calcExtrinsics(
os.path.join(videoDir, 'extrinsicImage0.png'),
CamParams, CheckerBoardParams, visualize=visualize,
imageUpsampleFactor=imageUpsampleFactor,
useSecondExtrinsicsSolution=useSecondExtrinsicsSolution)
while iTime == 0 and CamParamsTemp is None and upsampleIters < 3:
if imageUpsampleFactor > 1:
imageUpsampleFactor = 1
elif imageUpsampleFactor == 1:
imageUpsampleFactor = .5
elif imageUpsampleFactor < 1:
imageUpsampleFactor = 1
CamParamsTemp = calcExtrinsics(
os.path.join(videoDir, 'extrinsicImage0.png'),
CamParams, CheckerBoardParams, visualize=visualize,
imageUpsampleFactor=imageUpsampleFactor,
useSecondExtrinsicsSolution=useSecondExtrinsicsSolution)
upsampleIters += 1
if CamParamsTemp is not None:
# If checkerboard was found, exit.
CamParams = CamParamsTemp.copy()
return CamParams
# If made it through but didn't return camera params, throw an error.
exception = 'The checkerboard was not detected by at least one camera. Verify your setup and try again. Visit https://www.opencap.ai/best-pratices to learn more about camera calibration and https://www.opencap.ai/troubleshooting for potential causes for a failed calibration.'
raise Exception(exception, exception)
return None
# %%
def isCheckerboardUpsideDown(CameraParams):
# With backwall orientation, R[1,1] will always be positive in correct orientation
# and negative if upside down
for cam in list(CameraParams.keys()):
if CameraParams[cam] is not None:
upsideDown = CameraParams[cam]['rotation'][1,1] < 0
break
#Default if no camera params (which is a garbage case anyway)
upsideDown = False
return upsideDown
# %%
def autoSelectExtrinsicSolution(sessionDir,keypoints2D,confidence,extrinsicsOptions):
keypoints2D = copy.copy(keypoints2D)
confidence = copy.copy(confidence)
camNames = list(extrinsicsOptions.keys())
optimalCalibrationDict = {}
# Order the cameras based on biggest difference between solutions. Want to start
# with these
if len(camNames)>2:
camNames = orderCamerasForAutoCalDetection(extrinsicsOptions)
# Find first pair of cameras
optimalCalibrationDict[camNames[0]], optimalCalibrationDict[camNames[1]] = computeOptimalCalibrationCombination(
keypoints2D,confidence,extrinsicsOptions,[camNames[0],camNames[1]])
# Continue for third and additional cameras
additionalCameras = []
if len(camNames)>2:
additionalCameras = camNames[2:]
for camName in additionalCameras:
_, optimalCalibrationDict[camName] = computeOptimalCalibrationCombination(
keypoints2D,confidence,extrinsicsOptions,[camNames[0],camName],
firstCamSoln=optimalCalibrationDict[camNames[0]])
# save calibrationJson to Videos
calibrationOptionsFile = os.path.join(sessionDir,'Videos','calibOptionSelections.json')
with open(calibrationOptionsFile, 'w') as f:
json.dump(optimalCalibrationDict, f)
f.close()
# Make camera params dict
CamParamDict = {}
for camName in camNames:
CamParamDict[camName] = extrinsicsOptions[camName][optimalCalibrationDict[camName]]
# Switch any cameras in local file system.
for cam,val in optimalCalibrationDict.items():
if val == 1:
saveFileName = os.path.join(sessionDir,'Videos',cam,'cameraIntrinsicsExtrinsics.pickle')
saveCameraParameters(saveFileName,extrinsicsOptions[cam][1])
return CamParamDict
# %%
def computeOptimalCalibrationCombination(keypoints2D,confidence,extrinsicsOptions,
CamNames,firstCamSoln=None):
if firstCamSoln is None:
firstCamOptions = range(len(extrinsicsOptions[CamNames[0]]))
else:
firstCamOptions = [firstCamSoln]
# Remove face markers - they are intermittent.
_, idxFaceMarkers = getOpenPoseFaceMarkers()
#find most confident frame
confidenceMat = np.minimum(confidence[CamNames[0]],confidence[CamNames[1]])
confidenceMat = np.delete(confidenceMat, idxFaceMarkers,axis=0)
iFrame = np.argmax(confidenceMat.mean(axis=1))
# put keypoints in list and delete face markers
keypointList = [np.expand_dims(np.delete(keypoints2D[CamNames[0]],idxFaceMarkers,axis=0)[:,iFrame],axis=1),
np.expand_dims(np.delete(keypoints2D[CamNames[1]],idxFaceMarkers,axis=0)[:,iFrame],axis=1)]
meanReprojectionErrors = []
combinations = []
for iCam0 in firstCamOptions:
for iCam1 in range(len(extrinsicsOptions[CamNames[1]])):
combinations.append([iCam0,iCam1])
CameraParamList = [extrinsicsOptions[CamNames[0]][iCam0],
extrinsicsOptions[CamNames[1]][iCam1]]
# triangulate
points3D,_ = triangulateMultiview(CameraParamList,keypointList)
# reproject
# Make list of camera objects
cameraObjList = []
for camParams in CameraParamList:
c = Camera()
c.set_K(camParams['intrinsicMat'])
c.set_R(camParams['rotation'])
c.set_t(np.reshape(camParams['translation'],(3,1)))
cameraObjList.append(c)
# Organize points for reprojectionError function
stackedPoints = np.stack([k[:,None,0,:] for k in keypointList])
pointsInput = []
for i in range(stackedPoints.shape[1]):
pointsInput.append(stackedPoints[:,i,0,:].T)
# Calculate combined reprojection error
reprojError = calcReprojectionError(cameraObjList,pointsInput,points3D,
normalizeError=True)
meanReprojectionErrors.append(np.mean(reprojError))
# Select solution with minimum error
idx = np.argmin(meanReprojectionErrors)
if (sorted(meanReprojectionErrors)[1]-sorted(meanReprojectionErrors)[0])/sorted(meanReprojectionErrors)[0] < .5:
# This only happens when the vector from checker board origin to camera is < a few degrees. If you offset the board
# vertically by a few feet, the solution becomes very clear again (ratio of ~7). We could throw an error.
print("Warning: not much separability between auto checker board selection options. Try moving checkerboard closer to cameras, and move it so it is not straight-on with any of the cameras.")
# Pick default to first solution when they are super close like this.
idx = 0
return combinations[idx][0], combinations[idx][1]
# %%
def orderCamerasForAutoCalDetection(extrinsicsOptions):
# dict of rotations between first and second solutions
rotDifs = []
testVec = np.array((1,0,0))
for cals in extrinsicsOptions.values():
rot = np.matmul(cals[0]['rotation'],cals[1]['rotation'])
# This will be close to 0 if the rotation was small, 2 if it is 180
rotDifs.append(1-np.dot(np.matmul(testVec,rot),testVec))
sortedCams = [cam for _, cam in sorted(zip(rotDifs, extrinsicsOptions.keys()),reverse=True)]
return sortedCams
# %%
def synchronizeVideos(CameraDirectories, trialRelativePath, pathPoseDetector,
undistortPoints=False, CamParamDict=None,
confidenceThreshold=0.3,
filtFreqs={'gait':12,'default':30},
imageBasedTracker=False, cams2Use=['all'],
poseDetector='OpenPose', trialName=None, bbox_thr=0.8,
resolutionPoseDetection='default',
visualizeKeypointAnimation=False):
markerNames = getOpenPoseMarkerNames()
# Create list of cameras.
if cams2Use[0] == 'all':
cameras2Use = list(CameraDirectories.keys())
else:
cameras2Use = cams2Use
cameras2Use_in = copy.deepcopy(cameras2Use)
# Initialize output lists
pointList = []
confList = []
CameraDirectories_selectedCams = {}
CamParamList_selectedCams = []
for cam in cameras2Use:
CameraDirectories_selectedCams[cam] = CameraDirectories[cam]
CamParamList_selectedCams.append(CamParamDict[cam])
# Load data.
camsToExclude = []
for camName in CameraDirectories_selectedCams:
cameraDirectory = CameraDirectories_selectedCams[camName]
videoFullPath = os.path.normpath(os.path.join(cameraDirectory,
trialRelativePath))
trialPrefix, _ = os.path.splitext(
os.path.basename(trialRelativePath))
if poseDetector == 'OpenPose':
outputPklFolder = "OutputPkl_" + resolutionPoseDetection
elif poseDetector == 'mmpose':
outputPklFolder = "OutputPkl_mmpose_" + str(bbox_thr)
openposePklDir = os.path.join(outputPklFolder, trialName)
pathOutputPkl = os.path.join(cameraDirectory, openposePklDir)
ppPklPath = os.path.join(pathOutputPkl, trialPrefix+'_rotated_pp.pkl')
key2D, confidence = loadPklVideo(
ppPklPath, videoFullPath, imageBasedTracker=imageBasedTracker,
poseDetector=poseDetector,confidenceThresholdForBB=0.3)
thisVideo = cv2.VideoCapture(videoFullPath.replace('.mov', '_rotated.avi'))
frameRate = np.round(thisVideo.get(cv2.CAP_PROP_FPS))
if key2D.shape[1] == 0 and confidence.shape[1] == 0:
camsToExclude.append(camName)
else:
pointList.append(key2D)
confList.append(confidence)
# If video is not existing, the corresponding camera should be removed.
idx_camToExclude = []
for camToExclude in camsToExclude:
cameras2Use.remove(camToExclude)
CameraDirectories_selectedCams.pop(camToExclude)
idx_camToExclude.append(cameras2Use_in.index(camToExclude))
# By removing the cameras in CamParamDict and CameraDirectories, we
# modify those dicts in main, which is needed for the next stages.
CamParamDict.pop(camToExclude)
CameraDirectories.pop(camToExclude)
delete_multiple_element(CamParamList_selectedCams, idx_camToExclude)
# Creates a web animation for each camera's keypoints. For debugging.
if visualizeKeypointAnimation:
import plotly.express as px
import plotly.io as pio
pio.renderers.default = 'browser'
for i,data in enumerate(pointList):
nPoints,nFrames,_ = data.shape
# Reshape the 3D numpy array to 2D, preserving point and frame indices
data_reshaped = np.copy(data).reshape(-1, 2)
# Create DataFrame
df = pd.DataFrame(data_reshaped, columns=['x', 'y'])
# Add columns for point number and frame number
df['Point'] = np.repeat(np.arange(nPoints), nFrames)
df['Frame'] = np.tile(np.arange(nFrames), nPoints)
# Reorder columns if needed
df = df[['Point', 'Frame', 'x', 'y']]
# Create a figure and add an animated scatter plot
fig = px.scatter(df,x='x', y='y', title="Cam " + str(i),
animation_frame='Frame',
range_x=[0, 1200], range_y=[1200,0],
color='Point', color_continuous_scale=px.colors.sequential.Viridis)
# Show the animation
fig.show()
# Synchronize keypoints.
pointList, confList, nansInOutList,startEndFrameList = synchronizeVideoKeypoints(
pointList, confList, confidenceThreshold=confidenceThreshold,
filtFreqs=filtFreqs, sampleFreq=frameRate, visualize=False,
maxShiftSteps=2*frameRate, CameraParams=CamParamList_selectedCams,
cameras2Use=cameras2Use,
CameraDirectories=CameraDirectories_selectedCams, trialName=trialName)
if undistortPoints:
if CamParamList_selectedCams is None:
raise Exception('Need to have CamParamList to undistort Images')
# nFrames = pointList[0].shape[1]
unpackedPoints = unpackKeypointList(pointList) ;
undistortedPoints = []
for points in unpackedPoints:
undistortedPoints.append(undistort2Dkeypoints(
points, CamParamList_selectedCams, useIntrinsicMatAsP=True))
pointList = repackKeypointList(undistortedPoints)
pointDir = {}
confDir = {}
nansInOutDir = {}
startEndFrames = {}
for iCam, camName in enumerate(CameraDirectories_selectedCams):
pointDir[camName] = pointList[iCam]
confDir[camName] = confList[iCam]
nansInOutDir[camName] = nansInOutList[iCam]
startEndFrames[camName] = startEndFrameList[iCam]
return pointDir, confDir, markerNames, frameRate, nansInOutDir, startEndFrames, cameras2Use
# %%
def synchronizeVideoKeypoints(keypointList, confidenceList,
confidenceThreshold=0.3,
filtFreqs = {'gait':12,'default':500},
sampleFreq=30, visualize=False, maxShiftSteps=30,
isGait=False, CameraParams = None,
cameras2Use=['none'],CameraDirectories = None,
trialName=None, trialID=''):
visualize2Dkeypoint = False # this is a visualization just for testing what filtered input data looks like
# keypointList is a mCamera length list of (nmkrs,nTimesteps,2) arrays of camera 2D keypoints
print('Synchronizing Keypoints')
# Deep copies such that the inputs do not get modified.
c_CameraParams = copy.deepcopy(CameraParams)
c_cameras2Use = copy.deepcopy(cameras2Use)
c_CameraDirectoryDict = copy.deepcopy(CameraDirectories)
# Turn Camera Dict into List
c_CameraDirectories = list(c_CameraDirectoryDict.values())
# Check if one camera has only 0s as confidence scores, which would mean
# no one has been properly identified. We want to kick out this camera
# from the synchronization and triangulation. We do that by popping out
# the corresponding data before syncing and add back 0s later.
badCameras = []
for icam, conf in enumerate(confidenceList):
if np.max(conf) == 0.0:
badCameras.append(icam)
idxBadCameras = [badCameras[i]-i for i in range(len(badCameras))]
for idxBadCamera in idxBadCameras:
print('{} kicked out of synchronization'.format(
c_cameras2Use[idxBadCamera]))
keypointList.pop(idxBadCamera)
confidenceList.pop(idxBadCamera)
c_CameraParams.pop(idxBadCamera)
c_cameras2Use.pop(idxBadCamera)
c_CameraDirectories.pop(idxBadCamera)
markerNames = getOpenPoseMarkerNames()
mkrDict = {mkr:iMkr for iMkr,mkr in enumerate(markerNames)}
# First, remove occluded markers
footMkrs = {'right':[mkrDict['RBigToe'], mkrDict['RSmallToe'], mkrDict['RHeel'],mkrDict['RAnkle']],
'left':[mkrDict['LBigToe'], mkrDict['LSmallToe'], mkrDict['LHeel'],mkrDict['LAnkle']]}
armMkrs = {'right':[mkrDict['RElbow'], mkrDict['RWrist']],
'left':[mkrDict['LElbow'], mkrDict['LWrist']]}
plt.close('all')
# Copy for visualization
keypointListUnfilt = copy.deepcopy(keypointList)
# remove occluded foot markers (uses large differences in confidence)
keypointList,confidenceList = zip(*[removeOccludedSide(keys,conf,footMkrs,confidenceThreshold,visualize=False) for keys,conf in zip(keypointList,confidenceList)])
# remove occluded arm markers
keypointList,confidenceList = zip(*[removeOccludedSide(keys,conf,armMkrs,confidenceThreshold,visualize=False) for keys,conf in zip(keypointList,confidenceList)])
# Copy for visualization
keypointListOcclusionRemoved = copy.deepcopy(keypointList)
# Don't change these. The ankle markers are used for gait detector
markers4VertVel = [mkrDict['RAnkle'], mkrDict['LAnkle']] # R&L Ankles and Heels did best. There are some issues though - like when foot marker velocity is aligned with camera ray
markers4HandPunch = [mkrDict['RWrist'], mkrDict['LWrist'],mkrDict['RShoulder'],mkrDict['LShoulder']]
markers4Ankles = [mkrDict['RAnkle'],mkrDict['LAnkle']]
# find velocity signals for synchronization
nCams = len(keypointList)
vertVelList = []
mkrSpeedList = []
handPunchVertPositionList = []
allMarkerList = []
for (keyRaw,conf) in zip(keypointList,confidenceList):
keyRaw_clean, _, _, _ = clean2Dkeypoints(keyRaw,conf,confidenceThreshold=0.3,nCams=nCams,linearInterp=True)
keyRaw_clean_smooth = smoothKeypoints(keyRaw_clean, sdKernel=3)
handPunchVertPositionList.append(getPositions(keyRaw_clean_smooth,markers4HandPunch,direction=1))
vertVelList.append(getVertVelocity(keyRaw_clean_smooth)) # doing it again b/c these settings work well for synchronization
mkrSpeedList.append(getMarkerSpeed(keyRaw_clean_smooth,markers4VertVel,confidence=conf,averageVels=False)) # doing it again b/c these settings work well for synchronization
allMarkerList.append(keyRaw_clean_smooth)
# Find indices with high confidence that overlap between cameras.
# Note: Could get creative and do camera pair syncing in the future, based
# on cameras with greatest amount of overlapping confidence.
overlapInds_clean, minConfLength_all = findOverlap(confidenceList,
markers4VertVel)
# If no overlap found, try with fewer cameras.
c_nCams = len(confidenceList)
while not np.any(overlapInds_clean) and c_nCams>2:
print("Could not find overlap with {} cameras - trying with {} cameras".format(c_nCams, c_nCams-1))
cam_list = [i for i in range(nCams)]