-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathprecision_landing_single_aruco.py
212 lines (178 loc) · 7.08 KB
/
precision_landing_single_aruco.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
###########DEPENDENCIES################
import time
import socket
import math
import argparse
from arm_takeoff_3 import arm, takeoff, connectMyCopter
from location_based_movement import goto
import sys
import threading
from dronekit import connect, VehicleMode,LocationGlobalRelative,APIException
from pymavlink import mavutil
import cv2
import cv2.aruco as aruco
import numpy as np
from imutils.video import WebcamVideoStream
import imutils
#######VARIABLES####################
##Aruco
id_to_find = 72
marker_size = 19 #cm
takeoff_height = 8
velocity = .5
aruco_dict = aruco.getPredefinedDictionary(aruco.DICT_ARUCO_ORIGINAL)
parameters = aruco.DetectorParameters_create()
##
##Camera
horizontal_res = 800
vertical_res = 600
cap = WebcamVideoStream(src=0, width=horizontal_res, height=vertical_res).start()
horizontal_fov =59 * (math.pi / 180 ) ##Pi cam V1: 53.5 V2: 62.2
vertical_fov =46 * (math.pi / 180) ##Pi cam V1: 41.41 V2: 48.8
cameraMatrix = np.array([[933.9466925521707, 0, 358.59608943398365],
[0, 935.0635463990791, 293.0721064675127],
[0, 0, 1]])
cameraDistortion = np.array([-0.4530790972005633, 0.3951099938612813, 0.0037673873203789916, 0.0016363264710513889, -0.38177331299300393])
##
##Counters and script triggers
found_count=0
notfound_count=0
first_run=0 #Used to set initial time of function to determine FPS
start_time=0
end_time=0
script_mode = 1 ##1 for arm and takeoff, 2 for manual LOITER to GUIDED land
ready_to_land=0 ##1 to trigger landing
manualArm=True ##If True, arming from RC controller, If False, arming from this script.
#########FUNCTIONS#################
def send_local_ned_velocity(vx, vy, vz):
msg = vehicle.message_factory.set_position_target_local_ned_encode(
0,
0, 0,
mavutil.mavlink.MAV_FRAME_BODY_OFFSET_NED,
0b0000111111000111,
0, 0, 0,
vx, vy, vz,
0, 0, 0,
0, 0)
vehicle.send_mavlink(msg)
vehicle.flush()
def send_land_message(x,y):
msg = vehicle.message_factory.landing_target_encode(
0,
0,
mavutil.mavlink.MAV_FRAME_BODY_OFFSET_NED,
x,
y,
0,
0,
0,)
vehicle.send_mavlink(msg)
vehicle.flush()
def lander():
global first_run,notfound_count,found_count,marker_size,start_time
if first_run==0:
print("First run of lander!!")
first_run=1
start_time=time.time()
frame = cap.read()
frame = cv2.flip(frame,0) #flips camera to correct orientation
frame = cv2.flip(frame,1)
frame = cv2.resize(frame,(horizontal_res,vertical_res))
frame_np = np.array(frame)
gray_img = cv2.cvtColor(frame_np,cv2.COLOR_BGR2GRAY)
ids=''
corners, ids, rejected = aruco.detectMarkers(image=gray_img,dictionary=aruco_dict,parameters=parameters)
if vehicle.mode!='LAND' and vehicle.mode != "POSHOLD":
vehicle.mode=VehicleMode("LAND")
while vehicle.mode!='LAND':
print('WAITING FOR DRONE TO ENTER LAND MODE')
time.sleep(1)
try:
if ids is not None and ids[0] == id_to_find:
ret = aruco.estimatePoseSingleMarkers(corners,marker_size,cameraMatrix=cameraMatrix,distCoeffs=cameraDistortion)
(rvec, tvec) = (ret[0][0, 0, :], ret[1][0, 0, :])
x = '{:.2f}'.format(tvec[0])
y = '{:.2f}'.format(tvec[1])
z = '{:.2f}'.format(tvec[2])
y_sum = 0
x_sum = 0
x_sum = corners[0][0][0][0]+ corners[0][0][1][0]+ corners[0][0][2][0]+ corners[0][0][3][0]
y_sum = corners[0][0][0][1]+ corners[0][0][1][1]+ corners[0][0][2][1]+ corners[0][0][3][1]
x_avg = x_sum*.25
y_avg = y_sum*.25
x_ang = (x_avg - horizontal_res*.5)*(horizontal_fov/horizontal_res)
y_ang = (y_avg - vertical_res*.5)*(vertical_fov/vertical_res)
if vehicle.mode!='LAND':
vehicle.mode = VehicleMode('LAND')
while vehicle.mode!='LAND':
time.sleep(1)
print("------------------------")
print("Vehicle now in LAND mode")
print("------------------------")
send_land_message(x_ang,y_ang)
else:
send_land_message(x_ang,y_ang)
pass
print(("X CENTER PIXEL: "+str(x_avg)+" Y CENTER PIXEL: "+str(y_avg)))
print(("FOUND COUNT: "+str(found_count)+" NOTFOUND COUNT: "+str(notfound_count)))
print(("MARKER POSITION: x=" +x+" y= "+y+" z="+z))
found_count=found_count+1
print("")
else:
notfound_count=notfound_count+1
except Exception as e:
print(('Target likely not found. Error: '+str(e)))
notfound_count=notfound_count+1
def program_exit(vehicle):
if vehicle.armed:
if vehicle.mode != "LAND" or vehicle.mode != "RTL" or vehicle.mode != "GUIDED":
#se sube a 15m deja el drone en POSHOLD y cierra el script
vehicle.mode = VehicleMode("GUIDED")
while vehicle.mode != "GUIDED":
time.sleep(1)
print("Waiting for drone to enter GUIDED mode")
print("EMERGENCY STOP")
gotoLocation = LocationGlobalRelative(vehicle.location.lat, vehicle.location.lon, 15)
goto(gotoLocation)
vehicle.mode = VehicleMode("POSHOLD")
sys.exit()
######################################################
#######################MAIN###########################
######################################################
vehicle = connectMyCopter()
exitTread = threading.Thread(target=program_exit, args=(vehicle,))
exitTread.start()
##
##SETUP PARAMETERS TO ENABLE PRECISION LANDING
##
vehicle.parameters['PLND_ENABLED'] = 1
vehicle.parameters['PLND_TYPE'] = 1 ##1 for companion computer
vehicle.parameters['PLND_EST_TYPE'] = 0 ##0 for raw sensor, 1 for kalman filter pos estimation
vehicle.parameters['LAND_SPEED'] = 20 ##Descent speed of 30cm/s
if script_mode ==1:
arm(vehicle)
takeoff(7,vehicle)
print((str(time.time())))
#send_local_ned_velocity(velocity,velocity,0) ##Offset drone from target
time.sleep(1)
ready_to_land=1
elif script_mode==2:
while vehicle.mode!='GUIDED':
time.sleep(1)
print(("Waiting for manual change from mode "+str(vehicle.mode)+" to GUIDED"))
ready_to_land=1
if ready_to_land==1:
while vehicle.armed==True:
lander()
end_time=time.time()
total_time=end_time-start_time
total_time=abs(int(total_time))
total_count=found_count+notfound_count
freq_lander=total_count/total_time
print(("Total iterations: "+str(total_count)))
print(("Total seconds: "+str(total_time)))
print("------------------")
print(("lander function had frequency of: "+str(freq_lander)))
print("------------------")
print("Vehicle has landed")
print("------------------")