aruco testing

This commit is contained in:
2024-08-18 06:11:20 -04:00
parent 4c75d2f56e
commit 11f715c7e2
17 changed files with 16193 additions and 188061 deletions

View File

@@ -1,20 +1,29 @@
import cv2
import numpy as np
from Picam2Vid import Picam2Vid
import time
stream = Picam2Vid((1536, 864))
tag36h11 = cv2.aruco.DICT_APRILTAG_36h11
params = cv2.aruco.DetectorParameters_create()
dictionary = cv2.aruco.Dictionary_get(tag36h11)
while True:
stream = Picam2Vid()
start=time.time()
stream.update()
frame = cv2.imread(stream.read())
frame = stream.read()
grey = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
cv2.imshow('frame', frame)
cv2.waitKey(0)
cv2.waitKey(1)
tag36h11 = cv2.aruco.DICT_APRILTAG_36h11
params = cv2.aruco.DetectorParameters_create()
(corners, ids, rejcted) = cv2.aruco.detectMarkers(frame, tag36h11, parameters=params)
print(corners)
print(ids)
(corners, ids, rejected) = cv2.aruco.detectMarkers(grey, dictionary, parameters=params)
#print(corners)
print("ids: " + str(ids))
#print(rejected)
print("FPS: "+str(1/(time.time()-start)))

View File

@@ -24,7 +24,7 @@ class Picam2Vid:
self.camera.stop()
return
self.frame=self.camera.capture_array('main')
print(self.frame.dtype)
#print(self.frame.dtype)
#print("debug threading")
def read(self):

View File

@@ -13,14 +13,14 @@ dist = np.array([[-0.04790604, 0.08489533, -0.00387366, 0.00616192, -0.0387539
detector = dt_apriltags.Detector(searchpath=['apriltags'],
families='tag36h11',
nthreads=2,
quad_decimate=8.5,
quad_sigma=0.5,
quad_decimate=2,
quad_sigma=1,
refine_edges=3,
decode_sharpening=0,
decode_sharpening=0.25,
debug=1)
#image = cv2.imread("/home/tyler/Desktop/FRC-Apriltag-Pose-Detection/FRC_Fiducial_Tracking/Static_Tag_Pics/apriltagrobots_overlay.jpg")
image = cv2.imread("/home/tyler/Desktop/FRC-Apriltag-Pose-Detection/FRC_Fiducial_Tracking/Static_Tag_Pics/13.jpg")
image = cv2.imread("/home/tyler/Desktop/FRC-Apriltag-Pose-Detection/FRC_Fiducial_Tracking/Static_Tag_Pics/14.jpg")
#image = cv2.imread("/home/tyler/Desktop/FRC-Apriltag-Pose-Detection/20240814_043333.jpg")
#h, w = image.shape[:2]
@@ -34,12 +34,13 @@ image = cv2.imread("/home/tyler/Desktop/FRC-Apriltag-Pose-Detection/FRC_Fiducial
#dst = dst[y:y+h, x:x+w]
grey = cv2.cvtColor(image, cv2.COLOR_BGR2GRAY)
smaller = cv2.resize(grey, (640, 360))
print(grey)
print(smaller)
cv2.imshow("frame", grey)
cv2.imshow("frame", smaller)
cv2.waitKey(0)
output = detector.detect(grey, estimate_tag_pose=False, camera_params=None, tag_size=None)
output = detector.detect(smaller, estimate_tag_pose=False, camera_params=None, tag_size=None)
print(output)

Binary file not shown.

Before

Width:  |  Height:  |  Size: 724 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 603 KiB