Skip to content

Commit ceacc12

Browse files
hamishwilleetcr3dr
authored andcommitted
Fix error due to incorrect access of location in callback in drone_delivery
1 parent 3a3e91c commit ceacc12

File tree

2 files changed

+20
-28
lines changed

2 files changed

+20
-28
lines changed

docs/examples/drone_delivery.rst

Lines changed: 17 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -63,28 +63,17 @@ On the command prompt you should see (something like):
6363

6464
.. code-block:: bash
6565
66-
\dronekit-python\examples\drone_delivery>drone_delivery.py
67-
local path: E:\deleteme\dronekit-python\examples\drone_delivery
6866
Connecting to vehicle on: 127.0.0.1:14550
69-
>>> ☺APM:Copter V3.4-dev (e0810c2e)
70-
>>> ☺Frame: QUAD
71-
connected ...
67+
>>> Frame: QUAD
68+
[DEBUG]: Connected to vehicle.
7269
[DEBUG]: DroneDelivery Start
73-
[DEBUG]: Waiting for GPS Lock
74-
[DEBUG]: DroneDelivery Armed Callback
75-
[DEBUG]: GPS: GPSInfo:fix=3,num_sat=10
70+
[DEBUG]: Waiting for ability to arm...
7671
[DEBUG]: Running initial boot sequence
77-
[DEBUG]: Arming
72+
[DEBUG]: Changing to mode: GUIDED
73+
[DEBUG]: Waiting for arming...
7874
[DEBUG]: Taking off
79-
[DEBUG]: Mode: GUIDED
80-
INFO:cherrypy.error:[21/Oct/2015:16:33:15] ENGINE Bus STARTING
81-
INFO:cherrypy.error:[21/Oct/2015:16:33:15] ENGINE Started monitor thread 'Autoreloader'.
82-
INFO:cherrypy.error:[21/Oct/2015:16:33:15] ENGINE Started monitor thread '_TimeoutMonitor'.
83-
INFO:cherrypy.error:[21/Oct/2015:16:33:15] ENGINE Serving on http://0.0.0.0:8080
84-
INFO:cherrypy.error:[21/Oct/2015:16:33:15] ENGINE Bus STARTED
85-
>>> ☺ARMING MOTORS
86-
>>> ☺Initialising APM...
87-
...
75+
http://localhost:8080/
76+
[DEBUG]: Goto: [u'-35.4', u'149.2'], 29.98
8877
8978
9079
Screenshots
@@ -110,21 +99,24 @@ For instance, `drone_delivery.py <https://github.com/dronekit/dronekit-python/bl
11099

111100
.. code-block:: python
112101
113-
self.vehicle.add_attribute_observer('location', self.location_callback)
102+
self.vehicle.add_attribute_listener('location', self.location_callback)
114103
115104
...
116105
117-
def location_callback(self, location):
118-
location = location.global_frame
119-
120-
if location.alt is not None:
121-
self.altitude = location.alt
106+
def location_callback(self, vehicle, name, location):
107+
if location.global_relative_frame.alt is not None:
108+
self.altitude = location.global_relative_frame.alt
122109
123-
self.current_location = location
110+
self.current_location = location.global_relative_frame
124111
125112
126113
This results in DroneKit calling our ``location_callback`` method any time the location attribute gets changed.
127114

115+
.. tip::
116+
117+
It is also possible (and often more elegant) to add listeners using a decorator
118+
- see :py:func:`Vehicle.on_attribute <dronekit.Vehicle.on_attribute>`.
119+
128120

129121

130122
Starting CherryPy from a DroneKit application

examples/drone_delivery/drone_delivery.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010
import simplejson
1111
import time
1212
from pymavlink import mavutil
13-
from dronekit import connect, VehicleMode, LocationGlobal
13+
from dronekit import connect, VehicleMode, LocationGlobal, LocationGlobalRelative
1414
import cherrypy
1515
from cherrypy.process import wspbus, plugins
1616
from jinja2 import Environment, FileSystemLoader
@@ -130,9 +130,9 @@ def get_location(self):
130130

131131
def location_callback(self, vehicle, name, location):
132132
if location.global_relative_frame.alt is not None:
133-
self.altitude = location.alt
133+
self.altitude = location.global_relative_frame.alt
134134

135-
self.current_location = location
135+
self.current_location = location.global_relative_frame
136136

137137
def _log(self, message):
138138
print "[DEBUG]: {0}".format(message)

0 commit comments

Comments
 (0)