"""Download a public mission from droneshare (as JSON)"""
f = urllib.urlopen("%s/api/v1/mission/%s/messages.json?max_freq=%s&api_key=%s" % (api_server, mission_id, max_freq, api_key))
j = json.load(f, object_hook=_decode_dict)
f.close()
return j
Some comments:
* ``max_freq`` is used to throttle the messages found in the raw flight data to a lower message rate
* ``_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).
Setting the new waypoints
-------------------------
If necessary, the example then reduces the number of messages retrieved into a set that can fit on the vehicle (in this case 100 waypoints).
The following code shows how the vehicle writes the received messages as commands (this part of the code is very similar to that
shown in :ref:`example_mission_basic`):
.. code:: python
print "Generating %s waypoints from replay..." % len(messages)
cmds = vehicle.commands
cmds.clear()
for i in xrange(0, len(messages)):
pt = messages[i]
lat = pt['lat']
lon = pt['lon']
# To prevent accidents we don't trust the altitude in the original flight, instead
# we just put in a conservative cruising altitude.
altitude = 30.0 # pt['alt']
cmd = Command( 0,
0,
0,
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
0, 0, 0, 0, 0, 0,
lat, lon, altitude)
cmds.add(cmd)
#Upload clear message and command messages to vehicle.
cmds.upload()
Known issues
============
There are no known issues with this example.
Source code
===========
The full source code at documentation build-time is listed below (`current version on github <https://github.com/dronekit/dronekit-python/blob/master/examples/flight_replay/flight_replay.py>`_):
This example requests a past flight from Droneshare, and then 'replays'
the flight by sending waypoints to a vehicle.
Full documentation is provided at http://python.dronekit.io/examples/flight_replay.html
"""
fromdronekitimportconnect,Command
frompymavlinkimportmavutil
importjson,urllib,math
#Set up option parsing to get connection string
importargparse
parser=argparse.ArgumentParser(description='Get a flight from droneshare and send as waypoints to a vehicle. Connects to SITL on local PC by default.')