Note
This notebook can be downloaded here: aruco_calibration_rotation.ipynb
Camera calibration using CHARUCO¶
import numpy as np
import cv2, PIL, os
from cv2 import aruco
from mpl_toolkits.mplot3d import Axes3D
import matplotlib.pyplot as plt
import matplotlib as mpl
import pandas as pd
%matplotlib nbagg
2. Camera pose estimation using CHARUCO chessboard¶
First, let’s create the board.
workdir = "./workdir/"
aruco_dict = aruco.Dictionary_get(aruco.DICT_6X6_250)
board = aruco.CharucoBoard_create(7, 5, 1, .8, aruco_dict)
imboard = board.draw((2000, 2000))
cv2.imwrite(workdir + "chessboard.tiff", imboard)
fig = plt.figure()
ax = fig.add_subplot(1,1,1)
plt.imshow(imboard, cmap = mpl.cm.gray, interpolation = "nearest")
ax.axis("off")
plt.show()
<IPython.core.display.Javascript object>
And take photos of it from multiple angles, for example:
datadir = "../../data/calib_tel_ludo/"
images = np.array([datadir + f for f in os.listdir(datadir) if f.endswith(".png") ])
order = np.argsort([int(p.split(".")[-2].split("_")[-1]) for p in images])
images = images[order]
images
array(['../../data/calib_tel_ludo/VID_20180406_085421_0.png',
'../../data/calib_tel_ludo/VID_20180406_085421_5.png',
'../../data/calib_tel_ludo/VID_20180406_085421_10.png',
'../../data/calib_tel_ludo/VID_20180406_085421_15.png',
'../../data/calib_tel_ludo/VID_20180406_085421_20.png',
'../../data/calib_tel_ludo/VID_20180406_085421_25.png',
'../../data/calib_tel_ludo/VID_20180406_085421_30.png',
'../../data/calib_tel_ludo/VID_20180406_085421_35.png',
'../../data/calib_tel_ludo/VID_20180406_085421_40.png',
'../../data/calib_tel_ludo/VID_20180406_085421_45.png',
'../../data/calib_tel_ludo/VID_20180406_085421_50.png',
'../../data/calib_tel_ludo/VID_20180406_085421_55.png',
'../../data/calib_tel_ludo/VID_20180406_085421_60.png',
'../../data/calib_tel_ludo/VID_20180406_085421_65.png',
'../../data/calib_tel_ludo/VID_20180406_085421_70.png',
'../../data/calib_tel_ludo/VID_20180406_085421_75.png',
'../../data/calib_tel_ludo/VID_20180406_085421_80.png',
'../../data/calib_tel_ludo/VID_20180406_085421_85.png',
'../../data/calib_tel_ludo/VID_20180406_085421_90.png',
'../../data/calib_tel_ludo/VID_20180406_085421_95.png',
'../../data/calib_tel_ludo/VID_20180406_085421_100.png',
'../../data/calib_tel_ludo/VID_20180406_085421_105.png',
'../../data/calib_tel_ludo/VID_20180406_085421_110.png',
'../../data/calib_tel_ludo/VID_20180406_085421_115.png',
'../../data/calib_tel_ludo/VID_20180406_085421_120.png',
'../../data/calib_tel_ludo/VID_20180406_085421_125.png',
'../../data/calib_tel_ludo/VID_20180406_085421_130.png',
'../../data/calib_tel_ludo/VID_20180406_085421_135.png',
'../../data/calib_tel_ludo/VID_20180406_085421_140.png',
'../../data/calib_tel_ludo/VID_20180406_085421_145.png',
'../../data/calib_tel_ludo/VID_20180406_085421_150.png',
'../../data/calib_tel_ludo/VID_20180406_085421_155.png',
'../../data/calib_tel_ludo/VID_20180406_085421_160.png',
'../../data/calib_tel_ludo/VID_20180406_085421_165.png',
'../../data/calib_tel_ludo/VID_20180406_085421_170.png',
'../../data/calib_tel_ludo/VID_20180406_085421_175.png',
'../../data/calib_tel_ludo/VID_20180406_085421_180.png',
'../../data/calib_tel_ludo/VID_20180406_085421_185.png',
'../../data/calib_tel_ludo/VID_20180406_085421_190.png',
'../../data/calib_tel_ludo/VID_20180406_085421_195.png',
'../../data/calib_tel_ludo/VID_20180406_085421_200.png',
'../../data/calib_tel_ludo/VID_20180406_085421_205.png',
'../../data/calib_tel_ludo/VID_20180406_085421_210.png',
'../../data/calib_tel_ludo/VID_20180406_085421_215.png',
'../../data/calib_tel_ludo/VID_20180406_085421_220.png',
'../../data/calib_tel_ludo/VID_20180406_085421_225.png',
'../../data/calib_tel_ludo/VID_20180406_085421_230.png',
'../../data/calib_tel_ludo/VID_20180406_085421_235.png',
'../../data/calib_tel_ludo/VID_20180406_085421_240.png',
'../../data/calib_tel_ludo/VID_20180406_085421_245.png',
'../../data/calib_tel_ludo/VID_20180406_085421_250.png',
'../../data/calib_tel_ludo/VID_20180406_085421_255.png',
'../../data/calib_tel_ludo/VID_20180406_085421_260.png',
'../../data/calib_tel_ludo/VID_20180406_085421_265.png',
'../../data/calib_tel_ludo/VID_20180406_085421_270.png',
'../../data/calib_tel_ludo/VID_20180406_085421_275.png',
'../../data/calib_tel_ludo/VID_20180406_085421_280.png',
'../../data/calib_tel_ludo/VID_20180406_085421_285.png',
'../../data/calib_tel_ludo/VID_20180406_085421_290.png',
'../../data/calib_tel_ludo/VID_20180406_085421_295.png',
'../../data/calib_tel_ludo/VID_20180406_085421_300.png'],
dtype='<U53')
im = PIL.Image.open(images[0])
fig = plt.figure()
ax = fig.add_subplot(1,1,1)
plt.imshow(im)
#ax.axis('off')
plt.show()
<IPython.core.display.Javascript object>
Now, the camera calibration can be done using all the images of the chessboard. Two functions are necessary:
- The first will detect markers on all the images and.
- The second will proceed the detected markers to estimage the camera calibration data.
def read_chessboards(images):
"""
Charuco base pose estimation.
"""
print("POSE ESTIMATION STARTS:")
allCorners = []
allIds = []
decimator = 0
# SUB PIXEL CORNER DETECTION CRITERION
criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 100, 0.00001)
for im in images:
print("=> Processing image {0}".format(im))
frame = cv2.imread(im)
gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
corners, ids, rejectedImgPoints = cv2.aruco.detectMarkers(gray, aruco_dict)
if len(corners)>0:
# SUB PIXEL DETECTION
for corner in corners:
cv2.cornerSubPix(gray, corner,
winSize = (3,3),
zeroZone = (-1,-1),
criteria = criteria)
res2 = cv2.aruco.interpolateCornersCharuco(corners,ids,gray,board)
if res2[1] is not None and res2[2] is not None and len(res2[1])>3 and decimator%1==0:
allCorners.append(res2[1])
allIds.append(res2[2])
decimator+=1
imsize = gray.shape
return allCorners,allIds,imsize
allCorners,allIds,imsize=read_chessboards(images)
POSE ESTIMATION STARTS:
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_0.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_5.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_10.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_15.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_20.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_25.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_30.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_35.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_40.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_45.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_50.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_55.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_60.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_65.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_70.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_75.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_80.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_85.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_90.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_95.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_100.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_105.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_110.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_115.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_120.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_125.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_130.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_135.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_140.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_145.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_150.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_155.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_160.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_165.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_170.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_175.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_180.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_185.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_190.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_195.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_200.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_205.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_210.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_215.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_220.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_225.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_230.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_235.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_240.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_245.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_250.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_255.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_260.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_265.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_270.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_275.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_280.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_285.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_290.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_295.png
=> Processing image ../../data/calib_tel_ludo/VID_20180406_085421_300.png
def calibrate_camera(allCorners,allIds,imsize):
"""
Calibrates the camera using the dected corners.
"""
print("CAMERA CALIBRATION")
cameraMatrixInit = np.array([[ 1000., 0., imsize[0]/2.],
[ 0., 1000., imsize[1]/2.],
[ 0., 0., 1.]])
distCoeffsInit = np.zeros((5,1))
flags = (cv2.CALIB_USE_INTRINSIC_GUESS + cv2.CALIB_RATIONAL_MODEL + cv2.CALIB_FIX_ASPECT_RATIO)
#flags = (cv2.CALIB_RATIONAL_MODEL)
(ret, camera_matrix, distortion_coefficients0,
rotation_vectors, translation_vectors,
stdDeviationsIntrinsics, stdDeviationsExtrinsics,
perViewErrors) = cv2.aruco.calibrateCameraCharucoExtended(
charucoCorners=allCorners,
charucoIds=allIds,
board=board,
imageSize=imsize,
cameraMatrix=cameraMatrixInit,
distCoeffs=distCoeffsInit,
flags=flags,
criteria=(cv2.TERM_CRITERIA_EPS & cv2.TERM_CRITERIA_COUNT, 10000, 1e-9))
return ret, camera_matrix, distortion_coefficients0, rotation_vectors, translation_vectors
%time ret, mtx, dist, rvecs, tvecs = calibrate_camera(allCorners,allIds,imsize)
CAMERA CALIBRATION
CPU times: user 10.3 s, sys: 8.89 s, total: 19.2 s
Wall time: 5.26 s
ret
0.6363938527748627
mtx
array([[1.78952655e+03, 0.00000000e+00, 9.69572430e+02],
[0.00000000e+00, 1.78952655e+03, 5.64872516e+02],
[0.00000000e+00, 0.00000000e+00, 1.00000000e+00]])
dist
array([[ 5.33659854e+00],
[-1.67904382e+02],
[ 3.32943561e-03],
[-4.67385863e-03],
[ 9.75622127e+02],
[ 5.14691206e+00],
[-1.66105367e+02],
[ 9.69643912e+02],
[ 0.00000000e+00],
[ 0.00000000e+00],
[ 0.00000000e+00],
[ 0.00000000e+00],
[ 0.00000000e+00],
[ 0.00000000e+00]])
Check calibration results¶
i=20 # select image id
plt.figure()
frame = cv2.imread(images[i])
img_undist = cv2.undistort(frame,mtx,dist,None)
plt.subplot(1,2,1)
plt.imshow(frame)
plt.title("Raw image")
plt.axis("off")
plt.subplot(1,2,2)
plt.imshow(img_undist)
plt.title("Corrected image")
plt.axis("off")
plt.show()
<IPython.core.display.Javascript object>
3 . Use of camera calibration to estimate 3D translation and rotation of each marker on a scene¶
frame = cv2.imread("../../data/IMG_20180406_095219.jpg")
#frame = cv2.undistort(src = frame, cameraMatrix = mtx, distCoeffs = dist)
plt.figure()
plt.imshow(frame, interpolation = "nearest")
plt.show()
<IPython.core.display.Javascript object>
Post processing¶
gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
aruco_dict = aruco.Dictionary_get(aruco.DICT_6X6_250)
parameters = aruco.DetectorParameters_create()
corners, ids, rejectedImgPoints = aruco.detectMarkers(gray, aruco_dict,
parameters=parameters)
# SUB PIXEL DETECTION
criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 100, 0.0001)
for corner in corners:
cv2.cornerSubPix(gray, corner, winSize = (3,3), zeroZone = (-1,-1), criteria = criteria)
frame_markers = aruco.drawDetectedMarkers(frame.copy(), corners, ids)
corners
[array([[[1211. , 1744. ],
[1002. , 1678. ],
[1095. , 1553. ],
[1298.5002, 1611.7025]]], dtype=float32),
array([[[1067.8948, 1503.2638],
[ 880. , 1447. ],
[ 971.8308, 1339.5516],
[1155.9335, 1390.4458]]], dtype=float32),
array([[[1589., 2408.],
[1330., 2308.],
[1423., 2120.],
[1671., 2208.]]], dtype=float32),
array([[[2033., 2261.],
[1772., 2174.],
[1835., 2005.],
[2083., 2083.]]], dtype=float32),
array([[[ 935., 2158.],
[ 706., 2076.],
[ 827., 1911.],
[1046., 1986.]]], dtype=float32),
array([[[1378., 2036.],
[1153., 1957.],
[1245., 1810.],
[1460., 1882.]]], dtype=float32),
array([[[ 348., 1942.],
[ 144., 1867.],
[ 291., 1725.],
[ 484., 1792.]]], dtype=float32),
array([[[1782., 1928.],
[1556., 1853.],
[1624., 1717.],
[1839., 1783.]]], dtype=float32),
array([[[ 798., 1837.],
[ 597., 1770.],
[ 713., 1637.],
[ 906., 1700.]]], dtype=float32),
array([[[2154., 1823.],
[1930., 1755.],
[1977., 1630.],
[2188., 1691.]]], dtype=float32),
array([[[1580., 1650.],
[1381., 1590.],
[1449., 1482.],
[1641., 1535.]]], dtype=float32),
array([[[ 273., 1658.],
[ 98., 1592.],
[ 231., 1478.],
[ 403., 1539.]]], dtype=float32),
array([[[ 688., 1574.],
[ 509., 1517.],
[ 617., 1412.],
[ 790., 1465.]]], dtype=float32),
array([[[1415.4037, 1431.0923],
[1225.0386, 1377.4968],
[1300.2623, 1279.6166],
[1483.125 , 1329.8298]]], dtype=float32),
array([[[ 597.94867, 1363.2643 ],
[ 421.2595 , 1307.9504 ],
[ 535.3967 , 1211.2885 ],
[ 704.76355, 1262.5137 ]]], dtype=float32),
array([[[ 949.5966, 1301.637 ],
[ 775.0423, 1250.5741],
[ 867.6455, 1160.6498],
[1035.8293, 1207.2653]]], dtype=float32),
array([[[1929.4287, 1575.4489],
[1717.393 , 1515.709 ],
[1772.9988, 1407.4595],
[1975.8889, 1461.9364]]], dtype=float32)]
Very fast processing !
Results¶
plt.figure()
plt.imshow(frame_markers, interpolation = "nearest")
plt.show()
<IPython.core.display.Javascript object>
Add local axis on each marker¶
size_of_marker = 0.0285 # side lenght of the marker in meter
rvecs,tvecs = aruco.estimatePoseSingleMarkers(corners, size_of_marker , mtx, dist)
length_of_axis = 0.1
imaxis = aruco.drawDetectedMarkers(frame.copy(), corners, ids)
for i in range(len(tvecs)):
imaxis = aruco.drawAxis(imaxis, mtx, dist, rvecs[i], tvecs[i], length_of_axis)
plt.figure()
plt.imshow(imaxis)
plt.grid()
plt.show()
<IPython.core.display.Javascript object>
data = pd.DataFrame(data = tvecs.reshape(len(tvecs),3), columns = ["tx", "ty", "tz"],
index = ids.flatten())
data.index.name = "marker"
data.sort_index(inplace= True)
data
tx | ty | tz | |
---|---|---|---|
marker | |||
0 | 0.058386 | 0.185638 | 0.196745 |
1 | -0.010302 | 0.166097 | 0.203390 |
2 | -0.080577 | 0.156345 | 0.221786 |
3 | 0.116058 | 0.189125 | 0.216976 |
4 | 0.041465 | 0.165729 | 0.219531 |
5 | -0.027355 | 0.148248 | 0.227437 |
6 | -0.100679 | 0.140372 | 0.251642 |
7 | 0.097155 | 0.166912 | 0.238803 |
8 | 0.023141 | 0.137494 | 0.228381 |
9 | -0.044928 | 0.130699 | 0.253189 |
10 | 0.163007 | 0.172988 | 0.267740 |
11 | 0.078322 | 0.144059 | 0.258836 |
12 | 0.006806 | 0.117907 | 0.247738 |
13 | -0.057502 | 0.102385 | 0.255066 |
14 | 0.130086 | 0.136805 | 0.265516 |
15 | 0.056305 | 0.114980 | 0.261572 |
16 | -0.009219 | 0.097941 | 0.264597 |
datar = pd.DataFrame(data = tvecs.reshape(len(rvecs),3), columns = ["rx", "ry", "rz"],
index = ids.flatten())
datar.index.name = "marker"
datar.sort_index(inplace= True)
np.degrees(datar)
rx | ry | rz | |
---|---|---|---|
marker | |||
0 | 3.345263 | 10.636263 | 11.272638 |
1 | -0.590286 | 9.516639 | 11.653392 |
2 | -4.616715 | 8.957911 | 12.707418 |
3 | 6.649625 | 10.836080 | 12.431815 |
4 | 2.375792 | 9.495585 | 12.578208 |
5 | -1.567306 | 8.493977 | 13.031201 |
6 | -5.768467 | 8.042731 | 14.418019 |
7 | 5.566548 | 9.563349 | 13.682404 |
8 | 1.325893 | 7.877812 | 13.085270 |
9 | -2.574157 | 7.488515 | 14.506650 |
10 | 9.339589 | 9.911505 | 15.340350 |
11 | 4.487517 | 8.253984 | 14.830232 |
12 | 0.389962 | 6.755597 | 14.194362 |
13 | -3.294606 | 5.866220 | 14.614201 |
14 | 7.453402 | 7.838356 | 15.212937 |
15 | 3.226061 | 6.587856 | 14.986982 |
16 | -0.528237 | 5.611610 | 15.160290 |
v = data.loc[3:6].values
((v[1:] - v[:-1])**2).sum(axis = 1)**.5
array([0.07821726, 0.07144442, 0.07761642])
cv2.Rodrigues(rvecs[0], np.zeros((3,3)))
(array([[-0.86801078, -0.49450269, -0.04499303],
[ 0.02324173, 0.05005109, -0.99847619],
[ 0.49600111, -0.86773382, -0.03195179]]),
array([[ 0.17008214, -0.35187266, 0.58606527, -0.60094699, -0.15414543,
-0.02171528, 0.32580607, 0.19163346, -0.14667908],
[ 0.2919512 , -0.48377297, -0.31537661, 0.54686264, -0.3578951 ,
-0.00521095, 0.48529479, 0.25504826, 0.60693805],
[-0.27940432, 0.44000776, 0.55432899, -0.27008959, -0.61042134,
-0.03688581, -0.47630662, -0.28596013, 0.37208124]]))
fig = plt.figure()
#ax = fig.add_subplot(111, projection='3d')
ax = fig.add_subplot(1,2,1)
ax.set_aspect("equal")
plt.plot(data.tx, data.ty, "or-")
plt.grid()
ax = fig.add_subplot(1,2,2)
plt.imshow(imaxis, origin = "upper")
plt.plot(np.array(corners)[:, 0, 0,0], np.array(corners)[:, 0, 0,1], "or")
plt.show()
<IPython.core.display.Javascript object>
a = np.arange(50)
a
array([ 0, 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])
import pickle
f = open("truc.pckl", "wb")
pickle.dump(a, f)
f.close()
f = open("truc.pckl", "rb")
b = pickle.load(f)
b == a
array([ True, True, True, True, True, True, True, True, True,
True, True, True, True, True, True, True, True, True,
True, True, True, True, True, True, True, True, True,
True, True, True, True, True, True, True, True, True,
True, True, True, True, True, True, True, True, True,
True, True, True, True, True], dtype=bool)
corners = np.array(corners)
data2 = pd.DataFrame({"px": corners[:, 0, 0, 1],
"py": corners[:, 0, 0, 0]}, index = ids.flatten())
data2.sort_index(inplace=True)
data2
px | py | |
---|---|---|
0 | 177.324295 | 222.723907 |
1 | 174.117722 | 448.426971 |
5 | 165.167435 | 1385.455933 |
6 | 292.872223 | 348.533112 |
7 | 290.211761 | 572.901550 |
8 | 286.861359 | 800.593140 |
9 | 285.043823 | 1029.405640 |
10 | 284.054932 | 1261.753418 |
11 | 406.743347 | 250.763550 |
12 | 405.577484 | 469.121307 |
13 | 402.066681 | 691.525330 |
14 | 398.973602 | 918.603577 |
16 | 397.476105 | 1371.831177 |
17 | 514.600769 | 374.230682 |
18 | 512.135010 | 590.534302 |
19 | 509.453247 | 809.594849 |
20 | 507.959595 | 1029.593262 |
21 | 507.521088 | 1253.295044 |
22 | 615.594482 | 280.054901 |
23 | 614.357056 | 490.602081 |
24 | 613.074951 | 704.512085 |
25 | 611.417297 | 922.586426 |
26 | 611.085632 | 1139.391602 |
27 | 611.036255 | 1359.634644 |
28 | 716.764465 | 397.975067 |
29 | 716.205688 | 606.338318 |
30 | 714.187927 | 817.897095 |
31 | 713.494141 | 1029.665405 |
32 | 713.155762 | 1244.999390 |
33 | 811.479309 | 305.960754 |
34 | 811.358704 | 509.836670 |
35 | 810.507996 | 716.540955 |
36 | 810.085144 | 926.713257 |
37 | 810.013611 | 1135.423462 |
38 | 810.014771 | 1347.564697 |
39 | 906.448242 | 420.143951 |
40 | 906.174988 | 621.917664 |
41 | 905.748413 | 825.513733 |
42 | 906.083923 | 1029.803955 |
43 | 906.387878 | 1237.707520 |
m0 = data2.loc[0]
m43 = data2.loc[43]
d01 = ((m0 - m43).values**2).sum()**.5
d = 42.5e-3 * (3.5**2 + 4.5**2)**.5
factor = d / d01
data2["x"] = data2.px * factor
data2["y"] = data2.py * factor
((data2[["x", "y"]].loc[11] - data2[["x", "y"]].loc[0]).values**2).sum()**.5
0.043476117957396747
c = np.array(corners).astype(np.float64).reshape(44,4,2)
(((c[:, 1:] - c[:, :-1])**2).sum(axis = 2)**.5).mean(axis =1)
array([ 138.33575835, 143.00113377, 142.012097 , 140.69699432,
146.66782406, 144.02442319, 138.67845434, 142.33812925,
143.00229095, 140.33926025, 140.35356753, 146.66786569,
139.34054504, 146.67222201, 140.03570454, 148.01939184,
143.35647769, 142.67236143, 147.01931296, 148.02127735,
137.67392157, 135.35308209, 141.00354688, 143.67946992,
137.67149733, 138.67392207, 145.00112611, 142.33454105,
138.3466791 , 143.00234925, 139.0035972 , 143.00115739,
143.6865917 , 144.67964727, 144.33446711, 141.67253496,
143.67117097, 147.67232772, 150.35663387, 141.70034559,
149.01342342, 146.01949591, 144.34013329, 150.35333222])
c
array([[[ 2406., 1940.],
[ 2546., 1940.],
[ 2545., 2075.],
[ 2405., 2076.]],
[[ 1991., 1938.],
[ 2138., 1939.],
[ 2138., 2076.],
[ 1993., 2076.]],
[[ 1584., 1936.],
[ 1728., 1936.],
[ 1731., 2073.],
[ 1586., 2072.]],
[[ 2619., 1735.],
[ 2759., 1735.],
[ 2754., 1878.],
[ 2615., 1877.]],
[[ 2198., 1734.],
[ 2347., 1734.],
[ 2346., 1878.],
[ 2199., 1878.]],
[[ 973., 1733.],
[ 1117., 1731.],
[ 1121., 1874.],
[ 976., 1875.]],
[[ 572., 1732.],
[ 710., 1732.],
[ 713., 1874.],
[ 577., 1873.]],
[[ 2410., 1533.],
[ 2554., 1533.],
[ 2552., 1672.],
[ 2408., 1672.]],
[[ 1373., 1326.],
[ 1519., 1325.],
[ 1519., 1463.],
[ 1374., 1464.]],
[[ 1785., 1326.],
[ 1926., 1324.],
[ 1927., 1463.],
[ 1786., 1463.]],
[[ 2627., 1323.],
[ 2767., 1324.],
[ 2763., 1464.],
[ 2622., 1464.]],
[[ 2200., 1324.],
[ 2350., 1324.],
[ 2349., 1463.],
[ 2198., 1463.]],
[[ 760., 1128.],
[ 901., 1127.],
[ 903., 1265.],
[ 764., 1266.]],
[[ 1988., 1123.],
[ 2138., 1121.],
[ 2138., 1261.],
[ 1988., 1262.]],
[[ 547., 920.],
[ 687., 918.],
[ 692., 1058.],
[ 552., 1059.]],
[[ 2203., 910.],
[ 2354., 908.],
[ 2351., 1050.],
[ 2200., 1052.]],
[[ 2631., 908.],
[ 2775., 906.],
[ 2771., 1050.],
[ 2629., 1050.]],
[[ 750., 708.],
[ 890., 707.],
[ 892., 855.],
[ 752., 855.]],
[[ 2419., 695.],
[ 2565., 693.],
[ 2563., 842.],
[ 2417., 845.]],
[[ 946., 494.],
[ 1093., 491.],
[ 1096., 642.],
[ 950., 643.]],
[[ 1181., 1936.],
[ 1319., 1935.],
[ 1321., 2073.],
[ 1184., 2072.]],
[[ 780., 1935.],
[ 916., 1935.],
[ 920., 2070.],
[ 785., 2070.]],
[[ 1788., 1731.],
[ 1928., 1732.],
[ 1929., 1876.],
[ 1790., 1875.]],
[[ 1378., 1731.],
[ 1521., 1730.],
[ 1524., 1873.],
[ 1379., 1874.]],
[[ 771., 1533.],
[ 909., 1533.],
[ 911., 1671.],
[ 774., 1671.]],
[[ 1176., 1533.],
[ 1315., 1532.],
[ 1317., 1669.],
[ 1177., 1670.]],
[[ 1989., 1532.],
[ 2137., 1532.],
[ 2137., 1671.],
[ 1989., 1670.]],
[[ 1581., 1531.],
[ 1726., 1531.],
[ 1727., 1669.],
[ 1583., 1669.]],
[[ 560., 1329.],
[ 700., 1328.],
[ 703., 1465.],
[ 565., 1466.]],
[[ 966., 1328.],
[ 1112., 1327.],
[ 1113., 1465.],
[ 968., 1465.]],
[[ 1169., 1127.],
[ 1309., 1126.],
[ 1310., 1264.],
[ 1171., 1265.]],
[[ 1579., 1124.],
[ 1723., 1123.],
[ 1723., 1263.],
[ 1578., 1263.]],
[[ 2415., 1120.],
[ 2560., 1119.],
[ 2556., 1261.],
[ 2412., 1261.]],
[[ 956., 919.],
[ 1103., 918.],
[ 1106., 1058.],
[ 959., 1059.]],
[[ 1367., 917.],
[ 1514., 916.],
[ 1514., 1056.],
[ 1368., 1056.]],
[[ 1784., 914.],
[ 1926., 912.],
[ 1926., 1053.],
[ 1784., 1054.]],
[[ 1160., 706.],
[ 1302., 706.],
[ 1304., 854.],
[ 1163., 854.]],
[[ 1574., 703.],
[ 1722., 702.],
[ 1722., 850.],
[ 1575., 852.]],
[[ 1991., 699.],
[ 2142., 697.],
[ 2138., 847.],
[ 1988., 848.]],
[[ 539., 499.],
[ 677., 496.],
[ 681., 644.],
[ 542., 646.]],
[[ 1360., 490.],
[ 1508., 488.],
[ 1510., 639.],
[ 1362., 641.]],
[[ 1784., 486.],
[ 1928., 483.],
[ 1926., 635.],
[ 1784., 637.]],
[[ 2637., 479.],
[ 2778., 480.],
[ 2776., 630.],
[ 2634., 629.]],
[[ 2207., 481.],
[ 2356., 478.],
[ 2356., 629.],
[ 2205., 632.]]])
help(cv2.aruco.detectMarkers)
Help on built-in function detectMarkers:
detectMarkers(...)
detectMarkers(image, dictionary[, corners[, ids[, parameters[, rejectedImgPoints]]]]) -> corners, ids, rejectedImgPoints
(480, 640, 3)