forked from dronekit/dronekit-python
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathdrone_delivery.py
197 lines (159 loc) · 5.98 KB
/
drone_delivery.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
import os, os.path
import simplejson
from pymavlink import mavutil
import droneapi.lib
from droneapi.lib import VehicleMode, Location
import cherrypy
from cherrypy.process import wspbus, plugins
from jinja2 import Environment, FileSystemLoader
cherrypy_conf = {
'/': {
'tools.sessions.on': True,
'tools.staticdir.root': local_path
},
'/static': {
'tools.staticdir.on': True,
'tools.staticdir.dir': './html/assets'
}
}
class Drone(object):
def __init__(self, home_coords, server_enabled=True):
self.api = local_connect()
self.gps_lock = False
self.altitude = 30.0
self.vehicle = self.api.get_vehicles()[0]
self.commands = self.vehicle.commands
self.current_coords = []
self.home_coords = home_coords
self.webserver_enabled = server_enabled
self._log("DroneDelivery Start")
# Register observers
self.vehicle.add_attribute_observer('armed', self.armed_callback)
self.vehicle.add_attribute_observer('location', self.location_callback)
#self.vehicle.add_attribute_observer('mode', self.mode_callback)
self.vehicle.add_attribute_observer('gps_0', self.gps_callback)
self._log("Waiting for GPS Lock")
def takeoff(self):
self._log("Taking off")
self.commands.takeoff(30.0)
self.vehicle.flush()
def arm(self, toggle=True):
if toggle:
self._log("Arming")
else:
self._log("Disarming")
self.vehicle.armed = True
self.vehicle.flush()
def run(self):
self._log('Running initial boot sequence')
self.arm()
self.takeoff()
self.change_mode('GUIDED')
if self.webserver_enabled is True:
self._run_server()
def _run_server(self):
# Start web server if enabled
cherrypy.tree.mount(DroneDelivery(self), '/', config=cherrypy_conf)
cherrypy.config.update({
'server.socket_port': 8080,
'server.socket_host': '0.0.0.0',
'log.screen': None
})
cherrypy.engine.start()
def change_mode(self, mode):
self._log("Mode: {0}".format(mode))
self.vehicle.mode = VehicleMode(mode)
self.vehicle.flush()
def goto(self, location, relative=None):
self._log("Goto: {0}, {1}".format(location, self.altitude))
self.commands.goto(
Location(
float(location[0]), float(location[1]),
float(self.altitude),
is_relative=relative
)
)
self.vehicle.flush()
def get_location(self):
return [self.current_location.lat, self.current_location.lon]
def location_callback(self, location):
location = self.vehicle.location
if location.alt is not None:
self.altitude = location.alt
self.current_location = location
def armed_callback(self, armed):
self._log("DroneDelivery Armed Callback")
self.vehicle.remove_attribute_observer('armed', self.armed_callback)
def mode_callback(self, mode):
self._log("Mode: {0}".format(self.vehicle.mode))
def gps_callback(self, gps):
self._log("GPS: {0}".format(self.vehicle.gps_0))
if self.gps_lock is False:
self.gps_lock = True
self.vehicle.remove_attribute_observer('gps_0', self.gps_callback)
self.run()
def _log(self, message):
print "[DEBUG]: {0}".format(message)
class Templates:
def __init__(self, home_coords):
self.home_coords = home_coords
self.options = self.get_options()
self.environment = Environment(loader=FileSystemLoader( local_path + '/html'))
def get_options(self):
return {
'width': 670,
'height': 470,
'zoom': 13,
'format': 'png',
'access_token': 'pk.eyJ1IjoibXJwb2xsbyIsImEiOiJtUG0tRk9BIn0.AqAiefUV9fFYRo-w0jFR1Q',
'mapid': 'mrpollo.kfbnjbl0',
'home_coords': self.home_coords,
'menu': [
{'name': 'Home', 'location': '/'},
{'name': 'Track', 'location': '/track'},
{'name': 'Command', 'location': '/command'}
],
'current_url': '/',
'json': ''
}
def index(self):
self.options = self.get_options()
self.options['current_url'] = '/'
return self.get_template('index')
def track(self, current_coords):
self.options = self.get_options()
self.options['current_url'] = '/track'
self.options['current_coords'] = current_coords
self.options['json'] = simplejson.dumps(self.options)
return self.get_template('track')
def command(self, current_coords):
self.options = self.get_options()
self.options['current_url'] = '/command'
self.options['current_coords'] = current_coords
return self.get_template('command')
def get_template(self, file_name):
template = self.environment.get_template( file_name + '.html')
return template.render(options=self.options)
class DroneDelivery(object):
def __init__(self, drone):
self.drone = drone
self.templates = Templates(self.drone.home_coords)
@cherrypy.expose
def index(self):
return self.templates.index()
@cherrypy.expose
def command(self):
return self.templates.command(self.drone.get_location())
@cherrypy.expose
@cherrypy.tools.json_out()
def vehicle(self):
return dict(position=self.drone.get_location())
@cherrypy.expose
def track(self, lat=None, lon=None):
# Process POST request from Command
# Sending MAVLink packet with goto instructions
if(lat is not None and lon is not None):
self.drone.goto([lat, lon], True)
return self.templates.track(self.drone.get_location())
Drone([32.5738, -117.0068])
cherrypy.engine.block()