-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathjustImageProcess
161 lines (132 loc) · 4.98 KB
/
justImageProcess
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
#!/usr/bin/env python
# -*- coding: utf-8 -*-
from __future__ import print_function
import threading
import logging
import dronekit_sitl
from dronekit import connect, VehicleMode, LocationGlobalRelative, Command, LocationGlobal
import numpy as np
import cv2
from picamera import PiCamera
from picamera.array import PiRGBArray
import math
import time
from pymavlink import mavutil
#print('Connecting to vehicle on: %s' % connection_string)
#vehicle = connect(connection_string, wait_ready=True)
vehicle = connect('127.0.0.1:14550', wait_ready = True)
def arm_and_takeoff(aTargetAltitude):
"""
Arms vehicle and fly to aTargetAltitude.
"""
print("Basic pre-arm checks")
# Don't try to arm until autopilot is ready
while not vehicle.is_armable:
print(" Waiting for vehicle to initialise...")
time.sleep(1)
print("Arming motors")
# Copter should arm in GUIDED mode
vehicle.mode = VehicleMode("GUIDED")
vehicle.armed = True
# Confirm vehicle armed before attempting to take off
while not vehicle.armed:
print(" Waiting for arming...")
time.sleep(1)
print("Taking off!")
vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude
# Wait until the vehicle reaches a safe height before processing the goto
# (otherwise the command after Vehicle.simple_takeoff will execute
# immediately).
while True:
print(" Altitude: ", vehicle.location.global_relative_frame.alt)
# Break and return from function just below target altitude.
if vehicle.location.global_relative_frame.alt >= aTargetAltitude * 0.95:
print("Reached target altitude")
break
time.sleep(1)
arm_and_takeoff(5)
time.sleep(1)
print("Set default/target airspeed to 10")
vehicle.airspeed = 10
def go(p):
vehicle.simple_goto(p , 5)
class Velocity():
def set_velocity_body(self,vehicle, vx, vy, vz, duration):
""" Remember: vz is positive downward!!!
http://ardupilot.org/dev/docs/copter-commands-in-guided-mode.html
Bitmask to indicate which dimensions should be ignored by the vehicle
(a value of 0b0000000000000000 or 0b0000001000000000 indicates that
none of the setpoint dimensions should be ignored). Mapping:
bit 1: x, bit 2: y, bit 3: z,
bit 4: vx, bit 5: vy, bit 6: vz,
bit 7: ax, bit 8: ay, bit 9:
"""
msg = vehicle.message_factory.set_position_target_local_ned_encode(
0,
0, 0,
mavutil.mavlink.MAV_FRAME_BODY_NED,
0b0000111111000111, # -- BITMASK -> Consider only the velocities
0, 0, 0, # -- POSITION
vx, vy, vz, # -- VELOCITY
0, 0, 0, # -- ACCELERATIONS
0, 0)
for x in range(0, duration):
vehicle.send_mavlink(msg)
vehicle.flush()
p = LocationGlobalRelative(39.8720857, 32.7320695, 5)
go(p)
merkez = False
def ironmaiden(x, y, w, h, frame, t, color, a):
cv2.putText(frame, color + str(t), (int(x), int(y + 20)), cv2.FONT_HERSHEY_SIMPLEX, 0.75, (0, 255, 255))
M = cv2.moments(a)
ax = int(M["m10"] / M["m00"])
ay = int(M["m01"] / M["m00"])
cv2.circle(frame, (ax, ay), 3, (255, 255, 255), -1)
cv2.putText(frame, "center", (ax - 20, ay - 20), cv2.FONT_HERSHEY_SIMPLEX, 0.5, (255, 255, 255), 1)
return (ax, ay)
def moving(ax, ay):
v2 = Velocity()
if ax > 240:
#-y
v2.set_velocity_body(vehicle, 0, -0.2, 0, 3)
elif ax < 240:
v2.set_velocity_body(vehicle, 0, 0.2, 0, 3)
elif ay > 240:
v2.set_velocity_body(vehicle, 0.2, 0, 0, 3)
elif ay < 240:
v2.set_velocity_body(vehicle, -0.2, 0, 0, 3)
camera = PiCamera()
camera.resolution = (480, 480)
camera.framerate = 32
rawCapture = PiRGBArray(camera, size=(480, 480))
lower_red = np.array([130, 150, 150])
upper_red = np.array([200, 255, 255])
time.sleep(0.1)
for frame in camera.capture_continuous(rawCapture, format="bgr", use_video_port=True):
t = 0
shot = frame.array
cv2.circle(shot, (240, 240, 3, (255, 255, 255), -1))
blur = cv2.GaussianBlur(shot, (11, 11), 0)
hsv = cv2.cvtColor(blur, cv2.COLOR_BGR2HSV)
j = 0
mask = cv2.inRange(hsv, lower_red, upper_red)
kernelOPen = np.ones((20, 20))
mask = cv2.dilate(mask, kernelOPen, iterations=5)
__, countours, hierarchy = cv2.findContours(mask, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE)
if j == 0:
for a in countours:
peri = 0.01 * cv2.arcLength(a, True)
approx = cv2.approxPolyDP(a, peri, True)
if len(approx) >= 3:
if (cv2.contourArea(a) > 100):
x, y, w, h = cv2.boundingRect(a)
color = "Fire"
ax, ay = ironmaiden(x, y, w, h, shot, t, color, a)
moving(ax, ay)
cv2.imshow('cam', shot)
cv2.imshow('mask', mask)
rawCapture.truncate(0)
if ( 220<=ax<=240 and 220<=ay<=240):
merkez = True
if (merkez == True):
break