-
Notifications
You must be signed in to change notification settings - Fork 0
/
aruco_final.py
188 lines (165 loc) · 6.56 KB
/
aruco_final.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
#!/usr/bin/env python3
# Team ID:eYRC#HB#1776
# Author List:Dhanvantraj M, Vinoth B, Winston Doss, Madhusudhanan K
# Filename: aruco.py
#Theme: Hola bot
#Functions: coordinates,callback,main
################### IMPORT MODULES #######################
import socket
import time
import signal # To handle Signals by OS/user
import sys
#for coordinates fxn
import cv2
import imutils
from imutils.video import VideoStream
import math
import numpy
from cv_basics.msg import aruco_data
import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
####################### Global Variables#########################################
ARUCO_DICT = {
"DICT_4X4_50": cv2.aruco.DICT_4X4_50,
"DICT_4X4_100": cv2.aruco.DICT_4X4_100,
"DICT_4X4_250": cv2.aruco.DICT_4X4_250,
"DICT_4X4_1000": cv2.aruco.DICT_4X4_1000,
"DICT_5X5_50": cv2.aruco.DICT_5X5_50,
"DICT_5X5_100": cv2.aruco.DICT_5X5_100,
"DICT_5X5_250": cv2.aruco.DICT_5X5_250,
"DICT_5X5_1000": cv2.aruco.DICT_5X5_1000,
"DICT_6X6_50": cv2.aruco.DICT_6X6_50,
"DICT_6X6_100": cv2.aruco.DICT_6X6_100,
"DICT_6X6_250": cv2.aruco.DICT_6X6_250,
"DICT_6X6_1000": cv2.aruco.DICT_6X6_1000,
"DICT_7X7_50": cv2.aruco.DICT_7X7_50,
"DICT_7X7_100": cv2.aruco.DICT_7X7_100,
"DICT_7X7_250": cv2.aruco.DICT_7X7_250,
"DICT_7X7_1000": cv2.aruco.DICT_7X7_1000,
"DICT_ARUCO_ORIGINAL": cv2.aruco.DICT_ARUCO_ORIGINAL,
"DICT_APRILTAG_16h5": cv2.aruco.DICT_APRILTAG_16h5,
"DICT_APRILTAG_25h9": cv2.aruco.DICT_APRILTAG_25h9,
"DICT_APRILTAG_36h10": cv2.aruco.DICT_APRILTAG_36h10,
"DICT_APRILTAG_36h11": cv2.aruco.DICT_APRILTAG_36h11
}
#Initialize the video stream and allow the camera sensor to warm up
rospy.loginfo("[INFO] starting video stream...")
#Initializing publisher and odem message
aruco_publisher = rospy.Publisher('detected_aruco', aruco_data,queue_size=20)#Mention queue size if required
#aruco_msg: Stores aruco data published in /detected aruco topic
aruco_msg = aruco_data()
###############################FUNCTIONS#########################################
''' * Function Name: coordinates
* Input: arucodictionary,arucoparams,vs
* Output: originalcoord
* Logic: Takes image and detects all aruco markers and returns centroid of aruco marker with id 6
* Example Call: coordinates(ARUCODICTIONARY,ARUCOPARAMS,current_frame)
'''
def coordinates(arucodictionary,arucoparams,vs):
#Recieving frame and resize to 500x500
frame = vs
# detect ArUco markers in the input frame
(corners, ids, rejected) = cv2.aruco.detectMarkers(frame,arucodictionary, parameters=arucoparams)
if(len(corners)>0):
#ids: IDs of aruco markers
ids = ids.flatten()
for (markerCorner, markerID) in zip(corners, ids):
corners = markerCorner.reshape((4, 2))
(topLeft,topRight,bottomRight,bottomLeft) = corners
#topRight,bottomRight,bottomLeft,topLeft: tuple containing x,y coordinates of the corners of aruco markers
topRight = (int(topRight[0]), int(topRight[1]))
bottomRight = (int(bottomRight[0]), int(bottomRight[1]))
bottomLeft = (int(bottomLeft[0]), int(bottomLeft[1]))
topLeft = (int(topLeft[0]), int(topLeft[1]))
#Marking the marker and its center
cv2.line(frame,topLeft,topRight,(0,255,0),2)
cv2.line(frame, topRight, bottomRight, (0, 255, 0), 2)
cv2.line(frame, bottomRight, bottomLeft, (0, 255, 0), 2)
cv2.line(frame, bottomLeft, topLeft, (0, 255, 0), 2)
#Finding the Centroid
x0,y0=topLeft
x1,y1=topRight
x2,y2=bottomRight
x3,y3=bottomLeft
a=0.5*((x0*y1-x1*y0)+(x1*y2-x2*y1)+(x2*y3-x3*y2)+(x3*y0-x0*y3))
cX=int(1/(6*a))*(((x0+x1)*(x0*y1-x1*y0))+((x1+x2)*(x1*y2-x2*y1))+((x2+x3)*(x2*y3-x3*y2))+((x3+x0)*(x3*y0-x0*y3)))
cY=int(1/(6*a))*(((y0+y1)*(x0*y1-x1*y0))+((y1+y2)*(x1*y2-x2*y1))+((y2+y3)*(x2*y3-x3*y2))+((y3+y0)*(x3*y0-x0*y3)))
#cX,cY: Centroid of ID 6 aruco marker
cX = int((topLeft[0] + bottomRight[0]) / 2.0)
cY = int((topLeft[1] + bottomRight[1]) / 2.0)
#Marking the centre
cv2.circle(frame, (cX, cY), 4, (0, 0, 255), -1)
#Displaying the ID
cv2.putText(frame, str(markerID),
(topLeft[0], topLeft[1] - 15), cv2.FONT_HERSHEY_SIMPLEX,
0.5, (0, 255, 0), 2)
#Getting the arena boundries
if(markerID==4):
global arenatopright
arenatopright=topRight
elif(markerID==8):
global arenatopleft
arenatopleft=topLeft
elif(markerID==10):
global arenabottomleft
arenabottomleft=bottomLeft
elif(markerID==12):
global arenabottomright
arenabottomright=bottomRight
elif(markerID==6):
global holax,holay,c_edge_x,c_edge_y
holax=cX
holay=cY
c_edge_x = (topLeft[0] + bottomLeft[0]) / 2.0
c_edge_y = (topLeft[1] + bottomLeft[1]) / 2.0
else:
continue
#marking the arena border
cv2.line(frame,arenatopleft,arenatopright,(0,255,0),2)
cv2.line(frame,arenatopright,arenabottomright,(0,255,0),2)
cv2.line(frame,arenabottomright,arenabottomleft,(0,255,0),2)
cv2.line(frame,arenabottomleft,arenatopleft,(0,255,0),2)
#Getting the coordinates of the bot
coordx=int(500*(holax-arenabottomleft[0])/(arenabottomright[0]-arenabottomleft[0]))
coordy=int(500*(holay-arenabottomleft[1])/(arenatopleft[1]-arenabottomleft[1]))
theta = (math.atan2((holay-c_edge_y),(holax-c_edge_x)))
theta=-theta
originalcoord=str(coordx)+","+str(coordy)+","+str(theta)
#Display coordinates
cv2.putText(frame, originalcoord,
(holax, holay), cv2.FONT_HERSHEY_SIMPLEX,
0.5, (0, 255, 0), 2)
#cropping the arena from the frame and displaying it
frame = frame[arenatopleft[1]:arenabottomleft[1], arenabottomleft[0]:arenabottomright[0]]
cv2.imshow("Frame",frame)
cv2.waitKey(1)
#Aruco message to be published
aruco_msg.x = coordx
aruco_msg.y = coordy
aruco_msg.theta = theta
#Publishing aruco msgs
aruco_publisher.publish(aruco_msg)
return originalcoord
''' * Function Name: callback
* Input: data
* Output: none
* Logic: Takes in video feed and resize the frame.And passes the frame to coordinates()
* Example Call: callback()
'''
def callback(data):
br = CvBridge()
get_frame = br.imgmsg_to_cv2(data, "mono8")
current_frame = cv2.resize(get_frame, (1000, 1000), interpolation = cv2.INTER_LINEAR)
rospy.loginfo("Recieving camera feed")
ARUCODICTIONARY = cv2.aruco.Dictionary_get(ARUCO_DICT["DICT_4X4_250"])
ARUCOPARAMS = cv2.aruco.DetectorParameters_create()
coord=coordinates(ARUCODICTIONARY,ARUCOPARAMS,current_frame)
rospy.loginfo(coord)
###########################################MAIN#############################################################
def main():
rospy.init_node('Aruco_feedback_node')
rospy.Subscriber('/usb_cam/image_raw',Image,callback)
rospy.spin()
if __name__=='__main__':
main()