-
Notifications
You must be signed in to change notification settings - Fork 3
/
calibration_utils_kt_local.py
1248 lines (1076 loc) · 61.6 KB
/
calibration_utils_kt_local.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
#!/usr/bin/env python3
import cv2
import glob
import os
import shutil
import numpy as np
from scipy.spatial.transform import Rotation
import time
import json
import cv2.aruco as aruco
from pathlib import Path
from functools import reduce
from collections import deque
from typing import Optional
# Creates a set of 13 polygon coordinates
rectProjectionMode = 0
colors = [(0, 255 , 0), (0, 0, 255)]
def setPolygonCoordinates(height, width):
horizontal_shift = width//4
vertical_shift = height//4
margin = 60
slope = 150
p_coordinates = [
[[margin, margin], [margin, height-margin],
[width-margin, height-margin], [width-margin, margin]],
[[margin, 0], [margin, height], [width//2, height-slope], [width//2, slope]],
[[horizontal_shift, 0], [horizontal_shift, height], [
width//2 + horizontal_shift, height-slope], [width//2 + horizontal_shift, slope]],
[[horizontal_shift*2-margin, 0], [horizontal_shift*2-margin, height], [width//2 +
horizontal_shift*2-margin, height-slope], [width//2 + horizontal_shift*2-margin, slope]],
[[width-margin, 0], [width-margin, height],
[width//2, height-slope], [width//2, slope]],
[[width-horizontal_shift, 0], [width-horizontal_shift, height], [width //
2-horizontal_shift, height-slope], [width//2-horizontal_shift, slope]],
[[width-horizontal_shift*2+margin, 0], [width-horizontal_shift*2+margin, height], [width //
2-horizontal_shift*2+margin, height-slope], [width//2-horizontal_shift*2+margin, slope]],
[[0, margin], [width, margin], [
width-slope, height//2], [slope, height//2]],
[[0, vertical_shift], [width, vertical_shift], [width-slope,
height//2+vertical_shift], [slope, height//2+vertical_shift]],
[[0, vertical_shift*2-margin], [width, vertical_shift*2-margin], [width-slope,
height//2+vertical_shift*2-margin], [slope, height//2+vertical_shift*2-margin]],
[[0, height-margin], [width, height-margin],
[width-slope, height//2], [slope, height//2]],
[[0, height-vertical_shift], [width, height-vertical_shift], [width -
slope, height//2-vertical_shift], [slope, height//2-vertical_shift]],
[[0, height-vertical_shift*2+margin], [width, height-vertical_shift*2+margin], [width -
slope, height//2-vertical_shift*2+margin], [slope, height//2-vertical_shift*2+margin]]
]
return p_coordinates
def getPolygonCoordinates(idx, p_coordinates):
return p_coordinates[idx]
def getNumOfPolygons(p_coordinates):
return len(p_coordinates)
# Filters polygons to just those at the given indexes.
def select_polygon_coords(p_coordinates, indexes):
if indexes == None:
# The default
return p_coordinates
else:
print("Filtering polygons to those at indexes=", indexes)
return [p_coordinates[i] for i in indexes]
def image_filename(polygon_index, total_num_of_captured_images):
return "p{polygon_index}_{total_num_of_captured_images}.png".format(polygon_index=polygon_index, total_num_of_captured_images=total_num_of_captured_images)
def polygon_from_image_name(image_name):
"""Returns the polygon index from an image name (ex: "left_p10_0.png" => 10)"""
return int(re.findall("p(\d+)", image_name)[0])
class StereoCalibration(object):
"""Class to Calculate Calibration and Rectify a Stereo Camera."""
def __init__(self, traceLevel: float = 1.0, outputScaleFactor: float = 0.5, disableCamera: list = []):
self.traceLevel = traceLevel
self.output_scale_factor = outputScaleFactor
self.disableCamera = disableCamera
"""Class to Calculate Calibration and Rectify a Stereo Camera."""
def calibrate(self, board_config, filepath, square_size, mrk_size, squaresX, squaresY, camera_model, enable_disp_rectify):
"""Function to calculate calibration for stereo camera."""
start_time = time.time()
# init object data
if self.traceLevel == 2 or self.traceLevel == 10:
print(f'squareX is {squaresX}')
self.enable_rectification_disp = enable_disp_rectify
self.cameraModel = camera_model
self.data_path = filepath
self.aruco_dictionary = aruco.Dictionary_get(aruco.DICT_4X4_1000)
self.board = aruco.CharucoBoard_create(
# 22, 16,
squaresX, squaresY,
square_size,
mrk_size,
self.aruco_dictionary)
# parameters = aruco.DetectorParameters_create()
combinedCoverageImage = None
resizeWidth, resizeHeight = 1280, 800
assert mrk_size != None, "ERROR: marker size not set"
for camera in board_config['cameras'].keys():
cam_info = board_config['cameras'][camera]
if cam_info["name"] not in self.disableCamera:
images_path = filepath + '/' + cam_info['name']
image_files = glob.glob(images_path + "/*")
image_files.sort()
for im in image_files:
frame = cv2.imread(im)
height, width, _ = frame.shape
widthRatio = resizeWidth / width
heightRatio = resizeHeight / height
if (widthRatio > 0.8 and heightRatio > 0.8 and widthRatio <= 1.0 and heightRatio <= 1.0) or (widthRatio > 1.2 and heightRatio > 1.2) or (resizeHeight == 0):
resizeWidth = width
resizeHeight = height
break
for camera in board_config['cameras'].keys():
cam_info = board_config['cameras'][camera]
if cam_info["name"] not in self.disableCamera:
print(
'<------------Calibrating {} ------------>'.format(cam_info['name']))
images_path = filepath + '/' + cam_info['name']
ret, intrinsics, dist_coeff, _, _, filtered_ids, filtered_corners, size, coverageImage = self.calibrate_intrinsics(
images_path, cam_info['hfov'])
cam_info['intrinsics'] = intrinsics
cam_info['dist_coeff'] = dist_coeff
cam_info['size'] = size # (Width, height)
cam_info['reprojection_error'] = ret
cam_info['filtered_ids'] = filtered_ids
cam_info['filtered_corners'] = filtered_corners
print("Reprojection error of {0}: {1}".format(
cam_info['name'], ret))
if self.traceLevel == 3 or self.traceLevel == 10:
print("Estimated intrinsics of {0}: \n {1}".format(
cam_info['name'], intrinsics))
coverage_name = cam_info['name']
print_text = f'Coverage Image of {coverage_name} with reprojection error of {round(ret,5)}'
height, width, _ = coverageImage.shape
if width > resizeWidth and height > resizeHeight:
coverageImage = cv2.resize(
coverageImage, (0, 0), fx= resizeWidth / width, fy= resizeWidth / width)
height, width, _ = coverageImage.shape
if height > resizeHeight:
height_offset = (height - resizeHeight)//2
coverageImage = coverageImage[height_offset:height_offset+resizeHeight, :]
height, width, _ = coverageImage.shape
height_offset = (resizeHeight - height)//2
width_offset = (resizeWidth - width)//2
subImage = np.pad(coverageImage, ((height_offset, height_offset), (width_offset, width_offset), (0, 0)), 'constant', constant_values=0)
cv2.putText(subImage, print_text, (50, 50+height_offset), cv2.FONT_HERSHEY_SIMPLEX, 2*coverageImage.shape[0]/1750, (0, 0, 0), 2)
if combinedCoverageImage is None:
combinedCoverageImage = subImage
else:
combinedCoverageImage = np.hstack((combinedCoverageImage, subImage))
coverage_file_path = filepath + '/' + coverage_name + '_coverage.png'
cv2.imwrite(coverage_file_path, subImage)
combinedCoverageImage = cv2.resize(combinedCoverageImage, (0, 0), fx=self.output_scale_factor, fy=self.output_scale_factor)
if enable_disp_rectify:
#cv2.imshow('coverage image', combinedCoverageImage)
cv2.waitKey(0)
cv2.destroyAllWindows()
for camera in board_config['cameras'].keys():
left_cam_info = board_config['cameras'][camera]
if str(left_cam_info["name"]) not in self.disableCamera:
if 'extrinsics' in left_cam_info:
if 'to_cam' in left_cam_info['extrinsics']:
left_cam = camera
right_cam = left_cam_info['extrinsics']['to_cam']
left_path = filepath + '/' + left_cam_info['name']
right_cam_info = board_config['cameras'][left_cam_info['extrinsics']['to_cam']]
if str(right_cam_info["name"]) not in self.disableCamera:
right_path = filepath + '/' + right_cam_info['name']
print('<-------------Extrinsics calibration of {} and {} ------------>'.format(
left_cam_info['name'], right_cam_info['name']))
specTranslation = left_cam_info['extrinsics']['specTranslation']
rot = left_cam_info['extrinsics']['rotation']
translation = np.array(
[specTranslation['x'], specTranslation['y'], specTranslation['z']], dtype=np.float32)
rotation = Rotation.from_euler(
'xyz', [rot['r'], rot['p'], rot['y']], degrees=True).as_matrix().astype(np.float32)
extrinsics = self.calibrate_stereo(left_cam_info['filtered_ids'], left_cam_info['filtered_corners'], right_cam_info['filtered_ids'], right_cam_info['filtered_corners'], left_cam_info['intrinsics'], left_cam_info[
'dist_coeff'], right_cam_info['intrinsics'], right_cam_info['dist_coeff'], translation, rotation)
if extrinsics[0] == -1:
return -1, extrinsics[1]
if board_config['stereo_config']['left_cam'] == left_cam and board_config['stereo_config']['right_cam'] == right_cam:
board_config['stereo_config']['rectification_left'] = extrinsics[3]
board_config['stereo_config']['rectification_right'] = extrinsics[4]
elif board_config['stereo_config']['left_cam'] == right_cam and board_config['stereo_config']['right_cam'] == left_cam:
board_config['stereo_config']['rectification_left'] = extrinsics[4]
board_config['stereo_config']['rectification_right'] = extrinsics[3]
""" for stereoObj in board_config['stereo_config']:
if stereoObj['left_cam'] == left_cam and stereoObj['right_cam'] == right_cam and stereoObj['main'] == 1:
stereoObj['rectification_left'] = extrinsics[3]
stereoObj['rectification_right'] = extrinsics[4] """
print('<-------------Epipolar error of {} and {} ------------>'.format(
left_cam_info['name'], right_cam_info['name']))
print(f"dist {left_cam_info['name']}: {left_cam_info['dist_coeff']}")
print(f"dist {right_cam_info['name']}: {right_cam_info['dist_coeff']}")
left_cam_info['extrinsics']['epipolar_error'] = self.test_epipolar_charuco(
left_path,
right_path,
left_cam_info['intrinsics'],
left_cam_info['dist_coeff'],
right_cam_info['intrinsics'],
right_cam_info['dist_coeff'],
extrinsics[2], # Translation between left and right Cameras
extrinsics[3], # Left Rectification rotation
extrinsics[4]) # Right Rectification rotation
left_cam_info['extrinsics']['rotation_matrix'] = extrinsics[1]
left_cam_info['extrinsics']['translation'] = extrinsics[2]
left_cam_info['extrinsics']['stereo_error'] = extrinsics[0]
return 1, board_config
def draw_corners(self, charuco_corners, displayframe):
for corners in charuco_corners:
color = (int(np.random.randint(0, 255)), int(np.random.randint(0, 255)), int(np.random.randint(0, 255)))
for corner in corners:
corner_int = (int(corner[0][0]), int(corner[0][1]))
cv2.circle(displayframe, corner_int, 4, color, -1)
height, width = displayframe.shape[:2]
start_point = (0, 0) # top of the image
end_point = (0, height)
color = (0, 0, 0) # blue in BGR
thickness = 4
# Draw the line on the image
cv2.line(displayframe, start_point, end_point, color, thickness)
return displayframe
def detect_charuco_board(self, image: np.array):
arucoParams = cv2.aruco.DetectorParameters_create()
arucoParams.minMarkerDistanceRate = 0.01
corners, ids, rejectedImgPoints = cv2.aruco.detectMarkers(image, self.aruco_dictionary, parameters=arucoParams) # First, detect markers
marker_corners, marker_ids, refusd, recoverd = cv2.aruco.refineDetectedMarkers(image, self.board, corners, ids, rejectedCorners=rejectedImgPoints)
# If found, add object points, image points (after refining them)
if len(marker_corners)>0:
ret, corners, ids = cv2.aruco.interpolateCornersCharuco(marker_corners,marker_ids,image, self.board, minMarkers = 1)
return ret, corners, ids, marker_corners, marker_ids
else:
return None
def camera_pose_charuco(self, image: np.array, K: np.array, d: np.array):
corners = self.detect_charuco_board(image)
if corners is not None:
ret, p_rvec, p_tvec = cv2.aruco.estimatePoseCharucoBoard(corners[1], corners[2], self.board, K, d, np.empty(1), np.empty(1))
return p_rvec, p_tvec
else:
return None
def compute_reprojection_errors(self, obj_pts: np.array, img_pts: np.array, K: np.array, dist: np.array, rvec: np.array, tvec: np.array, fisheye = False):
if fisheye:
proj_pts, _ = cv2.fisheye.projectPoints(obj_pts, rvec, tvec, K, dist)
else:
proj_pts, _ = cv2.projectPoints(obj_pts, rvec, tvec, K, dist)
errs = np.linalg.norm(np.squeeze(proj_pts) - np.squeeze(img_pts), axis = 1)
return errs
def charuco_ids_to_objpoints(self, ids):
one_pts = self.board.chessboardCorners
objpts = []
for j in range(len(ids)):
objpts.append(one_pts[ids[j]])
return np.array(objpts)
def analyze_charuco(self, images, scale_req=False, req_resolution=(800, 1280)):
"""
Charuco base pose estimation.
"""
# print("POSE ESTIMATION STARTS:")
allCorners = []
allIds = []
all_marker_corners = []
all_marker_ids = []
all_recovered = []
# decimator = 0
# SUB PIXEL CORNER DETECTION CRITERION
criteria = (cv2.TERM_CRITERIA_EPS +
cv2.TERM_CRITERIA_MAX_ITER, 10000, 0.00001)
count = 0
skip_vis = False
for im in images:
if self.traceLevel == 3 or self.traceLevel == 10:
print("=> Processing image {0}".format(im))
img_pth = Path(im)
frame = cv2.imread(im)
gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
expected_height = gray.shape[0]*(req_resolution[1]/gray.shape[1])
if scale_req and not (gray.shape[0] == req_resolution[0] and gray.shape[1] == req_resolution[1]):
if int(expected_height) == req_resolution[0]:
# resizing to have both stereo and rgb to have same
# resolution to capture extrinsics of the rgb-right camera
gray = cv2.resize(gray, req_resolution[::-1],
interpolation=cv2.INTER_CUBIC)
else:
# resizing and cropping to have both stereo and rgb to have same resolution
# to calculate extrinsics of the rgb-right camera
scale_width = req_resolution[1]/gray.shape[1]
dest_res = (
int(gray.shape[1] * scale_width), int(gray.shape[0] * scale_width))
gray = cv2.resize(
gray, dest_res, interpolation=cv2.INTER_CUBIC)
if gray.shape[0] < req_resolution[0]:
raise RuntimeError("resizeed height of rgb is smaller than required. {0} < {1}".format(
gray.shape[0], req_resolution[0]))
# print(gray.shape[0] - req_resolution[0])
del_height = (gray.shape[0] - req_resolution[0]) // 2
# gray = gray[: req_resolution[0], :]
gray = gray[del_height: del_height + req_resolution[0], :]
count += 1
ret, charuco_corners, charuco_ids, marker_corners, marker_ids = self.detect_charuco_board(gray)
if self.traceLevel == 2 or self.traceLevel == 4 or self.traceLevel == 10:
print('{0} number of Markers corners detected in the image {1}'.format(
len(charuco_corners), img_pth.name))
if charuco_corners is not None and charuco_ids is not None and len(charuco_corners) > 3:
cv2.cornerSubPix(gray, charuco_corners,
winSize=(5, 5),
zeroZone=(-1, -1),
criteria=criteria)
allCorners.append(charuco_corners) # Charco chess corners
allIds.append(charuco_ids) # charuco chess corner id's
all_marker_corners.append(marker_corners)
all_marker_ids.append(marker_ids)
else:
print(im)
raise RuntimeError("Failed to detect markers in the image")
if self.traceLevel == 2 or self.traceLevel == 4 or self.traceLevel == 10:
rgb_img = cv2.cvtColor(gray, cv2.COLOR_GRAY2BGR)
cv2.aruco.drawDetectedMarkers(rgb_img, marker_corners, marker_ids, (0, 0, 255))
cv2.aruco.drawDetectedCornersCharuco(rgb_img, charuco_corners, charuco_ids, (0, 255, 0))
if rgb_img.shape[1] > 1920:
rgb_img = cv2.resize(rgb_img, (0, 0), fx=0.7, fy=0.7)
if not skip_vis:
name = img_pth.name + ' - ' + "marker frame"
#cv2.imshow(name, rgb_img)
k = cv2.waitKey(0)
if k == 27: # Esc key to skip vis
skip_vis = True
cv2.destroyAllWindows()
# imsize = gray.shape[::-1]
return allCorners, allIds, all_marker_corners, all_marker_ids, gray.shape[::-1], all_recovered
def calibrate_intrinsics(self, image_files, hfov):
image_files = glob.glob(image_files + "/*")
image_files.sort()
assert len(
image_files) != 0, "ERROR: Images not read correctly, check directory"
allCorners, allIds, _, _, imsize, _ = self.analyze_charuco(image_files)
coverageImage = np.ones(imsize[::-1], np.uint8) * 255
coverageImage = cv2.cvtColor(coverageImage, cv2.COLOR_GRAY2BGR)
coverageImage = self.draw_corners(allCorners, coverageImage)
if self.cameraModel == 'perspective':
ret, camera_matrix, distortion_coefficients, rotation_vectors, translation_vectors, filtered_ids, filtered_corners = self.calibrate_camera_charuco(
allCorners, allIds, imsize, hfov)
# (Height, width)
if self.traceLevel == 4 or self.traceLevel == 5 or self.traceLevel == 10:
self.undistort_visualization(
image_files, camera_matrix, distortion_coefficients, imsize)
return ret, camera_matrix, distortion_coefficients, rotation_vectors, translation_vectors, filtered_ids, filtered_corners, imsize, coverageImage
else:
print('Fisheye--------------------------------------------------')
ret, camera_matrix, distortion_coefficients, rotation_vectors, translation_vectors, filtered_ids, filtered_corners = self.calibrate_fisheye(
allCorners, allIds, imsize, hfov)
if self.traceLevel == 4 or self.traceLevel == 5 or self.traceLevel == 10:
self.undistort_visualization(
image_files, camera_matrix, distortion_coefficients, imsize)
print('Fisheye rotation vector', rotation_vectors[0])
print('Fisheye translation vector', translation_vectors[0])
# (Height, width)
return ret, camera_matrix, distortion_coefficients, rotation_vectors, translation_vectors, filtered_ids, filtered_corners, imsize, coverageImage
def scale_intrinsics(self, intrinsics, originalShape, destShape):
scale = destShape[1] / originalShape[1] # scale on width
scale_mat = np.array([[scale, 0, 0], [0, scale, 0], [0, 0, 1]])
scaled_intrinsics = np.matmul(scale_mat, intrinsics)
""" print("Scaled height offset : {}".format(
(originalShape[0] * scale - destShape[0]) / 2))
print("Scaled width offset : {}".format(
(originalShape[1] * scale - destShape[1]) / 2)) """
scaled_intrinsics[1][2] -= (originalShape[0] # c_y - along height of the image
* scale - destShape[0]) / 2
scaled_intrinsics[0][2] -= (originalShape[1] # c_x width of the image
* scale - destShape[1]) / 2
if self.traceLevel == 3 or self.traceLevel == 10:
print('original_intrinsics')
print(intrinsics)
print('scaled_intrinsics')
print(scaled_intrinsics)
return scaled_intrinsics
def undistort_visualization(self, img_list, K, D, img_size):
for im in img_list:
# print(im)
img = cv2.imread(im)
# h, w = img.shape[:2]
if self.cameraModel == 'perspective':
kScaled, _ = cv2.getOptimalNewCameraMatrix(K, D, img_size, 0)
# print(f'K scaled is \n {kScaled} and size is \n {img_size}')
# print(f'D Value is \n {D}')
map1, map2 = cv2.initUndistortRectifyMap(
K, D, np.eye(3), kScaled, img_size, cv2.CV_32FC1)
else:
map1, map2 = cv2.fisheye.initUndistortRectifyMap(
K, D, np.eye(3), K, img_size, cv2.CV_32FC1)
undistorted_img = cv2.remap(
img, map1, map2, interpolation=cv2.INTER_LINEAR, borderMode=cv2.BORDER_CONSTANT)
#cv2.imshow("undistorted", undistorted_img)
if self.traceLevel == 3 or self.traceLevel == 10:
print(f'image path - {im}')
print(f'Image Undistorted Size {undistorted_img.shape}')
k = cv2.waitKey(0)
if k == 27: # Esc key to stop
break
cv2.destroyWindow("undistorted")
def filter_corner_outliers(self, allIds, allCorners, camera_matrix, distortion_coefficients, rotation_vectors, translation_vectors):
corners_removed = False
for i in range(len(allIds)):
corners = allCorners[i]
ids = allIds[i]
objpts = self.charuco_ids_to_objpoints(ids)
if self.cameraModel == "fisheye":
errs = self.compute_reprojection_errors(objpts, corners, camera_matrix, distortion_coefficients, rotation_vectors[i], translation_vectors[i], fisheye = True)
else:
errs = self.compute_reprojection_errors(objpts, corners, camera_matrix, distortion_coefficients, rotation_vectors[i], translation_vectors[i])
suspicious_err_thr = max(2*np.median(errs), 100)
n_offending_pts = np.sum(errs > suspicious_err_thr)
offending_pts_idxs = np.where(errs > suspicious_err_thr)[0]
# check if there are offending points and if they form a minority
if n_offending_pts > 0 and n_offending_pts < len(corners)/5:
print(f"removing {n_offending_pts} offending points with errs {errs[offending_pts_idxs]}")
corners_removed = True
#remove the offending points
offset = 0
allCorners[i] = np.delete(allCorners[i],offending_pts_idxs, axis = 0)
allIds[i] = np.delete(allIds[i],offending_pts_idxs, axis = 0)
return corners_removed, allIds, allCorners
def calibrate_camera_charuco(self, allCorners, allIds, imsize, hfov):
"""
Calibrates the camera using the dected corners.
"""
f = imsize[0] / (2 * np.tan(np.deg2rad(hfov/2)))
# TODO(sachin): Change the initialization to be initialized using the guess from fov
print("INTRINSIC CALIBRATION")
cameraMatrixInit = np.array([[f, 0.0, imsize[0]/2],
[0.0, f, imsize[1]/2],
[0.0, 0.0, 1.0]])
# cameraMatrixInit = np.array([[857.1668, 0.0, 643.9126],
# [0.0, 856.0823, 387.56018],
# [0.0, 0.0, 1.0]])
""" if imsize[1] < 700:
cameraMatrixInit = np.array([[400.0, 0.0, imsize[0]/2],
[0.0, 400.0, imsize[1]/2],
[0.0, 0.0, 1.0]])
elif imsize[1] < 1100:
cameraMatrixInit = np.array([[857.1668, 0.0, 643.9126],
[0.0, 856.0823, 387.56018],
[0.0, 0.0, 1.0]])
else:
cameraMatrixInit = np.array([[3819.8801, 0.0, 1912.8375],
[0.0, 3819.8801, 1135.3433],
[0.0, 0.0, 1.]]) """
if self.traceLevel == 3 or self.traceLevel == 10:
print(
f'Camera Matrix initialization with HFOV of {hfov} is.............')
print(cameraMatrixInit)
distCoeffsInit = np.zeros((5, 1))
flags = (cv2.CALIB_USE_INTRINSIC_GUESS +
cv2.CALIB_RATIONAL_MODEL)
# flags = (cv2.CALIB_RATIONAL_MODEL)
(ret, camera_matrix, distortion_coefficients,
rotation_vectors, translation_vectors,
stdDeviationsIntrinsics, stdDeviationsExtrinsics,
perViewErrors) = cv2.aruco.calibrateCameraCharucoExtended(
charucoCorners=allCorners,
charucoIds=allIds,
board=self.board,
imageSize=imsize,
cameraMatrix=cameraMatrixInit,
distCoeffs=distCoeffsInit,
flags=flags,
criteria=(cv2.TERM_CRITERIA_EPS & cv2.TERM_CRITERIA_COUNT, 50000, 1e-9))
if self.traceLevel == 3 or self.traceLevel == 10:
print('Per View Errors...')
print(perViewErrors)
# check if there are any suspicious corners with high reprojection error
corners_removed, filtered_ids, filtered_corners = self.filter_corner_outliers(allIds, allCorners, camera_matrix, distortion_coefficients, rotation_vectors, translation_vectors)
if corners_removed:
# recompute the calibration if we removed any offending points
print("recomputing intrinsics")
(ret, camera_matrix, distortion_coefficients,
rotation_vectors, translation_vectors,
stdDeviationsIntrinsics, stdDeviationsExtrinsics,
perViewErrors) = cv2.aruco.calibrateCameraCharucoExtended(
charucoCorners=filtered_corners,
charucoIds=filtered_ids,
board=self.board,
imageSize=imsize,
cameraMatrix=cameraMatrixInit,
distCoeffs=distCoeffsInit,
flags=flags,
criteria=(cv2.TERM_CRITERIA_EPS & cv2.TERM_CRITERIA_COUNT, 50000, 1e-9))
return ret, camera_matrix, distortion_coefficients, rotation_vectors, translation_vectors, filtered_ids, filtered_corners
def calibrate_fisheye(self, allCorners, allIds, imsize, hfov):
one_pts = self.board.chessboardCorners
obj_points = []
for i in range(len(allIds)):
obj_points.append(self.charuco_ids_to_objpoints(allIds[i]))
f_init = imsize[0]/np.deg2rad(hfov)*1.15
cameraMatrixInit = np.array([[f_init, 0. , imsize[0]/2],
[0. , f_init, imsize[1]/2],
[0. , 0. , 1. ]])
print("Camera Matrix initialization.............")
print(cameraMatrixInit)
flags = 0
flags |= cv2.fisheye.CALIB_CHECK_COND
flags |= cv2.fisheye.CALIB_USE_INTRINSIC_GUESS
flags |= cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC
flags |= cv2.fisheye.CALIB_FIX_SKEW
distCoeffsInit = np.zeros((4,1))
# distCoeffsInit = np.array([
# -0.028964687138795853,
# 0.012780099175870419,
# -0.010693552903831005,
# 0.0013224288122728467
# ])
term_criteria = (cv2.TERM_CRITERIA_COUNT +
cv2.TERM_CRITERIA_EPS, 30, 1e-9)
try:
res, K, d, rvecs, tvecs = cv2.fisheye.calibrate(obj_points, allCorners, None, cameraMatrixInit, distCoeffsInit, flags=flags, criteria=term_criteria)
except:
# calibration failed for full FOV, let's try to limit the corners to smaller part of FOV first to find initial parameters
success = False
crop = 0.95
while not success:
print(f"trying crop factor {crop}")
obj_points_limited = []
corners_limited = []
for obj_pts, corners in zip(obj_points, allCorners):
obj_points_tmp = []
corners_tmp = []
for obj_pt, corner in zip(obj_pts, corners):
check_x = corner[0,0] > imsize[0]*(1-crop) and corner[0,0] < imsize[0]*crop
check_y = corner[0,1] > imsize[1]*(1-crop) and corner[0,1] < imsize[1]*crop
if check_x and check_y:
obj_points_tmp.append(obj_pt)
corners_tmp.append(corner)
obj_points_limited.append(np.array(obj_points_tmp))
corners_limited.append(np.array(corners_tmp))
try:
res, K, d, rvecs, tvecs = cv2.fisheye.calibrate(obj_points_limited, corners_limited, None, cameraMatrixInit, distCoeffsInit, flags=flags, criteria=term_criteria)
print(f"success with crop factor {crop}")
success = True
break
except:
print(f"failed with crop factor {crop}")
if crop > 0.7:
crop -= 0.05
else:
raise Exception("Calibration failed: Tried maximum crop factor and still no success")
if success:
# trying the full FOV once more with better initial K
print(f"new K init {K}")
print(f"new d_init {d}")
try:
res, K, d, rvecs, tvecs = cv2.fisheye.calibrate(obj_points, allCorners, imsize, K, distCoeffsInit, flags=flags, criteria=term_criteria)
except:
print(f"Failed the full res calib, using calibration with crop factor {crop}")
# check if there are any suspicious corners with high reprojection error
corners_removed, filtered_ids, filtered_corners = self.filter_corner_outliers(allIds, allCorners, K, d, rvecs, tvecs)
if corners_removed:
# recompute the calibration if we removed any offending points
obj_points = []
for i in range(len(filtered_ids)):
obj_points.append(self.charuco_ids_to_objpoints(filtered_ids[i]))
print("recomputing intrinsics")
res, K, d, rvecs, tvecs = cv2.fisheye.calibrate(obj_points, filtered_corners, None, K, d, flags=flags, criteria=term_criteria)
print(f"Updated intrinsics: {K}")
return res, K, d, rvecs, tvecs, filtered_ids, filtered_corners
def calibrate_stereo(self, allIds_l, allCorners_l, allIds_r, allCorners_r, cameraMatrix_l, distCoeff_l, cameraMatrix_r, distCoeff_r, t_in, r_in):
left_corners_sampled = []
right_corners_sampled = []
obj_pts = []
one_pts = self.board.chessboardCorners
if self.traceLevel == 2 or self.traceLevel == 4 or self.traceLevel == 10:
print('Length of allIds_l')
print(len(allIds_l))
print('Length of allIds_r')
print(len(allIds_r))
for i in range(len(allIds_l)):
left_sub_corners = []
right_sub_corners = []
obj_pts_sub = []
#if len(allIds_l[i]) < 70 or len(allIds_r[i]) < 70:
# continue
for j in range(len(allIds_l[i])):
idx = np.where(allIds_r[i] == allIds_l[i][j])
if idx[0].size == 0:
continue
left_sub_corners.append(allCorners_l[i][j])
right_sub_corners.append(allCorners_r[i][idx])
obj_pts_sub.append(one_pts[allIds_l[i][j]])
if len(left_sub_corners) > 3 and len(right_sub_corners) > 3:
obj_pts.append(np.array(obj_pts_sub, dtype=np.float32))
left_corners_sampled.append(
np.array(left_sub_corners, dtype=np.float32))
right_corners_sampled.append(
np.array(right_sub_corners, dtype=np.float32))
else:
return -1, "Stereo Calib failed due to less common features"
stereocalib_criteria = (cv2.TERM_CRITERIA_COUNT +
cv2.TERM_CRITERIA_EPS, 30, 1e-9)
if self.cameraModel == 'perspective':
flags = 0
# flags |= cv2.CALIB_USE_EXTRINSIC_GUESS
# print(flags)
flags |= cv2.CALIB_FIX_INTRINSIC
# flags |= cv2.CALIB_USE_INTRINSIC_GUESS
flags |= cv2.CALIB_RATIONAL_MODEL
# print(flags)
if self.traceLevel == 3 or self.traceLevel == 10:
print('Printing Extrinsics guesses...')
print(r_in)
print(t_in)
ret, M1, d1, M2, d2, R, T, E, F, _ = cv2.stereoCalibrateExtended(
obj_pts, left_corners_sampled, right_corners_sampled,
cameraMatrix_l, distCoeff_l, cameraMatrix_r, distCoeff_r, None,
R=r_in, T=t_in, criteria=stereocalib_criteria , flags=flags)
r_euler = Rotation.from_matrix(R).as_euler('xyz', degrees=True)
print(f'Reprojection error is {ret}')
if self.traceLevel == 3 or self.traceLevel == 10:
print('Printing Extrinsics res...')
print(R)
print(T)
print(f'Euler angles in XYZ {r_euler} degs')
R_l, R_r, P_l, P_r, Q, validPixROI1, validPixROI2 = cv2.stereoRectify(
cameraMatrix_l,
distCoeff_l,
cameraMatrix_r,
distCoeff_r,
None, R, T) # , alpha=0.1
# self.P_l = P_l
# self.P_r = P_r
r_euler = Rotation.from_matrix(R_l).as_euler('xyz', degrees=True)
if self.traceLevel == 5 or self.traceLevel == 10:
print(f'R_L Euler angles in XYZ {r_euler}')
r_euler = Rotation.from_matrix(R_r).as_euler('xyz', degrees=True)
if self.traceLevel == 5 or self.traceLevel == 10:
print(f'R_R Euler angles in XYZ {r_euler}')
# print(f'P_l is \n {P_l}')
# print(f'P_r is \n {P_r}')
return [ret, R, T, R_l, R_r, P_l, P_r]
elif self.cameraModel == 'fisheye':
# make sure all images have the same *number of* points
min_num_points = min([len(pts) for pts in obj_pts])
obj_pts_truncated = [pts[:min_num_points] for pts in obj_pts]
left_corners_truncated = [pts[:min_num_points] for pts in left_corners_sampled]
right_corners_truncated = [pts[:min_num_points] for pts in right_corners_sampled]
flags = 0
# flags |= cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC
# flags |= cv2.fisheye.CALIB_CHECK_COND
# flags |= cv2.fisheye.CALIB_FIX_SKEW
flags |= cv2.fisheye.CALIB_FIX_INTRINSIC
# flags |= cv2.fisheye.CALIB_FIX_K1
# flags |= cv2.fisheye.CALIB_FIX_K2
# flags |= cv2.fisheye.CALIB_FIX_K3
# flags |= cv2.fisheye.CALIB_FIX_K4
# flags |= cv2.CALIB_RATIONAL_MODEL
# TODO(sACHIN): Try without intrinsic guess
# flags |= cv2.CALIB_USE_INTRINSIC_GUESS
# TODO(sACHIN): Try without intrinsic guess
# flags |= cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC
# flags = cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC + cv2.fisheye.CALIB_CHECK_COND + cv2.fisheye.CALIB_FIX_SKEW
if self.traceLevel == 3 or self.traceLevel == 10:
print('Fisyeye stereo model..................')
(ret, M1, d1, M2, d2, R, T), E, F = cv2.fisheye.stereoCalibrate(
obj_pts_truncated, left_corners_truncated, right_corners_truncated,
cameraMatrix_l, distCoeff_l, cameraMatrix_r, distCoeff_r, None,
flags=flags, criteria=stereocalib_criteria), None, None
r_euler = Rotation.from_matrix(R).as_euler('xyz', degrees=True)
print(f'Reprojection error is {ret}')
if self.traceLevel == 3 or self.traceLevel == 10:
print('Printing Extrinsics res...')
print(R)
print(T)
print(f'Euler angles in XYZ {r_euler} degs')
isHorizontal = np.absolute(T[0]) > np.absolute(T[1])
R_l, R_r, P_l, P_r, Q = cv2.fisheye.stereoRectify(
cameraMatrix_l,
distCoeff_l,
cameraMatrix_r,
distCoeff_r,
None, R, T, flags=0)
r_euler = Rotation.from_matrix(R_l).as_euler('xyz', degrees=True)
if self.traceLevel == 3 or self.traceLevel == 10:
print(f'R_L Euler angles in XYZ {r_euler}')
r_euler = Rotation.from_matrix(R_r).as_euler('xyz', degrees=True)
if self.traceLevel == 3 or self.traceLevel == 10:
print(f'R_R Euler angles in XYZ {r_euler}')
return [ret, R, T, R_l, R_r, P_l, P_r]
def display_rectification(self, image_data_pairs, images_corners_l, images_corners_r, image_epipolar_color, isHorizontal):
print(
"Displaying Stereo Pair for visual inspection. Press the [ESC] key to exit.")
for idx, image_data_pair in enumerate(image_data_pairs):
if isHorizontal:
img_concat = cv2.hconcat(
[image_data_pair[0], image_data_pair[1]])
for left_pt, right_pt, colorMode in zip(images_corners_l[idx], images_corners_r[idx], image_epipolar_color[idx]):
cv2.line(img_concat,
(int(left_pt[0][0]), int(left_pt[0][1])), (int(right_pt[0][0]) + image_data_pair[0].shape[1], int(right_pt[0][1])),
colors[colorMode], 1)
else:
img_concat = cv2.vconcat(
[image_data_pair[0], image_data_pair[1]])
for left_pt, right_pt, colorMode in zip(images_corners_l[idx], images_corners_r[idx], image_epipolar_color[idx]):
cv2.line(img_concat,
(int(left_pt[0][0]), int(left_pt[0][1])), (int(right_pt[0][0]), int(right_pt[0][1]) + image_data_pair[0].shape[0]),
colors[colorMode], 1)
img_concat = cv2.resize(
img_concat, (0, 0), fx=0.8, fy=0.8)
# show image
#cv2.imshow('Stereo Pair', img_concat)
k = cv2.waitKey(0)
if k == 27: # Esc key to stop
break
# os._exit(0)
# raise SystemExit()
cv2.destroyWindow('Stereo Pair')
def scale_image(self, img, scaled_res):
expected_height = img.shape[0]*(scaled_res[1]/img.shape[1])
if self.traceLevel == 2 or self.traceLevel == 10:
print("Expected Height: {}".format(expected_height))
if not (img.shape[0] == scaled_res[0] and img.shape[1] == scaled_res[1]):
if int(expected_height) == scaled_res[0]:
# resizing to have both stereo and rgb to have same
# resolution to capture extrinsics of the rgb-right camera
img = cv2.resize(img, (scaled_res[1], scaled_res[0]),
interpolation=cv2.INTER_CUBIC)
return img
else:
# resizing and cropping to have both stereo and rgb to have same resolution
# to calculate extrinsics of the rgb-right camera
scale_width = scaled_res[1]/img.shape[1]
dest_res = (
int(img.shape[1] * scale_width), int(img.shape[0] * scale_width))
img = cv2.resize(
img, dest_res, interpolation=cv2.INTER_CUBIC)
if img.shape[0] < scaled_res[0]:
raise RuntimeError("resizeed height of rgb is smaller than required. {0} < {1}".format(
img.shape[0], scaled_res[0]))
# print(gray.shape[0] - req_resolution[0])
del_height = (img.shape[0] - scaled_res[0]) // 2
# gray = gray[: req_resolution[0], :]
img = img[del_height: del_height + scaled_res[0], :]
return img
else:
return img
def sgdEpipolar(self, images_left, images_right, M_lp, d_l, M_rp, d_r, r_l, r_r, kScaledL, kScaledR, scaled_res, isHorizontal):
if self.cameraModel == 'perspective':
mapx_l, mapy_l = cv2.initUndistortRectifyMap(
M_lp, d_l, r_l, kScaledL, scaled_res[::-1], cv2.CV_32FC1)
mapx_r, mapy_r = cv2.initUndistortRectifyMap(
M_rp, d_r, r_r, kScaledR, scaled_res[::-1], cv2.CV_32FC1)
else:
mapx_l, mapy_l = cv2.fisheye.initUndistortRectifyMap(
M_lp, d_l, r_l, kScaledL, scaled_res[::-1], cv2.CV_32FC1)
mapx_r, mapy_r = cv2.fisheye.initUndistortRectifyMap(
M_rp, d_r, r_r, kScaledR, scaled_res[::-1], cv2.CV_32FC1)
image_data_pairs = []
imagesCount = 0
for image_left, image_right in zip(images_left, images_right):
# read images
imagesCount += 1
# print(imagesCount)
img_l = cv2.imread(image_left, 0)
img_r = cv2.imread(image_right, 0)
img_l = self.scale_image(img_l, scaled_res)
img_r = self.scale_image(img_r, scaled_res)
# warp right image
# img_l = cv2.warpPerspective(img_l, self.H1, img_l.shape[::-1],
# cv2.INTER_CUBIC +
# cv2.WARP_FILL_OUTLIERS +
# cv2.WARP_INVERSE_MAP)
# img_r = cv2.warpPerspective(img_r, self.H2, img_r.shape[::-1],
# cv2.INTER_CUBIC +
# cv2.WARP_FILL_OUTLIERS +
# cv2.WARP_INVERSE_MAP)
img_l = cv2.remap(img_l, mapx_l, mapy_l, cv2.INTER_LINEAR)
img_r = cv2.remap(img_r, mapx_r, mapy_r, cv2.INTER_LINEAR)
image_data_pairs.append((img_l, img_r))
imgpoints_r = []
imgpoints_l = []
criteria = (cv2.TERM_CRITERIA_EPS +
cv2.TERM_CRITERIA_MAX_ITER, 10000, 0.00001)
for i, image_data_pair in enumerate(image_data_pairs):
res2_l = self.detect_charuco_board(image_data_pair[0])
res2_r = self.detect_charuco_board(image_data_pair[1])
if res2_l[1] is not None and res2_r[2] is not None and len(res2_l[1]) > 3 and len(res2_r[1]) > 3:
cv2.cornerSubPix(image_data_pair[0], res2_l[1],
winSize=(5, 5),
zeroZone=(-1, -1),
criteria=criteria)
cv2.cornerSubPix(image_data_pair[1], res2_r[1],
winSize=(5, 5),
zeroZone=(-1, -1),
criteria=criteria)
# termination criteria
img_pth_right = Path(images_right[i])
img_pth_left = Path(images_left[i])
org = (100, 50)
# #cv2.imshow('ltext', lText)
# cv2.waitKey(0)
localError = 0
corners_l = []
corners_r = []
for j in range(len(res2_l[2])):
idx = np.where(res2_r[2] == res2_l[2][j])
if idx[0].size == 0:
continue
corners_l.append(res2_l[1][j])
corners_r.append(res2_r[1][idx])
imgpoints_l.extend(corners_l)
imgpoints_r.extend(corners_r)
epi_error_sum = 0
for l_pt, r_pt in zip(corners_l, corners_r):
if isHorizontal:
epi_error_sum += abs(l_pt[0][1] - r_pt[0][1])
else:
epi_error_sum += abs(l_pt[0][0] - r_pt[0][0])
# localError = epi_error_sum / len(corners_l)
# print("Average Epipolar in test Error per image on host in " + img_pth_right.name + " : " +
# str(localError))
else:
print('Numer of corners is in left -> {} and right -> {}'.format(
len(marker_corners_l), len(marker_corners_r)))
raise SystemExit(1)
epi_error_sum = 0
for l_pt, r_pt in zip(imgpoints_l, imgpoints_r):
if isHorizontal:
epi_error_sum += abs(l_pt[0][1] - r_pt[0][1])
else:
epi_error_sum += abs(l_pt[0][0] - r_pt[0][0])
avg_epipolar = epi_error_sum / len(imgpoints_r)
print("Average Epipolar Error in test is : " + str(avg_epipolar))
return avg_epipolar
def test_epipolar_charuco(self, left_img_pth, right_img_pth, M_l, d_l, M_r, d_r, t, r_l, r_r):
images_left = glob.glob(left_img_pth + '/*.png')
images_right = glob.glob(right_img_pth + '/*.png')
images_left.sort()
images_right.sort()
assert len(images_left) != 0, "ERROR: Images not read correctly"
assert len(images_right) != 0, "ERROR: Images not read correctly"
isHorizontal = np.absolute(t[0]) > np.absolute(t[1])
scale = None
scale_req = False
frame_left_shape = cv2.imread(images_left[0], 0).shape
frame_right_shape = cv2.imread(images_right[0], 0).shape
scalable_res = frame_left_shape
scaled_res = frame_right_shape
if frame_right_shape[0] < frame_left_shape[0] and frame_right_shape[1] < frame_left_shape[1]:
scale_req = True
scale = frame_right_shape[1] / frame_left_shape[1]
elif frame_right_shape[0] > frame_left_shape[0] and frame_right_shape[1] > frame_left_shape[1]:
scale_req = True
scale = frame_left_shape[1] / frame_right_shape[1]
scalable_res = frame_right_shape
scaled_res = frame_left_shape
if scale_req:
scaled_height = scale * scalable_res[0]
diff = scaled_height - scaled_res[0]
if diff < 0:
scaled_res = (int(scaled_height), scaled_res[1])
if self.traceLevel == 3 or self.traceLevel == 10:
print(
f'Is scale Req: {scale_req}\n scale value: {scale} \n scalable Res: {scalable_res} \n scale Res: {scaled_res}')
print("Original res Left :{}".format(frame_left_shape))
print("Original res Right :{}".format(frame_right_shape))
# print("Scale res :{}".format(scaled_res))
M_lp = self.scale_intrinsics(M_l, frame_left_shape, scaled_res)
M_rp = self.scale_intrinsics(M_r, frame_right_shape, scaled_res)
criteria = (cv2.TERM_CRITERIA_EPS +
cv2.TERM_CRITERIA_MAX_ITER, 10000, 0.00001)
# TODO(Sachin): Observe Images by adding visualization