Skip to content

Commit a99d3d3

Browse files
committed
Update flight_replay docs and also to use standard takeoff function
1 parent 17bb5a4 commit a99d3d3

File tree

3 files changed

+174
-78
lines changed

3 files changed

+174
-78
lines changed

docs/examples/flight_replay.rst

Lines changed: 129 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -2,22 +2,21 @@
22
Example: Flight Replay
33
=========================
44

5-
This example requests a past flight from Droneshare, and then writes the recorded path to the vehicle as mission waypoints.
6-
For safety reasons, the altitude for the waypoints is set to 30 meters (irrespective of the recorded height).
7-
8-
.. note::
9-
10-
The mission is not actually run by this code - though it easily could be by taking off and putting the vehicle into
11-
AUTO mode.
12-
5+
This example creates and runs a waypoint mission using position information in a TLOG file.
136

14-
You can specify which mission to replay using a parameter when starting the script (for example, to replay your own local flights).
15-
By default the code gets the public `Droneshare mission with ID 101 <http://www.droneshare.com/mission/101>`_.
7+
The log used in this example contains around 2700 points. We reduce this to a smaller number
8+
(that is able to fit on the autopilot) by taking 100 points that are evenly spread across the range.
9+
After 60 seconds the mission is artificially ended by setting the mode to RTL (return to launch).
1610

1711
.. figure:: flight_replay_example.png
12+
:width: 50%
1813

19-
Droneshare Mission #101
14+
Mission generated from log
2015

16+
.. note::
17+
18+
A more detailed example might determine the best points for the mission
19+
by mapping the path to lines and spline curves.
2120

2221

2322
Running the example
@@ -26,75 +25,154 @@ Running the example
2625
The example can be run as described in :doc:`running_examples` (which in turn assumes that the vehicle
2726
and DroneKit have been set up as described in :ref:`installing_dronekit`).
2827

29-
If you're using a simulated vehicle, remember to :ref:`disable arming checks <disable-arming-checks>` so
30-
that the example can run.
31-
3228
In summary, after cloning the repository:
3329

3430
#. Navigate to the example folder as shown:
3531

3632
.. code-block:: bash
3733
3834
cd dronekit-python/examples/flight_replay/
39-
40-
41-
#. Start the example, passing the :ref:`connection string <get_started_connect_string>`
42-
you wish to use in the ``--connect`` parameter and specifying the mission to replay.
35+
36+
#. You can run the example against a simulator (DroneKit-SITL) by specifying the Python script without any arguments.
37+
The example will download SITL binaries if needed, start the simulator, and then connect to it:
4338

4439
.. code-block:: bash
4540
46-
python flight_replay.py --connect 127.0.0.1:14550 --mission_id 101
41+
python flight_replay.py
4742
48-
.. note::
43+
On the command prompt you should see (something like):
4944

50-
The ``--connect`` parameter above connects to SITL on udp port 127.0.0.1:14550, while
51-
``--mission_id`` specifies we're replaying mission 101. Both of these are the default
52-
values for the parameters, and may be omitted.
53-
45+
.. code:: bash
46+
47+
Generating waypoints from tlog...
48+
Generated 96 waypoints from tlog
49+
Starting copter simulator (SITL)
50+
SITL already Downloaded.
51+
Connecting to vehicle on: tcp:127.0.0.1:5760
52+
>>> APM:Copter V3.3 (d6053245)
53+
>>> Frame: QUAD
54+
>>> Calibrating barometer
55+
>>> Initialising APM...
56+
>>> barometer calibration complete
57+
>>> GROUND START
58+
Uploading 96 waypoints to vehicle...
59+
Arm and Takeoff
60+
Waiting for vehicle to initialise...
61+
>>> flight plan received
62+
Waiting for arming...
63+
...
64+
Waiting for arming...
65+
>>> ARMING MOTORS
66+
>>> GROUND START
67+
Waiting for arming...
68+
>>> Initialising APM...
69+
Waiting for arming...
70+
>>> ARMING MOTORS
71+
Taking off!
72+
Altitude: 0.010000 < 28.500000
73+
Altitude: 0.020000 < 28.500000
74+
...
75+
Altitude: 26.150000 < 28.500000
76+
Altitude: 28.170000 < 28.500000
77+
Reached target altitude of ~30.000000
78+
Starting mission
79+
Distance to waypoint (1): 6.31671220061
80+
Distance to waypoint (1): 5.54023406731
81+
>>> Reached Command #1
82+
Distance to waypoint (2): 4.05805003875
83+
...
84+
Distance to waypoint (2): 4.66600036548
85+
>>> Reached Command #2
86+
Distance to waypoint (3): 1.49371523482
87+
Distance to waypoint (3): 0.13542601646
88+
Distance to waypoint (3): 0.708432959397
89+
>>> Reached Command #3
90+
Distance to waypoint (4): 3.29161427437
91+
Distance to waypoint (4): 3.63454331996
92+
Distance to waypoint (4): 2.89070828637
93+
>>> Reached Command #4
94+
Distance to waypoint (5): 0.955857968149
95+
>>> Reached Command #5
96+
>>> Reached Command #6
97+
>>> Reached Command #7
98+
...
99+
>>> Reached Command #42
100+
Distance to waypoint (42): 7.6983209285
101+
...
102+
Distance to waypoint (43): 6.05247510021
103+
>>> Reached Command #43
104+
Distance to waypoint (43): 4.80180763387
105+
>>> Reached Command #44
106+
Distance to waypoint (44): 3.89880557617
107+
...
108+
Distance to waypoint (45): 11.0865559753
109+
>>> Reached Command #45
110+
Distance to waypoint (46): 9.45419808223
111+
...
112+
Distance to waypoint (46): 13.2676499949
113+
Return to launch
114+
Close vehicle object
115+
Completed...
116+
117+
.. tip::
118+
119+
It is more interesting to watch the example run on a map than the console. The topic :ref:`viewing_uav_on_map`
120+
explains how to set up *Mission Planner* to view a vehicle running on the simulator (SITL).
54121

55-
.. tip::
56-
57-
It is more interesting to watch the example above on a map than the console. The topic :ref:`viewing_uav_on_map`
58-
explains how to set up *Mission Planner* to view a vehicle running on the simulator (SITL).
122+
#. You can run the example against a specific connection (simulated or otherwise) by passing the :ref:`connection string <get_started_connect_string>` for your vehicle in the ``--connect`` parameter.
59123

60-
On the command prompt you should see (something like):
124+
For example, to connect to SITL running on UDP port 14550 on your local computer:
61125

62-
.. code-block:: bash
63-
64-
Connecting to vehicle on: 127.0.0.1:14550
65-
>>> APM:Copter V3.3 (d6053245)
66-
>>> Frame: QUAD
67-
JSON downloaded...
68-
Generating 95 waypoints from replay...
69-
Close vehicle object
70-
Completed...
126+
.. code-block:: bash
71127
128+
python simple_goto.py --connect 127.0.0.1:14550
129+
72130
131+
73132
How it works
74133
============
75134

76-
The example requests the web server for representative points from the flight, parses the JSON response
77-
and uses that data to generate 100 waypoints. These are then sent to the vehicle.
135+
The example parses the **flight.tlog** file for position information. It then selects about 100
136+
points that are evenly spread across the log and uploads them as a mission.
78137

138+
For safety reasons, the altitude for the waypoints is set to 30 meters (irrespective of the recorded height).
79139

80140
Getting the points
81141
------------------
82142

83-
The following simple function asks for the droneshare flight data:
143+
The following simple function parses the tlog for points and then
144+
returns 100 evenly points from the collected set.
84145

85146
.. code:: python
86147
87-
def download_messages(mission_id, max_freq = 1.0):
88-
"""Download a public mission from droneshare (as JSON)"""
89-
f = urllib.urlopen("%s/api/v1/mission/%s/messages.json?max_freq=%s&api_key=%s" % (api_server, mission_id, max_freq, api_key))
90-
j = json.load(f, object_hook=_decode_dict)
91-
f.close()
92-
return j
93-
94-
Some comments:
148+
def position_messages_from_tlog(filename):
149+
"""
150+
Given telemetry log, get a series of waypoints approximating the previous flight
151+
"""
152+
# Pull out just the global position msgs
153+
messages = []
154+
mlog = mavutil.mavlink_connection(filename)
155+
while True:
156+
try:
157+
m = mlog.recv_match(type=['GLOBAL_POSITION_INT'])
158+
if m is None:
159+
break
160+
except Exception:
161+
break
162+
# ignore we get where there is no fix:
163+
if m.lat == 0:
164+
continue
165+
messages.append(m)
166+
167+
# Shrink the # of pts to be lower than the max # of wpts allowed by vehicle
168+
num_points = len(messages)
169+
max_points = 99
170+
if num_points > max_points:
171+
step = int(math.ceil((float(num_points) / max_points)))
172+
shorter = [messages[i] for i in xrange(0, num_points, step)]
173+
messages = shorter
174+
return messages
95175
96-
* ``max_freq`` is used to throttle the messages found in the raw flight data to a lower message rate
97-
* ``_decode_dict`` is a utility function found on stack overflow which extracts usable strings from unicode encoded JSON (see `flight_replay.py <https://github.com/hamishwillee/dronekit-python/blob/master/examples/flight_replay/flight_replay.py>`_ for its implementation).
98176
99177
100178
Setting the new waypoints
-422 KB
Loading

examples/flight_replay/flight_replay.py

Lines changed: 45 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,9 @@ def distance_to_current_waypoint():
6868
return distancetopoint
6969

7070
def position_messages_from_tlog(filename):
71-
"""Given telemetry log, get a series of wpts approximating the previous flight"""
71+
"""
72+
Given telemetry log, get a series of wpts approximating the previous flight
73+
"""
7274
# Pull out just the global position msgs
7375
messages = []
7476
mlog = mavutil.mavlink_connection(filename)
@@ -92,10 +94,48 @@ def position_messages_from_tlog(filename):
9294
shorter = [messages[i] for i in xrange(0, num_points, step)]
9395
messages = shorter
9496
return messages
97+
98+
99+
def arm_and_takeoff(aTargetAltitude):
100+
"""
101+
Arms vehicle and fly to aTargetAltitude.
102+
"""
103+
104+
# Don't try to arm until autopilot is ready
105+
while not vehicle.is_armable:
106+
print " Waiting for vehicle to initialise..."
107+
time.sleep(1)
108+
109+
# Set mode to GUIDED for arming and takeoff:
110+
while (vehicle.mode.name != "GUIDED"):
111+
vehicle.mode = VehicleMode("GUIDED")
112+
time.sleep(0.1)
113+
114+
# Confirm vehicle armed before attempting to take off
115+
while not vehicle.armed:
116+
vehicle.armed = True
117+
print " Waiting for arming..."
118+
time.sleep(1)
119+
120+
print " Taking off!"
121+
vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude
122+
123+
# Wait until the vehicle reaches a safe height
124+
# before allowing next command to process.
125+
while True:
126+
requiredAlt = aTargetAltitude*0.95
127+
#Break and return from function just below target altitude.
128+
if vehicle.location.global_relative_frame.alt>=requiredAlt:
129+
print " Reached target altitude of ~%f" % (aTargetAltitude)
130+
break
131+
print " Altitude: %f < %f" % (vehicle.location.global_relative_frame.alt,
132+
requiredAlt)
133+
time.sleep(1)
134+
95135

96136
print("Generating waypoints from tlog...")
97137
messages = position_messages_from_tlog(args.tlog)
98-
print "Generated %d waypoints from tlog" % len(messages)
138+
print " Generated %d waypoints from tlog" % len(messages)
99139
if len(messages) == 0:
100140
print("No position messages found in log")
101141
exit(0)
@@ -124,7 +164,7 @@ def position_messages_from_tlog(filename):
124164
cmds.clear()
125165
for i in xrange(0, len(messages)):
126166
pt = messages[i]
127-
print "Point: %d %d" % (pt.lat, pt.lon,)
167+
#print "Point: %d %d" % (pt.lat, pt.lon,)
128168
lat = pt.lat
129169
lon = pt.lon
130170
# To prevent accidents we don't trust the altitude in the original flight, instead
@@ -143,31 +183,9 @@ def position_messages_from_tlog(filename):
143183
print("Uploading %d waypoints to vehicle..." % len(messages))
144184
cmds.upload()
145185

146-
# Set mode to STABILISE for arming and takeoff:
147-
while (vehicle.mode.name != "GUIDED"):
148-
vehicle.mode = VehicleMode("GUIDED")
149-
time.sleep(0.1)
150-
151-
while not vehicle.armed:
152-
print("Arming vehicle")
153-
vehicle.armed = True
154-
print "Waiting for arming..."
155-
time.sleep(1)
186+
print "Arm and Takeoff"
187+
arm_and_takeoff(30)
156188

157-
print("Taking off")
158-
aTargetAltitude = 30.0
159-
vehicle.simple_takeoff(aTargetAltitude)
160-
161-
# Wait until the vehicle reaches a safe height
162-
while True:
163-
requiredAlt = aTargetAltitude*0.95
164-
#Break and return from function just below target altitude.
165-
if vehicle.location.global_relative_frame.alt>=requiredAlt:
166-
print "Reached target altitude of ~%f" % (aTargetAltitude)
167-
break
168-
print " Altitude: %f < %f" % (vehicle.location.global_relative_frame.alt,
169-
requiredAlt)
170-
time.sleep(1)
171189

172190
print "Starting mission"
173191

0 commit comments

Comments
 (0)