Example: Mission Import/Export

This example shows how to import and export files in the Waypoint file format.

The commands are first imported from a file into a list and then uploaded to the vehicle. Then the current mission is downloaded from the vehicle and put into a list, which is then saved into (another file). Finally, we print out both the original and new files for comparison

The example does not show how missions can be modified, but once the mission is in a list, changing the order and content of commands is straightforward.

The guide topic Missions (AUTO Mode) provides information about missions and AUTO mode.

Running the example

The example can be run as described in Running the Examples (which in turn assumes that the vehicle and DroneKit have been set up as described in Installing DroneKit).

In summary, after cloning the repository:

  1. Navigate to the example folder as shown:

    cd dronekit-python/examples/mission_import_export/
    
  2. You can run the example against a simulator (DroneKit-SITL) by specifying the Python script without any arguments. The example will download SITL binaries (if needed), start the simulator, and then connect to it:

    python mission_import_export.py
    

    On the command prompt you should see (something like):

    Starting copter simulator (SITL)
    SITL already Downloaded.
    Connecting to vehicle on: tcp:127.0.0.1:5760
    >>> APM:Copter V3.3 (d6053245)
    >>> Frame: QUAD
    >>> Calibrating barometer
    >>> Initialising APM...
    >>> barometer calibration complete
    >>> GROUND START
     Waiting for vehicle to initialise...
     Waiting for vehicle to initialise...
     Waiting for vehicle to initialise...
     Waiting for vehicle to initialise...
     Waiting for vehicle to initialise...
     Reading mission from file: mpmission.txt
     Upload mission from a file: mpmission.txt
     Clear mission
     Upload mission
     Save mission from Vehicle to file: exportedmission.txt
     Download mission from vehicle
    >>> flight plan received
     Write mission to file
    Close vehicle object
     Show original and uploaded/downloaded files:
    
     Mission file: mpmission.txt
     QGC WPL 110
     0  1   0   16  0   0   0   0   -35.363262  149.165237  584.000000  1
     1  0   0   22  0.000000    0.000000    0.000000    0.000000    -35.361988  149.163753  00.000000  1
     2  0   0   16  0.000000    0.000000    0.000000    0.000000    -35.361992  149.163593  00.000000  1
     3  0   0   16  0.000000    0.000000    0.000000    0.000000    -35.363812  149.163609  00.000000  1
     4  0   0   16  0.000000    0.000000    0.000000    0.000000    -35.363768  149.166055  00.000000  1
     5  0   0   16  0.000000    0.000000    0.000000    0.000000    -35.361835  149.166012  00.000000  1
     6  0   0   16  0.000000    0.000000    0.000000    0.000000    -35.362150  149.165046  00.000000  1
    
     Mission file: exportedmission.txt
     QGC WPL 110
     0    1     0     16    0     0     0     0     -35.3632621765  149.165237427   583.989990234   1
     1    0     0     22    0.0   0.0   0.0   0.0   -35.3619880676  149.163757324   100.0   1
     2    0     0     16    0.0   0.0   0.0   0.0   -35.3619918823  149.163589478   100.0   1
     3    0     0     16    0.0   0.0   0.0   0.0   -35.3638114929  149.163604736   100.0   1
     4    0     0     16    0.0   0.0   0.0   0.0   -35.3637695312  149.166061401   100.0   1
     5    0     0     16    0.0   0.0   0.0   0.0   -35.3618354797  149.166015625   100.0   1
     6    0     0     16    0.0   0.0   0.0   0.0   -35.3621482849  149.165039062   100.0   1
    

    Note

    The position values uploaded and then downloaded above do not match exactly. This rounding error can be ignored because the difference is much smaller than the precision provided by GPS.

    The error occurs because all the params are encoded as 32-bit floats rather than 64-bit doubles (Python’s native datatype).

  3. You can run the example against a specific connection (simulated or otherwise) by passing the connection string for your vehicle in the --connect parameter.

    For example, to connect to SITL running on UDP port 14550 on your local computer:

    python mission_import_export.py --connect 127.0.0.1:14550
    

How does it work?

The source code is largely self-documenting.

More information about the functions can be found in the guide at Load a mission from a file and Save a mission to a file.

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):

#!/usr/bin/env python
# -*- coding: utf-8 -*-

"""
© Copyright 2015-2016, 3D Robotics.
mission_import_export.py: 

This example demonstrates how to import and export files in the Waypoint file format 
(http://qgroundcontrol.org/mavlink/waypoint_protocol#waypoint_file_format). The commands are imported
into a list, and can be modified before saving and/or uploading.

Documentation is provided at http://python.dronekit.io/examples/mission_import_export.html
"""
from __future__ import print_function


from dronekit import connect, Command
import time


#Set up option parsing to get connection string
import argparse  
parser = argparse.ArgumentParser(description='Demonstrates mission import/export from a file.')
parser.add_argument('--connect', 
                   help="Vehicle connection target string. If not specified, SITL automatically started and used.")
args = parser.parse_args()

connection_string = args.connect
sitl = None


#Start SITL if no connection string specified
if not connection_string:
    import dronekit_sitl
    sitl = dronekit_sitl.start_default()
    connection_string = sitl.connection_string()


# Connect to the Vehicle
print('Connecting to vehicle on: %s' % connection_string)
vehicle = connect(connection_string, wait_ready=True)

# Check that vehicle is armable. 
# This ensures home_location is set (needed when saving WP file)

while not vehicle.is_armable:
    print(" Waiting for vehicle to initialise...")
    time.sleep(1)


def readmission(aFileName):
    """
    Load a mission from a file into a list. The mission definition is in the Waypoint file
    format (http://qgroundcontrol.org/mavlink/waypoint_protocol#waypoint_file_format).

    This function is used by upload_mission().
    """
    print("\nReading mission from file: %s" % aFileName)
    cmds = vehicle.commands
    missionlist=[]
    with open(aFileName) as f:
        for i, line in enumerate(f):
            if i==0:
                if not line.startswith('QGC WPL 110'):
                    raise Exception('File is not supported WP version')
            else:
                linearray=line.split('\t')
                ln_index=int(linearray[0])
                ln_currentwp=int(linearray[1])
                ln_frame=int(linearray[2])
                ln_command=int(linearray[3])
                ln_param1=float(linearray[4])
                ln_param2=float(linearray[5])
                ln_param3=float(linearray[6])
                ln_param4=float(linearray[7])
                ln_param5=float(linearray[8])
                ln_param6=float(linearray[9])
                ln_param7=float(linearray[10])
                ln_autocontinue=int(linearray[11].strip())
                cmd = Command( 0, 0, 0, ln_frame, ln_command, ln_currentwp, ln_autocontinue, ln_param1, ln_param2, ln_param3, ln_param4, ln_param5, ln_param6, ln_param7)
                missionlist.append(cmd)
    return missionlist


def upload_mission(aFileName):
    """
    Upload a mission from a file. 
    """
    #Read mission from file
    missionlist = readmission(aFileName)
    
    print("\nUpload mission from a file: %s" % aFileName)
    #Clear existing mission from vehicle
    print(' Clear mission')
    cmds = vehicle.commands
    cmds.clear()
    #Add new mission to vehicle
    for command in missionlist:
        cmds.add(command)
    print(' Upload mission')
    vehicle.commands.upload()


def download_mission():
    """
    Downloads the current mission and returns it in a list.
    It is used in save_mission() to get the file information to save.
    """
    print(" Download mission from vehicle")
    missionlist=[]
    cmds = vehicle.commands
    cmds.download()
    cmds.wait_ready()
    for cmd in cmds:
        missionlist.append(cmd)
    return missionlist

def save_mission(aFileName):
    """
    Save a mission in the Waypoint file format 
    (http://qgroundcontrol.org/mavlink/waypoint_protocol#waypoint_file_format).
    """
    print("\nSave mission from Vehicle to file: %s" % aFileName)    
    #Download mission from vehicle
    missionlist = download_mission()
    #Add file-format information
    output='QGC WPL 110\n'
    #Add home location as 0th waypoint
    home = vehicle.home_location
    output+="%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\n" % (0,1,0,16,0,0,0,0,home.lat,home.lon,home.alt,1)
    #Add commands
    for cmd in missionlist:
        commandline="%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\t%s\n" % (cmd.seq,cmd.current,cmd.frame,cmd.command,cmd.param1,cmd.param2,cmd.param3,cmd.param4,cmd.x,cmd.y,cmd.z,cmd.autocontinue)
        output+=commandline
    with open(aFileName, 'w') as file_:
        print(" Write mission to file")
        file_.write(output)
        
        
def printfile(aFileName):
    """
    Print a mission file to demonstrate "round trip"
    """
    print("\nMission file: %s" % aFileName)
    with open(aFileName) as f:
        for line in f:
            print(' %s' % line.strip())        


import_mission_filename = 'mpmission.txt'
export_mission_filename = 'exportedmission.txt'


#Upload mission from file
upload_mission(import_mission_filename)

#Download mission we just uploaded and save to a file
save_mission(export_mission_filename)

#Close vehicle object before exiting script
print("Close vehicle object")
vehicle.close()

# Shut down simulator if it was started.
if sitl is not None:
    sitl.stop()


print("\nShow original and uploaded/downloaded files:")
#Print original file (for demo purposes only)
printfile(import_mission_filename)
#Print exported file (for demo purposes only)
printfile(export_mission_filename)